26 #include <condition_variable>
30 #include <mavros_msgs/WaypointList.h>
31 #include <mavros_msgs/WaypointClear.h>
32 #include <mavros_msgs/WaypointPull.h>
33 #include <mavros_msgs/WaypointPush.h>
37 using mavlink::common::MAV_CMD;
38 using mavlink::common::MAV_FRAME;
39 using MRES = mavlink::common::MAV_MISSION_RESULT;
41 using mavlink::common::MAV_FRAME;
42 using WP_ITEM = mavlink::common::msg::MISSION_ITEM;
44 using WP_TYPE = mavlink::common::MAV_MISSION_TYPE;
65 case enum_value(MAV_FRAME::GLOBAL_RELATIVE_ALT):
67 case enum_value(MAV_FRAME::GLOBAL_RELATIVE_ALT_INT):
68 case enum_value(MAV_FRAME::GLOBAL_TERRAIN_ALT):
69 case enum_value(MAV_FRAME::GLOBAL_TERRAIN_ALT_INT):
91 mavros_msgs::Waypoint ret;
112 ret.frame = mav_msg.frame;
113 ret.command = mav_msg.command;
114 ret.is_current = mav_msg.current;
115 ret.autocontinue = mav_msg.autocontinue;
116 ret.param1 = mav_msg.param1;
117 ret.param2 = mav_msg.param2;
118 ret.param3 = mav_msg.param3;
119 ret.param4 = mav_msg.param4;
120 ret.x_lat = mav_msg.x;
121 ret.y_long = mav_msg.y;
122 ret.z_alt = mav_msg.z;
131 mavros_msgs::Waypoint ret;
140 ret.frame = mav_msg.frame;
141 ret.command = mav_msg.command;
142 ret.is_current = mav_msg.current;
143 ret.autocontinue = mav_msg.autocontinue;
144 ret.param1 = mav_msg.param1;
145 ret.param2 = mav_msg.param2;
146 ret.param3 = mav_msg.param3;
147 ret.param4 = mav_msg.param4;
150 ret.z_alt = mav_msg.z;
157 template <
class ITEM>
165 ret.frame = wp.frame;
166 ret.command = wp.command;
167 ret.current = wp.is_current;
168 ret.autocontinue = wp.autocontinue;
169 ret.param1 = wp.param1;
170 ret.param2 = wp.param2;
171 ret.param3 = wp.param3;
172 ret.param4 = wp.param4;
197 ret.frame = wp.frame;
198 ret.command = wp.command;
199 ret.current = wp.is_current;
200 ret.autocontinue = wp.autocontinue;
201 ret.param1 = wp.param1;
202 ret.param2 = wp.param2;
203 ret.param3 = wp.param3;
204 ret.param4 = wp.param4;
218 template <
class ITEM>
221 std::stringstream ss;
223 ss <<
'#' << wp.seq << (wp.current ?
'*' :
' ') <<
" F:" << +wp.frame <<
" C:" << std::setw(3) << wp.command;
224 ss <<
" p: " << wp.param1 <<
' ' << wp.param2 <<
' ' << wp.param3 <<
' ' << wp.param4 <<
" x: " << wp.x <<
" y: " << wp.y <<
" z: " << wp.z;
358 void handle_mission_request(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_REQUEST &mreq);
375 void handle_mission_count(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_COUNT &mcnt);
383 void handle_mission_ack(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_ACK &mack);
450 template <
class ITEM>
454 auto wpi = mav_from_msg<ITEM>(wp_msg, seq,
wp_type);
468 == std::cv_status::no_timeout
481 == std::cv_status::no_timeout
490 it.is_current = (i == seq) ?
true :
false;
512 mavlink::common::msg::MISSION_REQUEST mrq {};
524 mavlink::common::msg::MISSION_REQUEST_INT mrq {};
536 mavlink::common::msg::MISSION_SET_CURRENT msc {};
547 mavlink::common::msg::MISSION_REQUEST_LIST mrl {};
558 mavlink::common::msg::MISSION_COUNT mcnt {};
569 log_ns.c_str(),start_index, end_index);
571 mavlink::common::msg::MISSION_WRITE_PARTIAL_LIST mwpl {};
572 mwpl.start_index = start_index;
573 mwpl.end_index = end_index;
584 mavlink::common::msg::MISSION_CLEAR_ALL mclr {};
594 mavlink::common::msg::MISSION_ACK mack {};