From 6104d14968f7093cc3299f1dec25b7b7422fa4bb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 6 Sep 2013 16:51:46 +0200 Subject: Have systems loiter at the last waypoint --- src/modules/mavlink/missionlib.c | 6 +++--- src/modules/mavlink/waypoints.c | 6 ++++-- 2 files changed, 7 insertions(+), 5 deletions(-) (limited to 'src/modules/mavlink') diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c index be88b8794..3175e64ce 100644 --- a/src/modules/mavlink/missionlib.c +++ b/src/modules/mavlink/missionlib.c @@ -167,9 +167,9 @@ bool set_special_fields(float param1, float param2, float param3, float param4, sp->loiter_direction = (param3 >= 0) ? 1 : -1; sp->param1 = param1; - sp->param1 = param2; - sp->param1 = param3; - sp->param1 = param4; + sp->param2 = param2; + sp->param3 = param3; + sp->param4 = param4; } /** diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c index 16a7c2d35..12d82ccc2 100644 --- a/src/modules/mavlink/waypoints.c +++ b/src/modules/mavlink/waypoints.c @@ -417,6 +417,7 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_ } if (time_elapsed) { + if (cur_wp->autocontinue) { cur_wp->current = 0; @@ -425,9 +426,10 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_ if (wpm->current_active_wp_id == wpm->size - 1 && wpm->size > 1) { /* the last waypoint was reached, if auto continue is - * activated restart the waypoint list from the beginning + * activated keep the system loitering there. */ - wpm->current_active_wp_id = 0; + cur_wp->MAV_CMD_NAV_LOITER_UNLIM; + cur_wp->param3 = 15.0f // XXX magic number 15 m loiter radius } else { if ((uint16_t)(wpm->current_active_wp_id + 1) < wpm->size) -- cgit v1.2.3