MAVLINK C库的使用并与PX4飞控通信

我们平常调试时使用的较多的为MAVLINK C++库(例如QGC地面站),由于我的项目需要使用Vxworks操作系统来将MAVLINK消息发送出来给到飞控,所以需要将Mavlink_C库移植到VxWorks的工程中。

但是虽然和C++的操作过程有不同,但是common库的文件必须与飞控里面的common库保持一致,即各个MAVLINK_MSG_****.h文件必须与飞控里面的一致。

头文件包含mavlink helpers.h因为调用了里面的一个函数

void mavlink_to_send_buffer(uint8 *buf,const mavlink_msg_t *msg)

 头文件包含mavlink_msg***.h因为我们需要使用里面的结构体和mavlink_msg_***_pack()函数,根据自己需要发送的mavlinkID把需要使用的mavlink_msg_***.h文件包含进去

头文件包含common.h,是因为在给某些mavlinkID结构体赋值时,里面的参数可以直接使用common.h中的

下面以我的工程来举例,发送mavlink的过程

//串口发送函数
void uart_sendto_feik(char *buf, int len)
{
	int i = 0;
	//判断发送FiFo是否已经满
	while(read_register32(UART_BASE_ADDR, TX_FIFO_STATUS) != 0)
	{
		//printf("data:\n");
		//通过串口发送给飞控
		for(i = 0;i<len;i++)
		{
			printf("0x%x ",buf[i]);
			write_register32(UART_BASE_ADDR, TX_DATA_ADDR, buf[i]);
		}	
		break ;
	}
}

 mavlink ID 对应的结构体赋值

    mavCmdCon.latitude1 = frameD.Latitude1;//
    mavCmdCon.longitude1 = frameD.Longitude1;
    mavCmdCon.altitude1 = frameD.Altitude1;
    mavCmdCon.latitude2 = frameD.Latitude2;//
    mavCmdCon.longitude2 = frameD.Longitude2;
    mavCmdCon.altitude2 = frameD.Altitude2;
    mavCmdCon.latitude3 = frameD.Latitude3;//
    mavCmdCon.longitude3 = frameD.Longitude3;
    mavCmdCon.altitude3 = frameD.Altitude3;
    mavCmdCon.altitude = frameD.Height; //
    mavCmdCon.vx1 = frameD.EastwardSpeed1;
    mavCmdCon.vy1 = frameD.NorthboundSpeed1;
    mavCmdCon.vz1 = frameD.CelestialSpeed1;
    mavCmdCon.accx1 = frameD.EastwardAcceleration1;
    mavCmdCon.accy1 = frameD.NorthboundAcceleration1;
    mavCmdCon.accz1 = frameD.CelestialAcceleration1;
    mavCmdCon.heading_angle1 = frameD.HeadingAngle1;
    mavCmdCon.heading_angular_velocity1 = frameD.HeadingAngleSpeed1;
    mavCmdCon.vx2 = frameD.EastwardSpeed2;
    mavCmdCon.vy2 = frameD.NorthboundSpeed2;
    mavCmdCon.vz2 = frameD.CelestialSpeed2;
    mavCmdCon.accx2 = frameD.EastwardAcceleration2;
    mavCmdCon.accy2 = frameD.NorthboundAcceleration2;
    mavCmdCon.accz2 = frameD.CelestialAcceleration2;
    mavCmdCon.heading_angle2 = frameD.HeadingAngle2;
    mavCmdCon.heading_angular_velocity2 = frameD.HeadingAngleSpeed2;
    mavCmdCon.vx3 = frameD.EastwardSpeed3;
    mavCmdCon.vy3 = frameD.NorthboundSpeed3;
    mavCmdCon.vz3 = frameD.CelestialSpeed3;
    mavCmdCon.accx3 = frameD.EastwardAcceleration3;
    mavCmdCon.accy3 = frameD.NorthboundAcceleration3;
    mavCmdCon.accz3 = frameD.CelestialAcceleration3;
    mavCmdCon.heading_angle3 = frameD.HeadingAngle3;
    mavCmdCon.heading_angular_velocity3 = frameD.HeadingAngleSpeed3;
    mavCmdCon.vx = frameD.FAndB_MS;
    mavCmdCon.vy = frameD.LAndR_MS;
    mavCmdCon.vz = frameD.UAndD_MS;
    mavCmdCon.heading_angular_velocity = frameD.LAndR_RS;
    mavCmdCon.status_mode = frameD.mode; //todo
    mavCmdCon.track_validity = frameD.EffectiveTrajectory;
    mavCmdCon.locus1 = frameD.Trajectory1;
    mavCmdCon.locus2 = frameD.Trajectory2;
    mavCmdCon.locus3 = frameD.Trajectory3;
    mavCmdCon.enmergency_command = frameD.EmergencyControl;

 mavlink消息发送过程:

1.打包

mavlink_msg_command_control_pack(0,0,&mavMsg,mavCmdCon.status_mode,
								mavCmdCon.track_validity,mavCmdCon.latitude1,mavCmdCon.longitude1,mavCmdCon.altitude1,
								mavCmdCon.vx1,mavCmdCon.vy1,mavCmdCon.vz1,mavCmdCon.accx1 ,mavCmdCon.accy1,mavCmdCon.accz1,
								mavCmdCon.heading_angle1 ,mavCmdCon.heading_angular_velocity1 ,mavCmdCon.locus1,
								mavCmdCon.latitude2 ,mavCmdCon.longitude2 ,mavCmdCon.altitude2 ,
								mavCmdCon.vx2 ,mavCmdCon.vy2,mavCmdCon.vz2,mavCmdCon.accx2, mavCmdCon.accy2, mavCmdCon.accz2,
								mavCmdCon.heading_angle2,mavCmdCon.heading_angular_velocity2,mavCmdCon.locus2,mavCmdCon.latitude3,mavCmdCon.longitude3,
								mavCmdCon.altitude3 ,mavCmdCon.vx3 ,mavCmdCon.vy3 ,mavCmdCon.vz3 ,mavCmdCon.accx3 ,mavCmdCon.accy3 ,
								mavCmdCon.accz3 ,mavCmdCon.heading_angle3 ,mavCmdCon.heading_angular_velocity3 ,mavCmdCon.locus3 ,mavCmdCon.altitude ,
								mavCmdCon.vx ,mavCmdCon.vy ,mavCmdCon.vz ,mavCmdCon.heading_angular_velocity ,mavCmdCon.enmergency_command);

 这个函数填充顺序要完全按照mavlink_msg_command_control.h里面的函数结构对应

2.把打包完的msg数据转换成数据流

mavlink_msg_to_send_buffer(&frameDBuf, &mavMsg);

3.使用发送函数,发送给飞控

uart_sendto_feik(&frameDBuf, sizeof(frameDBuf));

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值