如果想要通过发布力和力矩控制全驱无人机,那么就需要发布三个方向的力矩和三个方向的力,总共六个控制量,而对于默认原版的actuator_control消息,其中只有四个控制量,因此需要进行修改。具体修改流程如下:
一、修改UORB消息
在msg文件夹下对actuator_controls.msg文件进行修改,增添三方向力参数,分别命名为INDEX_X_THRUST、INDEX_Y_THRUST、INDEX_Z_THRUST,控制通道数由8改为11
修改完成后编译,会生成对应.h头文件
make px4_sitl gazebo
二、修改MAVROS包
因为我们需要对MAVROS和MAVLINK包进行二次开发,因此这里不建议使用二进制安装,更推荐使用源码安装,安装步骤可参考我之前的博客:源码方式安装MAVROS包;如果是已经进行过二进制安装的,也建议将之前的包删除,避免不必要的麻烦。
在mavros_msg/msg文件夹下找到ActuatorControl.msg文件,将控制通道数由8改为11
这里我们先不编译,等到修改MavLink包后一同编译
三、修改MAVLINK包
在mavlink/message_definition/v1.0/文件夹下找到common.xml文件,分别将“SET_ACTUATOR_CONTROL_TARGET”和“ACTUATOR_CONTROL_TARGET”这两块对应的控制通道数改为11
保存后进行编译
catkin build
若修改成功,可以在build文件夹下找到mavlink_msg_actuator_control_target.h文件,检查通道数与一些其他参数是否发生改变;若发生改变,则说明修改成功
四、修改PX4/Firmware中的mavlink包
步骤同上,在ma