mission_protocol_base.cpp
Go to the documentation of this file.
1 
8 /*
9  * Copyright 2014,2015,2016,2017,2018 Vladimir Ermakov.
10  * Copyright 2021 Charlie Burge.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
18 
19 
20 namespace mavros {
21 namespace plugin {
22 void MissionBase::handle_mission_item_int(const mavlink::mavlink_message_t *msg, WP_ITEM_INT &wpi)
23 {
24  unique_lock lock(mutex);
25 
26  /* Only interested in the specific msg type */
27  if (wpi.mission_type != enum_value(wp_type)) {
28  return;
29  }
30  /* receive item only in RX state */
31  else if (wp_state == WP::RXWPINT) {
32  if (wpi.seq != wp_cur_id) {
33  ROS_WARN_NAMED(log_ns, "%s: Seq mismatch, dropping item (%d != %zu)",
34  log_ns.c_str(), wpi.seq, wp_cur_id);
35  return;
36  }
37 
38  ROS_INFO_STREAM_NAMED(log_ns, log_ns << ": item " << waypoint_to_string<WP_ITEM_INT>(wpi));
39 
40  waypoints.push_back(mav_to_msg<WP_ITEM_INT>(wpi));
41  if (++wp_cur_id < wp_count) {
44  }
45  else {
48  lock.unlock();
50  }
51  }
52  else {
53  ROS_DEBUG_NAMED(log_ns, "%s: rejecting item, wrong state %d", log_ns.c_str(), enum_value(wp_state));
55  ROS_DEBUG_NAMED(log_ns, "%s: reschedule pull", log_ns.c_str());
57  }
58  }
59 }
60 
61 
62 void MissionBase::handle_mission_item(const mavlink::mavlink_message_t *msg, WP_ITEM &wpi)
63 {
64  unique_lock lock(mutex);
65 
66  /* Only interested in the specific msg type */
67  if (wpi.mission_type != enum_value(wp_type)) {
68  return;
69  }
70  /* receive item only in RX state */
71  else if (wp_state == WP::RXWP) {
72  if (wpi.seq != wp_cur_id) {
73  ROS_WARN_NAMED(log_ns, "%s: Seq mismatch, dropping item (%d != %zu)",
74  log_ns.c_str(), wpi.seq, wp_cur_id);
75  return;
76  }
77 
78  ROS_INFO_STREAM_NAMED(log_ns, log_ns << ": item " << waypoint_to_string<WP_ITEM>(wpi));
79 
80  waypoints.push_back(mav_to_msg<WP_ITEM>(wpi));
81  if (++wp_cur_id < wp_count) {
84  }
85  else {
87  lock.unlock();
89  }
90  }
91  else {
92  ROS_DEBUG_NAMED(log_ns, "%s: rejecting item, wrong state %d", log_ns.c_str(), enum_value(wp_state));
94  ROS_DEBUG_NAMED(log_ns, "%s: reschedule pull", log_ns.c_str());
96  }
97  }
98 }
99 
100 
101 bool MissionBase::sequence_mismatch(const uint16_t &seq)
102 {
103  if (seq != wp_cur_id && seq != wp_cur_id + 1) {
104  ROS_WARN_NAMED(log_ns, "%s: Seq mismatch, dropping request (%d != %zu)",
105  log_ns.c_str(), seq, wp_cur_id);
106  return true;
107  } else {
108  return false;
109  }
110 }
111 
112 
113 void MissionBase::handle_mission_request(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_REQUEST &mreq)
114 {
115  lock_guard lock(mutex);
116 
117  /* Only interested in the specific msg type */
118  if (mreq.mission_type != enum_value(wp_type)) {
119  return;
120  }
121  else if ((wp_state == WP::TXLIST && mreq.seq == 0) || (wp_state == WP::TXPARTIAL && mreq.seq == wp_start_id) || (wp_state == WP::TXWP) || (wp_state == WP::TXWPINT)) {
122  if (sequence_mismatch(mreq.seq)) {
123  return;
124  }
125 
127  if (mreq.seq < wp_end_id) {
128  ROS_DEBUG_NAMED(log_ns, "%s: FCU requested MISSION_ITEM waypoint %d", log_ns.c_str(), mreq.seq);
129  wp_cur_id = mreq.seq;
130  if (use_mission_item_int) {
131  ROS_DEBUG_NAMED(log_ns, "%s: Trying to send a MISSION_ITEM_INT instead", log_ns.c_str());
133  send_waypoint<WP_ITEM_INT>(wp_cur_id);
134  } else {
135  wp_state = WP::TXWP;
136  send_waypoint<WP_ITEM>(wp_cur_id);
137  }
138  }
139  else
140  ROS_ERROR_NAMED(log_ns, "%s: FCU require seq out of range", log_ns.c_str());
141  }
142  else
143  ROS_DEBUG_NAMED(log_ns, "%s: rejecting request, wrong state %d", log_ns.c_str(), enum_value(wp_state));
144 }
145 
146 
147 void MissionBase::handle_mission_request_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_REQUEST_INT &mreq)
148 {
149  lock_guard lock(mutex);
150 
151  /* Only interested in the specific msg type */
152  if (mreq.mission_type != enum_value(wp_type)) {
153  return;
154  }
155  else if ((wp_state == WP::TXLIST && mreq.seq == 0) || (wp_state == WP::TXPARTIAL && mreq.seq == wp_start_id) || (wp_state == WP::TXWPINT)) {
156  if (sequence_mismatch(mreq.seq)) {
157  return;
158  }
159 
160 
161  if (!use_mission_item_int) {
162  use_mission_item_int = true;
163  }
166  }
167 
169  if (mreq.seq < wp_end_id) {
170  ROS_DEBUG_NAMED(log_ns, "%s: FCU reqested MISSION_ITEM_INT waypoint %d", log_ns.c_str(), mreq.seq);
172  wp_cur_id = mreq.seq;
173  send_waypoint<WP_ITEM_INT>(wp_cur_id);
174  }
175  else
176  ROS_ERROR_NAMED(log_ns, "%s: FCU require seq out of range", log_ns.c_str());
177  }
178  else
179  ROS_DEBUG_NAMED(log_ns, "%s: rejecting request, wrong state %d", log_ns.c_str(), enum_value(wp_state));
180 }
181 
182 
183 void MissionBase::handle_mission_count(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_COUNT &mcnt)
184 {
185  unique_lock lock(mutex);
186 
187  /* Only interested in the specific msg type */
188  if (mcnt.mission_type != enum_value(wp_type)) {
189  return;
190  }
191  else if (wp_state == WP::RXLIST) {
192  /* FCU report of MISSION_REQUEST_LIST */
193  ROS_DEBUG_NAMED(log_ns, "%s: count %d", log_ns.c_str(), mcnt.count);
194 
195  wp_count = mcnt.count;
196  wp_cur_id = 0;
197 
198  waypoints.clear();
199  waypoints.reserve(wp_count);
200 
201  if (wp_count > 0) {
202  if (use_mission_item_int) {
206  } else {
207  wp_state = WP::RXWP;
210  }
211  }
212  else {
214  lock.unlock();
216  }
217  }
218  else {
219  ROS_INFO_NAMED(log_ns, "%s: seems GCS requesting mission", log_ns.c_str());
220  /* schedule pull after GCS done */
221  if (do_pull_after_gcs) {
222  ROS_INFO_NAMED(log_ns, "%s: scheduling pull after GCS is done", log_ns.c_str());
223  reschedule_pull = true;
225  }
226  }
227 }
228 
229 
230 void MissionBase::handle_mission_ack(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_ACK &mack)
231 {
232  unique_lock lock(mutex);
233 
234  auto ack_type = static_cast<MRES>(mack.type);
235 
236  /* Only interested in the specific msg type */
237  if (mack.mission_type != enum_value(wp_type)) {
238  return;
239  }
241  && (wp_cur_id == wp_end_id - 1)
242  && (ack_type == MRES::ACCEPTED)) {
243  go_idle();
245  send_waypoints.clear();
247  lock.unlock();
248  list_sending.notify_all();
250  ROS_INFO_NAMED(log_ns, "%s: mission sended", log_ns.c_str());
251  }
252  else if ((wp_state == WP::TXWP || wp_state == WP::TXWPINT) && ack_type == MRES::INVALID_SEQUENCE) {
253  // Mission Ack: INVALID_SEQUENCE received during TXWP
254  // This happens when waypoint N was received by autopilot, but the request for waypoint N+1 failed.
255  // This causes seq mismatch, ignore and eventually the request for n+1 will get to us and seq will sync up.
256  ROS_DEBUG_NAMED(log_ns, "%s: Received INVALID_SEQUENCE ack", log_ns.c_str());
257  }
259  go_idle();
260  /* use this flag for failure report */
261  is_timedout = true;
262  lock.unlock();
263  list_sending.notify_all();
264 
265  ROS_ERROR_STREAM_NAMED(log_ns, log_ns << ": upload failed: " << utils::to_string(ack_type));
266  }
267  else if (wp_state == WP::CLEAR) {
268  go_idle();
269  if (ack_type != MRES::ACCEPTED) {
270  is_timedout = true;
271  lock.unlock();
272  ROS_ERROR_STREAM_NAMED(log_ns, log_ns << ": clear failed: " << utils::to_string(ack_type));
273  }
274  else {
275  waypoints.clear();
276  lock.unlock();
278  ROS_INFO_NAMED(log_ns, "%s: mission cleared", log_ns.c_str());
279  }
280 
281  list_sending.notify_all();
282  }
283  else
284  ROS_DEBUG_NAMED(log_ns, "%s: not planned ACK, type: %d", log_ns.c_str(), mack.type);
285 }
286 
287 
289 {
290  unique_lock lock(mutex);
291  if (wp_retries > 0) {
292  wp_retries--;
293  ROS_WARN_NAMED(log_ns, "%s: timeout, retries left %zu", log_ns.c_str(), wp_retries);
294 
295  switch (wp_state) {
296  case WP::RXLIST:
298  break;
299  case WP::RXWP:
301  break;
302  case WP::RXWPINT:
304  break;
305  case WP::TXLIST:
307  break;
308  case WP::TXPARTIAL:
310  break;
311  case WP::TXWP:
312  send_waypoint<WP_ITEM>(wp_cur_id);
313  break;
314  case WP::TXWPINT:
315  send_waypoint<WP_ITEM_INT>(wp_cur_id);
316  break;
317  case WP::CLEAR:
319  break;
320  case WP::SET_CUR:
322  break;
323 
324  case WP::IDLE:
325  break;
326  }
327 
329  }
330  else {
332  ROS_ERROR_NAMED(log_ns, "%s: mission_item_int timed out, falling back to mission_item.", log_ns.c_str());
333  use_mission_item_int = false;
334 
335  wp_state = WP::TXWP;
337  send_waypoint<WP_ITEM>(wp_cur_id);
339  ROS_ERROR_NAMED(log_ns, "%s: mission_item_int timed out, falling back to mission_item.", log_ns.c_str());
340  use_mission_item_int = false;
341 
342  wp_state = WP::RXWP;
345  } else {
346  ROS_ERROR_NAMED(log_ns, "%s: timed out.", log_ns.c_str());
347  go_idle();
348  is_timedout = true;
349  /* prevent waiting cond var timeout */
350  lock.unlock();
351  list_receiving.notify_all();
352  list_sending.notify_all();
353  }
354  }
355 }
356 } // namespace plugin
357 } // namespace mavros
mavros::plugin::MissionBase::handle_mission_count
void handle_mission_count(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_COUNT &mcnt)
handle MISSION_COUNT mavlink msg Handles a mission count from FCU in a Waypoint Pull Triggers a pull ...
Definition: mission_protocol_base.cpp:183
mavros::plugin::MissionBase::handle_mission_request
void handle_mission_request(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_REQUEST &mreq)
handle MISSION_REQUEST mavlink msg handles and acts on misison request from FCU
Definition: mission_protocol_base.cpp:113
mavros::plugin::MissionBase::wp_cur_id
size_t wp_cur_id
Definition: mission_protocol_base.h:292
mavros::plugin::WP_ITEM_INT
mavlink::common::msg::MISSION_ITEM_INT WP_ITEM_INT
Definition: mission_protocol_base.h:43
mavros::plugin::MissionBase::handle_mission_item_int
void handle_mission_item_int(const mavlink::mavlink_message_t *msg, WP_ITEM_INT &wpi)
handle MISSION_ITEM_INT mavlink msg handles and stores mission items when pulling waypoints
Definition: mission_protocol_base.cpp:22
mavros::plugin::MissionBase::list_sending
std::condition_variable list_sending
Definition: mission_protocol_base.h:300
mavros::plugin::MissionBase::use_mission_item_int
bool use_mission_item_int
Definition: mission_protocol_base.h:309
mavros::plugin::MissionBase::mission_write_partial_list
void mission_write_partial_list(uint16_t start_index, uint16_t end_index)
Definition: mission_protocol_base.h:566
mavros::plugin::MissionBase::log_ns
std::string log_ns
Definition: mission_protocol_base.h:267
mavros::plugin::MissionBase::mission_request_list
void mission_request_list()
Definition: mission_protocol_base.h:543
mission_protocol_base.h
Mission base plugin.
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
mavros::plugin::MissionBase::mission_request
void mission_request(uint16_t seq)
Definition: mission_protocol_base.h:508
mavros::plugin::MissionBase::mutex
std::recursive_mutex mutex
Definition: mission_protocol_base.h:269
mavros::plugin::MRES
mavlink::common::MAV_MISSION_RESULT MRES
Definition: mission_protocol_base.h:39
mavros::plugin::MissionBase::wp_state
WP wp_state
Definition: mission_protocol_base.h:286
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
mavros::plugin::MissionBase::wp_count
size_t wp_count
Definition: mission_protocol_base.h:289
mavros::plugin::MissionBase::sequence_mismatch
bool sequence_mismatch(const uint16_t &seq)
checks for a sequence mismatch between a MISSION_REQUEST(_INT) sequence and the current waypoint that...
Definition: mission_protocol_base.cpp:101
mavros::plugin::MissionBase::mission_count
void mission_count(uint16_t cnt)
Definition: mission_protocol_base.h:554
mavros::utils::to_string
std::string to_string(timesync_mode e)
Definition: enum_to_string.cpp:331
mavros::plugin::MissionBase::unique_lock
std::unique_lock< std::recursive_mutex > unique_lock
Definition: mission_protocol_base.h:264
mavros::plugin::MissionBase::WP::RXWPINT
@ RXWPINT
mavros::plugin::MissionBase::list_receiving
std::condition_variable list_receiving
Definition: mission_protocol_base.h:299
mavros::plugin::MissionBase::reschedule_pull
bool reschedule_pull
Definition: mission_protocol_base.h:307
mavros::plugin::MissionBase::schedule_pull
void schedule_pull(const ros::Duration &dt)
Definition: mission_protocol_base.h:442
mavros::plugin::MissionBase::go_idle
void go_idle(void)
Definition: mission_protocol_base.h:422
mavros::plugin::MissionBase::WP::RXLIST
@ RXLIST
mavros::plugin::MissionBase::wp_end_id
size_t wp_end_id
Definition: mission_protocol_base.h:291
mavros::plugin::MissionBase::WP_TIMEOUT_DT
const ros::Duration WP_TIMEOUT_DT
Definition: mission_protocol_base.h:321
ros::TimerEvent
mavros::plugin::MissionBase::WP::SET_CUR
@ SET_CUR
mavros::plugin::MissionBase::is_timedout
bool is_timedout
Definition: mission_protocol_base.h:296
mavros::plugin::MissionBase::restart_timeout_timer_int
void restart_timeout_timer_int(void)
Definition: mission_protocol_base.h:435
mavros::plugin::MissionBase::wp_set_active
size_t wp_set_active
Definition: mission_protocol_base.h:294
mavros::plugin::MissionBase::restart_timeout_timer
void restart_timeout_timer(void)
Definition: mission_protocol_base.h:429
mavros::plugin::MissionBase::wp_start_id
size_t wp_start_id
Definition: mission_protocol_base.h:290
mavros::plugin::MissionBase::RESCHEDULE_DT
const ros::Duration RESCHEDULE_DT
Definition: mission_protocol_base.h:322
mavros
Definition: frame_tf.h:34
mavros::plugin::WP_ITEM
mavlink::common::msg::MISSION_ITEM WP_ITEM
Definition: mission_protocol_base.h:42
mavros::plugin::MissionBase::timeout_cb
void timeout_cb(const ros::TimerEvent &event)
Act on a timeout Resend the message that may have been lost.
Definition: mission_protocol_base.cpp:288
mavros::plugin::MissionBase::wp_retries
size_t wp_retries
Definition: mission_protocol_base.h:295
mavros::plugin::MissionBase::send_waypoints
std::vector< mavros_msgs::Waypoint > send_waypoints
Definition: mission_protocol_base.h:272
mavros::plugin::MissionBase::wp_type
WP_TYPE wp_type
Definition: mission_protocol_base.h:288
mavros::plugin::MissionBase::mission_request_int
void mission_request_int(uint16_t seq)
Definition: mission_protocol_base.h:520
mavros::plugin::MissionBase::waypoints
std::vector< mavros_msgs::Waypoint > waypoints
Definition: mission_protocol_base.h:271
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
mavros::plugin::MissionBase::lock_guard
std::lock_guard< std::recursive_mutex > lock_guard
Definition: mission_protocol_base.h:265
mavros::plugin::MissionBase::WP::IDLE
@ IDLE
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
mavros::plugin::MissionBase::publish_waypoints
virtual void publish_waypoints()=0
publish the updated waypoint list after operation
mavros::plugin::MissionBase::do_pull_after_gcs
bool do_pull_after_gcs
Definition: mission_protocol_base.h:304
mavros::plugin::MissionBase::handle_mission_item
void handle_mission_item(const mavlink::mavlink_message_t *msg, WP_ITEM &wpi)
handle MISSION_ITEM mavlink msg handles and stores mission items when pulling waypoints
Definition: mission_protocol_base.cpp:62
mavros::plugin::MissionBase::mission_item_int_support_confirmed
bool mission_item_int_support_confirmed
Definition: mission_protocol_base.h:310
mavros::plugin::MissionBase::mission_set_current
void mission_set_current(uint16_t seq)
Definition: mission_protocol_base.h:532
mavros::plugin::MissionBase::WP::TXPARTIAL
@ TXPARTIAL
mavros::plugin::MissionBase::request_mission_done
void request_mission_done(void)
Send ACK back to FCU after pull.
Definition: mission_protocol_base.h:412
mavros::plugin::MissionBase::WP::TXWPINT
@ TXWPINT
mavros::plugin::MissionBase::mission_clear_all
void mission_clear_all()
Definition: mission_protocol_base.h:580
mavros::plugin::MissionBase::WP::TXLIST
@ TXLIST
mavros::utils::enum_value
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
mavros::plugin::MissionBase::WP::TXWP
@ TXWP
mavros::plugin::MissionBase::handle_mission_ack
void handle_mission_ack(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_ACK &mack)
handle MISSION_ACK mavlink msg Handles a MISSION_ACK which marks the end of a push,...
Definition: mission_protocol_base.cpp:230
mavros::plugin::MissionBase::WP::CLEAR
@ CLEAR
mavros::plugin::MissionBase::WP::RXWP
@ RXWP
mavros::plugin::MissionBase::handle_mission_request_int
void handle_mission_request_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MISSION_REQUEST_INT &mreq)
handle MISSION_REQUEST_INT mavlink msg handles and acts on misison request from FCU
Definition: mission_protocol_base.cpp:147


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03