当前位置:   article > 正文

px4与gazebo的多无人机编队仿真学习_px4无人机编队

px4无人机编队

1、修改launch文件

在/PX4-Autopilot/launch目录下,找到multi_uav_mavros_sitl.launch文件,添加无人机和配置通信端口
可以直接复制文件中已有的配置文件,比如下面照片中是multi_uav_mavros_sitl.launch文件中已有的UAV0无人机的配置代码,我们可以直接复制,然后修改fcu_url, mavlink_udp_port和mavlink_tcp_port(在uav0的基础上加ID号即可)
开启多机

2、多机测试代码

  1. /**
  2. * @file offb_node.cpp
  3. * @brief Offboard control example node, written with MAVROS version 0.19.x, PX4 Pro Flight
  4. * Stack and tested in Gazebo SITL
  5. */
  6. #include <ros/ros.h>
  7. #include <geometry_msgs/PoseStamped.h>
  8. #include <mavros_msgs/CommandBool.h>
  9. #include <mavros_msgs/SetMode.h>
  10. #include <mavros_msgs/State.h>
  11. mavros_msgs::State current_state;
  12. void state_cb(const mavros_msgs::State::ConstPtr& msg){
  13. current_state = *msg;
  14. }
  15. int main(int argc, char **argv)
  16. {
  17. ros::init(argc, argv, "offb_node");
  18. //uav0
  19. ros::NodeHandle nh0;
  20. ros::Subscriber state_sub0 = nh0.subscribe<mavros_msgs::State>
  21. ("uav0/mavros/state", 10, state_cb);
  22. ros::Publisher local_pos_pub0 = nh0.advertise<geometry_msgs::PoseStamped>
  23. ("/uav0/mavros/setpoint_position/local", 10);
  24. ros::ServiceClient arming_client0 = nh0.serviceClient<mavros_msgs::CommandBool>
  25. ("/uav0/mavros/cmd/arming");
  26. ros::ServiceClient set_mode_client0 = nh0.serviceClient<mavros_msgs::SetMode>
  27. ("/uav0/mavros/set_mode");
  28. //uav1
  29. ros::NodeHandle nh1;
  30. ros::Subscriber state_sub1 = nh1.subscribe<mavros_msgs::State>
  31. ("uav1/mavros/state", 10, state_cb);
  32. ros::Publisher local_pos_pub1 = nh1.advertise<geometry_msgs::PoseStamped>
  33. ("/uav1/mavros/setpoint_position/local", 10);
  34. ros::ServiceClient arming_client1 = nh1.serviceClient<mavros_msgs::CommandBool>
  35. ("/uav1/mavros/cmd/arming");
  36. ros::ServiceClient set_mode_client1 = nh1.serviceClient<mavros_msgs::SetMode>
  37. ("/uav1/mavros/set_mode");
  38. //uav2
  39. ros::NodeHandle nh2;
  40. ros::Subscriber state_sub2 = nh2.subscribe<mavros_msgs::State>
  41. ("uav2/mavros/state", 10, state_cb);
  42. ros::Publisher local_pos_pub2 = nh2.advertise<geometry_msgs::PoseStamped>
  43. ("/uav2/mavros/setpoint_position/local", 10);
  44. ros::ServiceClient arming_client2 = nh2.serviceClient<mavros_msgs::CommandBool>
  45. ("/uav2/mavros/cmd/arming");
  46. ros::ServiceClient set_mode_client2 = nh2.serviceClient<mavros_msgs::SetMode>
  47. ("/uav2/mavros/set_mode");
  48. //uav3
  49. ros::NodeHandle nh3;
  50. ros::Subscriber state_sub3 = nh3.subscribe<mavros_msgs::State>
  51. ("uav3/mavros/state", 10, state_cb);
  52. ros::Publisher local_pos_pub3 = nh3.advertise<geometry_msgs::PoseStamped>
  53. ("/uav3/mavros/setpoint_position/local", 10);
  54. ros::ServiceClient arming_client3 = nh3.serviceClient<mavros_msgs::CommandBool>
  55. ("/uav3/mavros/cmd/arming");
  56. ros::ServiceClient set_mode_client3 = nh3.serviceClient<mavros_msgs::SetMode>
  57. ("/uav3/mavros/set_mode");
  58. //the setpoint publishing rate MUST be faster than 2Hz
  59. ros::Rate rate(20.0);
  60. // wait for FCU connection
  61. while(ros::ok() && !current_state.connected){
  62. ros::spinOnce();
  63. rate.sleep();
  64. }
  65. // x_num, y_num refer to the desired uav input position
  66. //all the uavs have the same height : z
  67. float x0 = 0.0, y0 = 0.0;
  68. float x1 = 0.0, y1 = 0.0;
  69. float x2 = 0.0, y2 = 0.0;
  70. float x3 = 0.0, y3 = 0.0;
  71. float z = 2.0;
  72. float w = 0.0;
  73. const float pi = 3.1415926;
  74. geometry_msgs::PoseStamped pose0;
  75. geometry_msgs::PoseStamped pose1;
  76. geometry_msgs::PoseStamped pose2;
  77. geometry_msgs::PoseStamped pose3;
  78. pose0.pose.position.x = x0;
  79. pose0.pose.position.y = y0;
  80. pose0.pose.position.z = z;
  81. pose1.pose.position.x = x1;
  82. pose1.pose.position.y = y1;
  83. pose1.pose.position.z = z;
  84. pose2.pose.position.x = x2;
  85. pose2.pose.position.y = y2;
  86. pose2.pose.position.z = z;
  87. pose3.pose.position.x = x3;
  88. pose3.pose.position.y = y3;
  89. pose3.pose.position.z = z;
  90. //uavs have the initial position offset because of the .launch config file
  91. float x0_offset = -3;
  92. float x1_offset = -1;
  93. float x2_offset = 1;
  94. float x3_offset = 3;
  95. //define uavs' coordinates in the formation coordinate system
  96. float x0_f = -0.5, y0_f = 0.5;
  97. float x1_f = 0.5, y1_f = 0.5;
  98. float x2_f = -0.5, y2_f = -0.5;
  99. float x3_f = 0.5, y3_f = -0.5;
  100. float xx, yy;
  101. //send a few setpoints before starting
  102. for(int i = 100; ros::ok() && i > 0; --i){
  103. local_pos_pub0.publish(pose0);
  104. local_pos_pub1.publish(pose1);
  105. local_pos_pub2.publish(pose2);
  106. local_pos_pub3.publish(pose3);
  107. ros::spinOnce();
  108. rate.sleep();
  109. }
  110. mavros_msgs::SetMode offb_set_mode;
  111. offb_set_mode.request.custom_mode = "OFFBOARD";
  112. mavros_msgs::CommandBool arm_cmd;
  113. arm_cmd.request.value = true;
  114. ros::Time last_request = ros::Time::now();
  115. while(ros::ok()){
  116. if( current_state.mode != "OFFBOARD" &&
  117. (ros::Time::now() - last_request > ros::Duration(5.0))){
  118. if( set_mode_client0.call(offb_set_mode) &&
  119. set_mode_client1.call(offb_set_mode) &&
  120. set_mode_client2.call(offb_set_mode) &&
  121. set_mode_client3.call(offb_set_mode) &&
  122. offb_set_mode.response.mode_sent){
  123. ROS_INFO("Offboard enabled : 4");
  124. }
  125. last_request = ros::Time::now();
  126. } else {
  127. if( !current_state.armed &&
  128. (ros::Time::now() - last_request > ros::Duration(5.0))){
  129. if( arming_client0.call(arm_cmd) &&
  130. arming_client1.call(arm_cmd) &&
  131. arming_client2.call(arm_cmd) &&
  132. arming_client3.call(arm_cmd) &&
  133. arm_cmd.response.success){
  134. ROS_INFO("Vehicle armed : 4");
  135. }
  136. last_request = ros::Time::now();
  137. }
  138. }
  139. local_pos_pub0.publish(pose0);
  140. local_pos_pub1.publish(pose1);
  141. local_pos_pub2.publish(pose2);
  142. local_pos_pub3.publish(pose3);
  143. w = w + 2*pi/(30/(1/20.0));
  144. if(w > 2*pi){
  145. w = w - 2*pi;
  146. }
  147. xx = 4.75*cos(w);
  148. yy = 4.75*sin(w);
  149. x0 = x0_f*cos(w) - y0_f*sin(w) + xx - x0_offset;
  150. y0 = y0_f*cos(w) + x0_f*sin(w) + yy;
  151. pose0.pose.position.x = x0;
  152. pose0.pose.position.y = y0;
  153. x1 = x1_f*cos(w) - y1_f*sin(w) + xx - x1_offset;
  154. y1 = y1_f*cos(w) + x1_f*sin(w) + yy;
  155. pose1.pose.position.x = x1;
  156. pose1.pose.position.y = y1;
  157. x2 = x2_f*cos(w) - y2_f*sin(w) + xx - x2_offset;
  158. y2 = y2_f*cos(w) + x2_f*sin(w) + yy;
  159. pose2.pose.position.x = x2;
  160. pose2.pose.position.y = y2;
  161. x3 = x3_f*cos(w) - y3_f*sin(w) + xx - x3_offset;
  162. y3 = y3_f*cos(w) + x3_f*sin(w) + yy;
  163. pose3.pose.position.x = x3;
  164. pose3.pose.position.y = y3;
  165. ros::spinOnce();
  166. rate.sleep();
  167. }
  168. return 0;
  169. }

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

闽ICP备14008679号