当前位置:   article > 正文

PX4 全驱无人机 MAVROS 发布 actuator_control 消息_px4 actuators

px4 actuators

如果想要通过发布力和力矩控制全驱无人机,那么就需要发布三个方向的力矩和三个方向的力,总共六个控制量,而对于默认原版的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包

步骤同上,在mavlink/include/mavlink/v2.0/message_definition/文件夹下找到common.xml文件,分别将“SET_ACTUATOR_CONTROL_TARGET”和“ACTUATOR_CONTROL_TARGET”这两块对应的控制通道数改为11

保存后,首先需要使用Mavlink Generator工具进行编译,可以在源码安装的mavlink包中找到mavgenerate.py文件,在命令行中输入

python3 mavgenerate.py

即可运行Mavlink Generator工具

XML一栏选择~/Firmware/mavlink/include/mavlink/v2.0/message_definitions/standard.xml
输出一栏选择~/Firmware/mavlink/include/mavlink/v2.0
语言一栏选择 C
选择 2.0
勾选 Validate
点击 Generate 按钮

若修改成功,可以在mavlink/include/mavlink/v2.0/common文件夹下找到mavlink_msg_actuator_control_target.h文件,检查通道数与一些其他参数是否发生改变;若发生改变,则说明修改成功,注意此时与步骤三中最后生成的文件完成一致,若有部分参数不一致,说明修改失败

五、修改PX4/Firmware中的mavlink_receiver模块

在src/modules/mavlink文件夹下找到mavlink_receiver.cpp,对handle_message_set_actuator_control_target函数进行修改

六、修改参数ENABLE_LOCKSTEP_SCHEDULER

在boards/px4/sitl文件夹下找到default.cmake文件,修改参数ENABLE_LOCKSTEP_SCHEDULER为no

在对应模型的sdf文件中修改mavlink插件下的参数enable_lockstep为0

 结束后再对整个固件进行编译

make px4_sitl gazebo

七、测试

启动mavros仿真

roslaunch mavros_posix_sitl.launch

运行自定义mavros程序,发布actuator_control数据,示例代码如下:

  1. #! /usr/bin/env python
  2. import rospy
  3. import math
  4. from geometry_msgs.msg import PoseStamped
  5. from mavros_msgs.msg import State, ActuatorControl
  6. from mavros_msgs.srv import CommandBool, CommandBoolRequest, SetMode, SetModeRequest
  7. current_state = State()
  8. def state_cb(msg):
  9. global current_state
  10. current_state = msg
  11. local_pos = PoseStamped()
  12. def local_pos_cb(local_pos_msg):
  13. global local_pos
  14. local_pos = local_pos_msg
  15. if __name__ == "__main__":
  16. rospy.init_node("offb_force_py")
  17. state_sub = rospy.Subscriber("mavros/state", State, callback = state_cb)
  18. local_pos_sb = rospy.Subscriber("mavros/local_position/pose", PoseStamped, callback = local_pos_cb)
  19. local_pos_pub = rospy.Publisher("mavros/setpoint_position/local", PoseStamped, queue_size=10)
  20. ActuatorControl_pub = rospy.Publisher("mavros/actuator_control", ActuatorControl, queue_size=10)
  21. rospy.wait_for_service("/mavros/cmd/arming")
  22. arming_client = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
  23. rospy.wait_for_service("/mavros/set_mode")
  24. set_mode_client = rospy.ServiceProxy("mavros/set_mode", SetMode)
  25. # Setpoint publishing MUST be faster than 2Hz
  26. rate = rospy.Rate(250)
  27. # Wait for Flight Controller connection
  28. while(not rospy.is_shutdown() and not current_state.connected):
  29. rate.sleep()
  30. pose = PoseStamped()
  31. pose.pose.position.x = 0
  32. pose.pose.position.y = 0
  33. pose.pose.position.z = 2
  34. actuator_control = ActuatorControl()
  35. actuator_control.group_mix = 0
  36. actuator_control.controls[0] = 0.000 # ROLL
  37. actuator_control.controls[1] = 0.000 # PITCH
  38. actuator_control.controls[2] = 0.000 # YAW
  39. actuator_control.controls[3] = 0.824 # THROTTLE
  40. actuator_control.controls[4] = 0.0 # FLAPS
  41. actuator_control.controls[5] = 0.0 # SPOILERS
  42. actuator_control.controls[6] = 0.0 # AIRBRAKES
  43. actuator_control.controls[7] = -1.0 # LANDING_GEAR
  44. actuator_control.controls[8] = 0.000 # X_THRUST
  45. actuator_control.controls[9] = -0.00 # Y_THRUST
  46. actuator_control.controls[10] = -0.824 # Z_THRUST
  47. # actuator_control.header.seq = 1
  48. # actuator_control.header.stamp = rospy.Time.now()
  49. # actuator_control.header.frame_id = "test"
  50. # Send a few setpoints before starting
  51. for i in range(100):
  52. if(rospy.is_shutdown()):
  53. break
  54. local_pos_pub.publish(pose)
  55. ActuatorControl_pub.publish(actuator_control)
  56. rate.sleep()
  57. offb_set_mode = SetModeRequest()
  58. offb_set_mode.custom_mode = 'OFFBOARD'
  59. arm_cmd = CommandBoolRequest()
  60. arm_cmd.value = True
  61. last_req = rospy.Time.now()
  62. count = 0
  63. take_off = False
  64. reach_height = False
  65. while(not rospy.is_shutdown()):
  66. if(current_state.mode != "OFFBOARD" and (rospy.Time.now() - last_req) > rospy.Duration(2.0)):
  67. if(set_mode_client.call(offb_set_mode).mode_sent == True):
  68. rospy.loginfo("OFFBOARD enabled")
  69. last_req = rospy.Time.now()
  70. else:
  71. if(not current_state.armed and (rospy.Time.now() - last_req) > rospy.Duration(2.0)):
  72. if(arming_client.call(arm_cmd).success == True):
  73. rospy.loginfo("Vehicle armed")
  74. take_off = True
  75. last_req = rospy.Time.now()
  76. if(count == 0 and not reach_height):
  77. local_pos_pub.publish(pose)
  78. if(math.fabs(local_pos.pose.position.z - 2) <= 0.3):
  79. reach_height = True
  80. rospy.loginfo("Reach Height!")
  81. count = 1
  82. elif(take_off and count == 1):
  83. actuator_control.header.stamp = rospy.Time.now()
  84. ActuatorControl_pub.publish(actuator_control)
  85. rate.sleep()

在mavros仿真窗口中输入

listener actuator_controls_0

可以看到如下结果,说明修改成功

声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/weixin_40725706/article/detail/871905
推荐阅读
相关标签
  

闽ICP备14008679号