00001
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #include <chrono>
00028 #include <condition_variable>
00029 #include <mavros/mavros_plugin.h>
00030 #include <pluginlib/class_list_macros.h>
00031
00032 #include <mavros/WaypointList.h>
00033 #include <mavros/WaypointSetCurrent.h>
00034 #include <mavros/WaypointClear.h>
00035 #include <mavros/WaypointPull.h>
00036 #include <mavros/WaypointPush.h>
00037 #include <mavros/WaypointGOTO.h>
00038
00039 namespace mavplugin {
00040
00041 class WaypointItem {
00042 public:
00043 uint16_t seq;
00044 enum MAV_FRAME frame;
00045 enum MAV_CMD command;
00046 uint8_t current;
00047 bool autocontinue;
00048 float param1;
00049 float param2;
00050 float param3;
00051 float param4;
00052 double x_lat;
00053 double y_long;
00054 double z_alt;
00055
00056 static mavros::Waypoint to_msg(WaypointItem &wp) {
00057 mavros::Waypoint ret;
00058
00059 ret.frame = static_cast<uint8_t>(wp.frame);
00060 ret.command = static_cast<uint16_t>(wp.command);
00061 ret.is_current = !!wp.current;
00062 ret.autocontinue = wp.autocontinue;
00063 ret.param1 = wp.param1;
00064 ret.param2 = wp.param2;
00065 ret.param3 = wp.param3;
00066 ret.param4 = wp.param4;
00067 ret.x_lat = wp.x_lat;
00068 ret.y_long = wp.y_long;
00069 ret.z_alt = wp.z_alt;
00070
00071 return ret;
00072 }
00073
00074 static WaypointItem from_msg(mavros::Waypoint &wp, uint16_t seq) {
00075 WaypointItem ret;
00076
00077 ret.seq = seq;
00078 ret.frame = static_cast<enum MAV_FRAME>(wp.frame);
00079 ret.command = static_cast<enum MAV_CMD>(wp.command);
00080 ret.current = wp.is_current;
00081 ret.autocontinue = wp.autocontinue;
00082 ret.param1 = wp.param1;
00083 ret.param2 = wp.param2;
00084 ret.param3 = wp.param3;
00085 ret.param4 = wp.param4;
00086 ret.x_lat = wp.x_lat;
00087 ret.y_long = wp.y_long;
00088 ret.z_alt = wp.z_alt;
00089
00090 return ret;
00091 }
00092
00093 static WaypointItem from_mission_item(mavlink_mission_item_t &mit) {
00094 WaypointItem ret;
00095
00096 ret.seq = mit.seq;
00097 ret.frame = static_cast<enum MAV_FRAME>(mit.frame);
00098 ret.command = static_cast<enum MAV_CMD>(mit.command);
00099 ret.current = mit.current;
00100 ret.autocontinue = mit.autocontinue;
00101 ret.param1 = mit.param1;
00102 ret.param2 = mit.param2;
00103 ret.param3 = mit.param3;
00104 ret.param4 = mit.param4;
00105 ret.x_lat = mit.x;
00106 ret.y_long = mit.y;
00107 ret.z_alt = mit.z;
00108
00109 return ret;
00110 }
00111
00112 static std::string to_string_frame(WaypointItem &wpi) {
00113 switch (wpi.frame) {
00114 case MAV_FRAME_GLOBAL: return "GAA";
00115 case MAV_FRAME_LOCAL_NED: return "LNED";
00116 case MAV_FRAME_MISSION: return "MIS";
00117 case MAV_FRAME_GLOBAL_RELATIVE_ALT: return "GRA";
00118 case MAV_FRAME_LOCAL_ENU: return "LENU";
00119 default:
00120 std::ostringstream unk;
00121 unk << "UNK " << (int)wpi.frame;
00122 return unk.str();
00123 }
00124 }
00125
00126 static std::string to_string_command(WaypointItem &wpi) {
00127 switch (wpi.command) {
00128 case MAV_CMD_NAV_WAYPOINT: return "WAYPOINT";
00129 case MAV_CMD_NAV_LOITER_UNLIM: return "LOITER UNLIM";
00130 case MAV_CMD_NAV_LOITER_TURNS: return "LOITER TURNS";
00131 case MAV_CMD_NAV_LOITER_TIME: return "LOITER TIME";
00132 case MAV_CMD_NAV_RETURN_TO_LAUNCH: return "RTL";
00133 case MAV_CMD_NAV_LAND: return "LAND";
00134 case MAV_CMD_NAV_TAKEOFF: return "TAKEOFF";
00135 case MAV_CMD_NAV_ROI: return "ROI";
00136 case MAV_CMD_NAV_PATHPLANNING: return "PATH PLANNING";
00137 default:
00138 std::ostringstream unk;
00139 unk << "UNK " << (int)wpi.command;
00140 return unk.str();
00141 }
00142 }
00143 };
00144
00145
00149 class WaypointPlugin : public MavRosPlugin {
00150 public:
00151 WaypointPlugin() :
00152 uas(nullptr),
00153 wp_state(WP_IDLE),
00154 wp_retries(RETRIES_COUNT),
00155 wp_count(0),
00156 wp_cur_id(0),
00157 wp_cur_active(0),
00158 wp_set_active(0),
00159 is_timedout(false),
00160 do_pull_after_gcs(false),
00161 reshedule_pull(false),
00162 BOOTUP_TIME_DT(BOOTUP_TIME_MS / 1000.0),
00163 LIST_TIMEOUT_DT(LIST_TIMEOUT_MS / 1000.0),
00164 WP_TIMEOUT_DT(WP_TIMEOUT_MS/ 1000.0),
00165 RESHEDULE_DT(RESHEDULE_MS / 1000.0)
00166 { };
00167
00168 void initialize(UAS &uas_,
00169 ros::NodeHandle &nh,
00170 diagnostic_updater::Updater &diag_updater)
00171 {
00172 uas = &uas_;
00173 wp_state = WP_IDLE;
00174
00175 wp_nh = ros::NodeHandle(nh, "mission");
00176
00177 wp_nh.param("pull_after_gcs", do_pull_after_gcs, false);
00178
00179 wp_list_pub = wp_nh.advertise<mavros::WaypointList>("waypoints", 2, true);
00180 pull_srv = wp_nh.advertiseService("pull", &WaypointPlugin::pull_cb, this);
00181 push_srv = wp_nh.advertiseService("push", &WaypointPlugin::push_cb, this);
00182 clear_srv = wp_nh.advertiseService("clear", &WaypointPlugin::clear_cb, this);
00183 set_cur_srv = wp_nh.advertiseService("set_current", &WaypointPlugin::set_cur_cb, this);
00184 goto_srv = wp_nh.advertiseService("goto", &WaypointPlugin::goto_cb, this);
00185
00186 wp_timer = wp_nh.createTimer(WP_TIMEOUT_DT, &WaypointPlugin::timeout_cb, this, true);
00187 wp_timer.stop();
00188 shedule_timer = wp_nh.createTimer(BOOTUP_TIME_DT, &WaypointPlugin::sheduled_pull_cb, this, true);
00189 shedule_timer.stop();
00190 uas->sig_connection_changed.connect(boost::bind(&WaypointPlugin::connection_cb, this, _1));
00191 };
00192
00193 std::string const get_name() const {
00194 return "Waypoint";
00195 };
00196
00197 const message_map get_rx_handlers() {
00198 return {
00199 MESSAGE_HANDLER(MAVLINK_MSG_ID_MISSION_ITEM, &WaypointPlugin::handle_mission_item),
00200 MESSAGE_HANDLER(MAVLINK_MSG_ID_MISSION_REQUEST, &WaypointPlugin::handle_mission_request),
00201 MESSAGE_HANDLER(MAVLINK_MSG_ID_MISSION_CURRENT, &WaypointPlugin::handle_mission_current),
00202 MESSAGE_HANDLER(MAVLINK_MSG_ID_MISSION_COUNT, &WaypointPlugin::handle_mission_count),
00203 MESSAGE_HANDLER(MAVLINK_MSG_ID_MISSION_ITEM_REACHED, &WaypointPlugin::handle_mission_item_reached),
00204 MESSAGE_HANDLER(MAVLINK_MSG_ID_MISSION_ACK, &WaypointPlugin::handle_mission_ack),
00205 };
00206 }
00207
00208 private:
00209 std::recursive_mutex mutex;
00210 UAS *uas;
00211
00212 ros::NodeHandle wp_nh;
00213 ros::Publisher wp_list_pub;
00214 ros::ServiceServer pull_srv;
00215 ros::ServiceServer push_srv;
00216 ros::ServiceServer clear_srv;
00217 ros::ServiceServer set_cur_srv;
00218 ros::ServiceServer goto_srv;
00219
00220 std::vector<WaypointItem> waypoints;
00221 std::vector<WaypointItem> send_waypoints;
00222 enum {
00223 WP_IDLE,
00224 WP_RXLIST,
00225 WP_RXWP,
00226 WP_TXLIST,
00227 WP_TXWP,
00228 WP_CLEAR,
00229 WP_SET_CUR
00230 } wp_state;
00231
00232 size_t wp_count;
00233 size_t wp_cur_id;
00234 size_t wp_cur_active;
00235 size_t wp_set_active;
00236 size_t wp_retries;
00237 bool is_timedout;
00238 std::mutex recv_cond_mutex;
00239 std::mutex send_cond_mutex;
00240 std::condition_variable list_receiving;
00241 std::condition_variable list_sending;
00242
00243 ros::Timer wp_timer;
00244 ros::Timer shedule_timer;
00245 bool do_pull_after_gcs;
00246 bool reshedule_pull;
00247
00248 static constexpr int BOOTUP_TIME_MS = 15000;
00249 static constexpr int LIST_TIMEOUT_MS = 30000;
00250 static constexpr int WP_TIMEOUT_MS = 1000;
00251 static constexpr int RESHEDULE_MS = 5000;
00252 static constexpr int RETRIES_COUNT = 3;
00253
00254 const ros::Duration BOOTUP_TIME_DT;
00255 const ros::Duration LIST_TIMEOUT_DT;
00256 const ros::Duration WP_TIMEOUT_DT;
00257 const ros::Duration RESHEDULE_DT;
00258
00259
00260
00261 void handle_mission_item(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00262 mavlink_mission_item_t mit;
00263 mavlink_msg_mission_item_decode(msg, &mit);
00264 WaypointItem wpi = WaypointItem::from_mission_item(mit);
00265 unique_lock lock(mutex);
00266
00267
00268 if (wp_state == WP_RXWP) {
00269 if (mit.seq != wp_cur_id) {
00270 ROS_WARN_NAMED("wp", "WP: Seq mismatch, dropping item (%d != %zu)",
00271 mit.seq, wp_cur_id);
00272 return;
00273 }
00274
00275 ROS_INFO_STREAM_NAMED("wp", "WP: item #" << wpi.seq <<
00276 " " << WaypointItem::to_string_frame(wpi) <<
00277 " " << WaypointItem::to_string_command(wpi) <<
00278 ((wpi.current) ? " CUR" : " ") <<
00279 " params: " << wpi.param1 <<
00280 ", " << wpi.param2 <<
00281 ", " << wpi.param3 <<
00282 ", " << wpi.param4 <<
00283 " x: " << wpi.x_lat <<
00284 " y: " << wpi.y_long <<
00285 " z: " << wpi.z_alt);
00286
00287 waypoints.push_back(wpi);
00288 if (++wp_cur_id < wp_count) {
00289 restart_timeout_timer();
00290 mission_request(wp_cur_id);
00291 }
00292 else {
00293 request_mission_done();
00294 lock.unlock();
00295 publish_waypoints();
00296 }
00297 }
00298 else {
00299 ROS_DEBUG_NAMED("wp", "WP: rejecting item, wrong state %d", wp_state);
00300 if (do_pull_after_gcs && reshedule_pull) {
00301 ROS_DEBUG_NAMED("wp", "WP: reshedule pull");
00302 shedule_pull(WP_TIMEOUT_DT);
00303 }
00304 }
00305 }
00306
00307 void handle_mission_request(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00308 mavlink_mission_request_t mreq;
00309 mavlink_msg_mission_request_decode(msg, &mreq);
00310 lock_guard lock(mutex);
00311
00312 if ((wp_state == WP_TXLIST && mreq.seq == 0) || (wp_state == WP_TXWP)) {
00313 if (mreq.seq != wp_cur_id && mreq.seq != wp_cur_id + 1) {
00314 ROS_WARN_NAMED("wp", "WP: Seq mismatch, dropping request (%d != %zu)",
00315 mreq.seq, wp_cur_id);
00316 return;
00317 }
00318
00319 restart_timeout_timer();
00320 if (mreq.seq < send_waypoints.size()) {
00321 wp_state = WP_TXWP;
00322 wp_cur_id = mreq.seq;
00323 send_waypoint(wp_cur_id);
00324 }
00325 else
00326 ROS_ERROR_NAMED("wp", "WP: FCU require seq out of range");
00327 }
00328 else
00329 ROS_DEBUG_NAMED("wp", "WP: rejecting request, wrong state %d", wp_state);
00330 }
00331
00332 void handle_mission_current(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00333 mavlink_mission_current_t mcur;
00334 mavlink_msg_mission_current_decode(msg, &mcur);
00335 unique_lock lock(mutex);
00336
00337 if (wp_state == WP_SET_CUR) {
00338
00339 ROS_DEBUG_NAMED("wp", "WP: set current #%d done", mcur.seq);
00340 go_idle();
00341 wp_cur_active = mcur.seq;
00342 set_current_waypoint(wp_cur_active);
00343
00344 lock.unlock();
00345 list_sending.notify_all();
00346 publish_waypoints();
00347 }
00348 else if (wp_state == WP_IDLE && wp_cur_active != mcur.seq) {
00349
00350 ROS_DEBUG_NAMED("wp", "WP: update current #%d", mcur.seq);
00351 wp_cur_active = mcur.seq;
00352 set_current_waypoint(wp_cur_active);
00353
00354 lock.unlock();
00355 publish_waypoints();
00356 }
00357 }
00358
00359 void handle_mission_count(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00360 mavlink_mission_count_t mcnt;
00361 mavlink_msg_mission_count_decode(msg, &mcnt);
00362 unique_lock lock(mutex);
00363
00364 if (wp_state == WP_RXLIST) {
00365
00366 ROS_DEBUG_NAMED("wp", "WP: count %d", mcnt.count);
00367
00368 wp_count = mcnt.count;
00369 wp_cur_id = 0;
00370
00371 waypoints.clear();
00372 waypoints.reserve(wp_count);
00373
00374 if (wp_count > 0) {
00375 wp_state = WP_RXWP;
00376 restart_timeout_timer();
00377 mission_request(wp_cur_id);
00378 }
00379 else {
00380 request_mission_done();
00381 lock.unlock();
00382 publish_waypoints();
00383 }
00384 }
00385 else {
00386 ROS_INFO_NAMED("wp", "WP: seems GCS requesting mission");
00387
00388 if (do_pull_after_gcs) {
00389 ROS_INFO_NAMED("wp", "WP: sheduling pull after GCS is done");
00390 reshedule_pull = true;
00391 shedule_pull(RESHEDULE_DT);
00392 }
00393 }
00394 }
00395
00396 void handle_mission_item_reached(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00397 mavlink_mission_item_reached_t mitr;
00398 mavlink_msg_mission_item_reached_decode(msg, &mitr);
00399
00400
00401 ROS_INFO_NAMED("wp", "WP: reached #%d", mitr.seq);
00402 }
00403
00404 void handle_mission_ack(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00405 mavlink_mission_ack_t mack;
00406 mavlink_msg_mission_ack_decode(msg, &mack);
00407 unique_lock lock(mutex);
00408
00409 if ((wp_state == WP_TXLIST || wp_state == WP_TXWP)
00410 && (wp_cur_id == send_waypoints.size() - 1)
00411 && (mack.type == MAV_MISSION_ACCEPTED)) {
00412
00413 go_idle();
00414 waypoints = send_waypoints;
00415 send_waypoints.clear();
00416
00417 lock.unlock();
00418 list_sending.notify_all();
00419 publish_waypoints();
00420 ROS_INFO_NAMED("wp", "WP: mission sended");
00421 }
00422 else if (wp_state == WP_TXLIST || wp_state == WP_TXWP) {
00423 go_idle();
00424
00425 is_timedout = true;
00426 lock.unlock();
00427 list_sending.notify_all();
00428
00429 switch (mack.type) {
00430 case MAV_MISSION_ERROR:
00431 ROS_ERROR_NAMED("wp", "WP: upload failed: general error");
00432 break;
00433
00434 case MAV_MISSION_UNSUPPORTED_FRAME:
00435 ROS_ERROR_NAMED("wp", "WP: upload failed: unsupported frame");
00436 break;
00437
00438 case MAV_MISSION_UNSUPPORTED:
00439 ROS_ERROR_NAMED("wp", "WP: upload failed: command unsupported");
00440 break;
00441
00442 case MAV_MISSION_NO_SPACE:
00443 ROS_ERROR_NAMED("wp", "WP: upload failed: no space left on mission storage");
00444 break;
00445
00446 case MAV_MISSION_DENIED:
00447 ROS_ERROR_NAMED("wp", "WP: upload failed: denied");
00448 break;
00449
00450 default:
00451 ROS_ERROR_NAMED("wp", "WP: upload failed: error #%d", mack.type);
00452 break;
00453 }
00454 }
00455 else if (wp_state == WP_CLEAR) {
00456 go_idle();
00457 if (mack.type != MAV_MISSION_ACCEPTED) {
00458 is_timedout = true;
00459 lock.unlock();
00460 ROS_ERROR_NAMED("wp", "WP: clear failed: error #%d", mack.type);
00461 }
00462 else {
00463 waypoints.clear();
00464 lock.unlock();
00465 publish_waypoints();
00466 ROS_INFO_NAMED("wp", "WP: mission cleared");
00467 }
00468
00469 list_sending.notify_all();
00470 }
00471 else
00472 ROS_DEBUG_NAMED("wp", "WP: not planned ACK, type: %d", mack.type);
00473 }
00474
00475
00476
00477 void timeout_cb(const ros::TimerEvent &event) {
00478 unique_lock lock(mutex);
00479 if (wp_retries > 0) {
00480 wp_retries--;
00481 ROS_WARN_NAMED("wp", "WP: timeout, retries left %zu", wp_retries);
00482
00483 switch (wp_state) {
00484 case WP_RXLIST:
00485 mission_request_list();
00486 break;
00487 case WP_RXWP:
00488 mission_request(wp_cur_id);
00489 break;
00490 case WP_TXLIST:
00491 mission_count(wp_count);
00492 break;
00493 case WP_TXWP:
00494 send_waypoint(wp_cur_id);
00495 break;
00496 case WP_CLEAR:
00497 mission_clear_all();
00498 break;
00499 case WP_SET_CUR:
00500 mission_set_current(wp_set_active);
00501 break;
00502
00503 case WP_IDLE:
00504 break;
00505 }
00506
00507 restart_timeout_timer_int();
00508 }
00509 else {
00510 ROS_ERROR_NAMED("wp", "WP: timed out.");
00511 go_idle();
00512 is_timedout = true;
00513
00514 lock.unlock();
00515 list_receiving.notify_all();
00516 list_sending.notify_all();
00517 }
00518 }
00519
00520 void connection_cb(bool connected) {
00521 lock_guard lock(mutex);
00522 if (connected)
00523 shedule_pull(BOOTUP_TIME_DT);
00524 else
00525 shedule_timer.stop();
00526 }
00527
00528 void sheduled_pull_cb(const ros::TimerEvent &event) {
00529 lock_guard lock(mutex);
00530 if (wp_state != WP_IDLE) {
00531
00532 ROS_DEBUG_NAMED("wp", "WP: busy, reshedule pull");
00533 shedule_pull(RESHEDULE_DT);
00534 return;
00535 }
00536
00537 ROS_DEBUG_NAMED("wp", "WP: start sheduled pull");
00538 wp_state = WP_RXLIST;
00539 wp_count = 0;
00540 restart_timeout_timer();
00541 mission_request_list();
00542 }
00543
00544 void request_mission_done(void) {
00545
00546 mission_ack(MAV_MISSION_ACCEPTED);
00547
00548 go_idle();
00549 list_receiving.notify_all();
00550 ROS_INFO_NAMED("wp", "WP: mission received");
00551 }
00552
00553 void go_idle(void) {
00554 reshedule_pull = false;
00555 wp_state = WP_IDLE;
00556 wp_timer.stop();
00557 }
00558
00559 void restart_timeout_timer(void) {
00560 wp_retries = RETRIES_COUNT;
00561 restart_timeout_timer_int();
00562 }
00563
00564 void restart_timeout_timer_int(void) {
00565 is_timedout = false;
00566 wp_timer.stop();
00567 wp_timer.start();
00568 }
00569
00570 void shedule_pull(const ros::Duration &dt) {
00571 shedule_timer.stop();
00572 shedule_timer.setPeriod(dt);
00573 shedule_timer.start();
00574 }
00575
00576 void send_waypoint(size_t seq) {
00577 if (seq < send_waypoints.size()) {
00578 WaypointItem wpi = send_waypoints.at(seq);
00579 mission_item(wpi);
00580
00581 ROS_DEBUG_STREAM_NAMED("wp", "WP: send item #" << wpi.seq <<
00582 " " << WaypointItem::to_string_frame(wpi) <<
00583 " " << WaypointItem::to_string_command(wpi) <<
00584 ((wpi.current) ? " CUR" : " ") <<
00585 " params: " << wpi.param1 <<
00586 ", " << wpi.param2 <<
00587 ", " << wpi.param3 <<
00588 ", " << wpi.param4 <<
00589 " x: " << wpi.x_lat <<
00590 " y: " << wpi.y_long <<
00591 " z: " << wpi.z_alt);
00592 }
00593 }
00594
00595 bool wait_fetch_all() {
00596 std::unique_lock<std::mutex> lock(recv_cond_mutex);
00597
00598 return list_receiving.wait_for(lock, std::chrono::nanoseconds(LIST_TIMEOUT_DT.toNSec()))
00599 == std::cv_status::no_timeout
00600 && !is_timedout;
00601 }
00602
00603 bool wait_push_all() {
00604 std::unique_lock<std::mutex> lock(send_cond_mutex);
00605
00606 return list_sending.wait_for(lock, std::chrono::nanoseconds(LIST_TIMEOUT_DT.toNSec()))
00607 == std::cv_status::no_timeout
00608 && !is_timedout;
00609 }
00610
00611 void set_current_waypoint(size_t seq) {
00612 for (auto it = waypoints.begin();
00613 it != waypoints.end();
00614 ++it)
00615 it->current = (it->seq == seq) ? true : false;
00616 }
00617
00618 void publish_waypoints() {
00619 mavros::WaypointListPtr wpl = boost::make_shared<mavros::WaypointList>();
00620 unique_lock lock(mutex);
00621
00622 wpl->waypoints.clear();
00623 wpl->waypoints.reserve(waypoints.size());
00624 for (auto it = waypoints.begin();
00625 it != waypoints.end();
00626 ++it) {
00627 wpl->waypoints.push_back(WaypointItem::to_msg(*it));
00628 }
00629
00630 lock.unlock();
00631 wp_list_pub.publish(wpl);
00632 }
00633
00634
00635
00636 void mission_item(WaypointItem &wp) {
00637 mavlink_message_t msg;
00638
00639 mavlink_msg_mission_item_pack_chan(UAS_PACK_CHAN(uas), &msg,
00640 UAS_PACK_TGT(uas),
00641 wp.seq,
00642 wp.frame,
00643 wp.command,
00644 wp.current,
00645 wp.autocontinue,
00646 wp.param1,
00647 wp.param2,
00648 wp.param3,
00649 wp.param4,
00650 wp.x_lat,
00651 wp.y_long,
00652 wp.z_alt
00653 );
00654 UAS_FCU(uas)->send_message(&msg);
00655 }
00656
00657 void mission_request(uint16_t seq) {
00658 mavlink_message_t msg;
00659
00660 ROS_DEBUG_NAMED("wp", "WP:m: request #%u", seq);
00661 mavlink_msg_mission_request_pack_chan(UAS_PACK_CHAN(uas), &msg,
00662 UAS_PACK_TGT(uas),
00663 seq
00664 );
00665 UAS_FCU(uas)->send_message(&msg);
00666 }
00667
00668 void mission_set_current(uint16_t seq) {
00669 mavlink_message_t msg;
00670
00671 ROS_DEBUG_NAMED("wp", "WP:m: set current #%u", seq);
00672 mavlink_msg_mission_set_current_pack_chan(UAS_PACK_CHAN(uas), &msg,
00673 UAS_PACK_TGT(uas),
00674 seq
00675 );
00676 UAS_FCU(uas)->send_message(&msg);
00677 }
00678
00679 void mission_request_list() {
00680 mavlink_message_t msg;
00681
00682 ROS_DEBUG_NAMED("wp", "WP:m: request list");
00683 mavlink_msg_mission_request_list_pack_chan(UAS_PACK_CHAN(uas), &msg,
00684 UAS_PACK_TGT(uas)
00685 );
00686 UAS_FCU(uas)->send_message(&msg);
00687 }
00688
00689 void mission_count(uint16_t cnt) {
00690 mavlink_message_t msg;
00691
00692 ROS_DEBUG_NAMED("wp", "WP:m: count %u", cnt);
00693 mavlink_msg_mission_count_pack_chan(UAS_PACK_CHAN(uas), &msg,
00694 UAS_PACK_TGT(uas),
00695 cnt
00696 );
00697 UAS_FCU(uas)->send_message(&msg);
00698 }
00699
00700 void mission_clear_all() {
00701 mavlink_message_t msg;
00702
00703 ROS_DEBUG_NAMED("wp", "WP:m: clear all");
00704 mavlink_msg_mission_clear_all_pack_chan(UAS_PACK_CHAN(uas), &msg,
00705 UAS_PACK_TGT(uas)
00706 );
00707 UAS_FCU(uas)->send_message(&msg);
00708 }
00709
00710 void mission_ack(enum MAV_MISSION_RESULT type) {
00711 mavlink_message_t msg;
00712
00713 ROS_DEBUG_NAMED("wp", "WP:m: ACK %u", type);
00714 mavlink_msg_mission_ack_pack_chan(UAS_PACK_CHAN(uas), &msg,
00715 UAS_PACK_TGT(uas),
00716 type
00717 );
00718 UAS_FCU(uas)->send_message(&msg);
00719 }
00720
00721
00722
00723 bool pull_cb(mavros::WaypointPull::Request &req,
00724 mavros::WaypointPull::Response &res) {
00725 unique_lock lock(mutex);
00726
00727 if (wp_state != WP_IDLE)
00728
00729 return false;
00730
00731 wp_state = WP_RXLIST;
00732 wp_count = 0;
00733 restart_timeout_timer();
00734
00735 lock.unlock();
00736 mission_request_list();
00737 res.success = wait_fetch_all();
00738 lock.lock();
00739
00740 res.wp_received = waypoints.size();
00741 go_idle();
00742 return true;
00743 }
00744
00745 bool push_cb(mavros::WaypointPush::Request &req,
00746 mavros::WaypointPush::Response &res) {
00747 unique_lock lock(mutex);
00748
00749 if (wp_state != WP_IDLE)
00750
00751 return false;
00752
00753 wp_state = WP_TXLIST;
00754
00755 send_waypoints.clear();
00756 send_waypoints.reserve(req.waypoints.size());
00757 uint16_t seq = 0;
00758 for (auto it = req.waypoints.begin();
00759 it != req.waypoints.end();
00760 ++it, ++seq) {
00761 send_waypoints.push_back(WaypointItem::from_msg(*it, seq));
00762 }
00763
00764 wp_count = send_waypoints.size();
00765 wp_cur_id = 0;
00766 restart_timeout_timer();
00767
00768 lock.unlock();
00769 mission_count(wp_count);
00770 res.success = wait_push_all();
00771 lock.lock();
00772
00773 res.wp_transfered = wp_cur_id + 1;
00774 go_idle();
00775 return true;
00776 }
00777
00778 bool clear_cb(mavros::WaypointClear::Request &req,
00779 mavros::WaypointClear::Response &res) {
00780 unique_lock lock(mutex);
00781
00782 if (wp_state != WP_IDLE)
00783 return false;
00784
00785 wp_state = WP_CLEAR;
00786 restart_timeout_timer();
00787
00788 lock.unlock();
00789 mission_clear_all();
00790 res.success = wait_push_all();
00791
00792 lock.lock();
00793 go_idle();
00794 return true;
00795 }
00796
00797 bool set_cur_cb(mavros::WaypointSetCurrent::Request &req,
00798 mavros::WaypointSetCurrent::Response &res) {
00799 unique_lock lock(mutex);
00800
00801 if (wp_state != WP_IDLE)
00802 return false;
00803
00804 wp_state = WP_SET_CUR;
00805 wp_set_active = req.wp_seq;
00806 restart_timeout_timer();
00807
00808 lock.unlock();
00809 mission_set_current(wp_set_active);
00810 res.success = wait_push_all();
00811
00812 lock.lock();
00813 go_idle();
00814 return true;
00815 }
00816
00817 bool goto_cb(mavros::WaypointGOTO::Request &req,
00818 mavros::WaypointGOTO::Response &res) {
00819 unique_lock lock(mutex);
00820
00821 if (wp_state != WP_IDLE)
00822 return false;
00823
00824 if (!uas->is_ardupilotmega()) {
00825 ROS_ERROR_NAMED("wp", "WP: FCU not support GOTO command");
00826 return false;
00827 }
00828
00829 wp_state = WP_TXWP;
00830
00831 WaypointItem wpi = WaypointItem::from_msg(req.waypoint, 0);
00832 wpi.current = 2;
00833
00834 send_waypoints.clear();
00835 send_waypoints.push_back(wpi);
00836
00837 wp_count = 1;
00838 wp_cur_id = 0;
00839 restart_timeout_timer();
00840
00841 lock.unlock();
00842 send_waypoint(wp_cur_id);
00843 res.success = wait_push_all();
00844 lock.lock();
00845
00846 go_idle();
00847 return true;
00848 }
00849 };
00850
00851 };
00852
00853 PLUGINLIB_EXPORT_CLASS(mavplugin::WaypointPlugin, mavplugin::MavRosPlugin)
00854