当前位置:   article > 正文

通过mavros实现无人机航点飞行(mission模式)示例代码

通过mavros实现无人机航点飞行(mission模式)示例代码

通过mavros实现无人机航点飞行(mission模式)示例代码

通过 mavros/mission/push 这个服务进行航点上传 

Mavros-AUTO.MISSION-mode: This script will activate AUTO.MISSION mode along with pushing waypoints to be followed by the drone while PX4 gazebo simulation wrapped with mavros running for VTOL quad-plane. - Gitee.com

wayPointMission.py

  1. #!/usr/bin/env python
  2. # ROS python API
  3. import rospy
  4. # 3D point & Stamped Pose msgs
  5. from geometry_msgs.msg import Point, PoseStamped
  6. # import all mavros messages and services
  7. from mavros_msgs.msg import *
  8. from mavros_msgs.srv import *
  9. class Modes:
  10. def __init__(self):
  11. pass
  12. def setArm(self):
  13. rospy.wait_for_service('mavros/cmd/arming')
  14. try:
  15. armService = rospy.ServiceProxy('mavros/cmd/arming', mavros_msgs.srv.CommandBool)
  16. armService(True)
  17. except rospy.ServiceException, e:
  18. print "Service arming call failed: %s"%e
  19. def auto_set_mode(self):
  20. rospy.wait_for_service('mavros/set_mode')
  21. try:
  22. # setModeService = rospy.ServiceProxy('mavros/set_mode', mavros_msgs.srv.set_mode.request.custom_mode)
  23. setModeService = rospy.ServiceProxy('mavros/set_mode', mavros_msgs.srv.SetMode)
  24. setModeService(custom_mode="AUTO.MISSION")
  25. except rospy.ServiceException, e:
  26. print "Service takeoff call failed: %s"%e
  27. def wpPush(self,index,wps):
  28. rospy.wait_for_service('mavros/mission/push')
  29. try:
  30. wpPushService = rospy.ServiceProxy('mavros/mission/push', WaypointPush,persistent=True)
  31. wpPushService(start_index=0,waypoints=wps)#start_index = the index at which we want the mission to start
  32. print "Waypoint Pushed"
  33. except rospy.ServiceException, e:
  34. print "Service takeoff call failed: %s"%e
  35. def wpPull(self,wps):
  36. rospy.wait_for_service('mavros/mission/pull')
  37. try:
  38. wpPullService = rospy.ServiceProxy('mavros/mission/pull', WaypointPull,persistent=True)
  39. print wpPullService().wp_received
  40. print "Waypoint Pulled"
  41. except rospy.ServiceException, e:
  42. print "Service Puling call failed: %s"%e
  43. class stateMoniter:
  44. def __init__(self):
  45. self.state = State()
  46. # Instantiate a setpoints message
  47. self.sp = PositionTarget()
  48. # set the flag to use position setpoints and yaw angle
  49. self.sp.type_mask = int('010111111000', 2)
  50. def stateCb(self, msg):
  51. self.state = msg
  52. class wpMissionCnt:
  53. def __init__(self):
  54. self.wp =Waypoint()
  55. def setWaypoints(self,frame,command,is_current,autocontinue,param1,param2,param3,param4,x_lat,y_long,z_alt):
  56. self.wp.frame =frame # FRAME_GLOBAL_REL_ALT = 3 for more visit http://docs.ros.org/api/mavros_msgs/html/msg/Waypoint.html
  57. self.wp.command = command '''VTOL TAKEOFF = 84,NAV_WAYPOINT = 16, TAKE_OFF=22 for checking out other parameters go to https://github.com/mavlink/mavros/blob/master/mavros_msgs/msg/CommandCode.msg'''
  58. self.wp.is_current= is_current
  59. self.wp.autocontinue = autocontinue # enable taking and following upcoming waypoints automatically
  60. self.wp.param1=param1 # no idea what these are for but the script will work so go ahead
  61. self.wp.param2=param2
  62. self.wp.param3=param3
  63. self.wp.param4=param4
  64. self.wp.x_lat= x_lat
  65. self.wp.y_long=y_long
  66. self.wp.z_alt= z_alt #relative altitude.
  67. return self.wp
  68. def main():
  69. rospy.init_node('waypointMission', anonymous=True)
  70. rate = rospy.Rate(20.0)
  71. stateMt = stateMoniter()
  72. md = Modes()
  73. wayp0 = wpMissionCnt()
  74. wayp1 = wpMissionCnt()
  75. wayp2 = wpMissionCnt()
  76. wayp3 = wpMissionCnt()
  77. wps = [] #List to story waypoints
  78. w = wayp0.setWaypoints(3,84,True,True,0.0,0.0,0.0,float('nan'),47.397713,8.547605,50)
  79. wps.append(w)
  80. w = wayp1.setWaypoints(3,16,False,True,0.0,0.0,0.0,float('nan'),47.398621,8.547745,50)
  81. wps.append(w)
  82. w = wayp2.setWaypoints(3,16,False,True,0.0,0.0,0.0,float('nan'),47.399151,8.545320,50)
  83. wps.append(w)
  84. print wps
  85. md.wpPush(0,wps)
  86. md.wpPull(0)
  87. rospy.Subscriber("/mavros/state",State, stateMt.stateCb)
  88. # Arming the drone
  89. while not stateMt.state.armed:
  90. md.setArm()
  91. rate.sleep()
  92. # Switching the state to auto mode
  93. while not stateMt.state.mode=="AUTO.MISSION":
  94. md.auto_set_mode()
  95. rate.sleep()
  96. print "AUTO.MISSION"
  97. # rospy.spin()
  98. if __name__ == '__main__':
  99. try:
  100. main()
  101. except rospy.ROSInterruptException:
  102. pass

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

闽ICP备14008679号