diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-06 16:59:37 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-06 17:00:49 +0200 |
commit | 127832b8fdec4a81b81d332e68f20d62e609023e (patch) | |
tree | 7baffaed95f977abe351b434bce547f6f0b3518b /src/modules/mavlink | |
parent | 6104d14968f7093cc3299f1dec25b7b7422fa4bb (diff) | |
parent | c8b667c9cc5149f0cfd849c8b86c5f5356e53bb6 (diff) | |
download | px4-firmware-127832b8fdec4a81b81d332e68f20d62e609023e.tar.gz px4-firmware-127832b8fdec4a81b81d332e68f20d62e609023e.tar.bz2 px4-firmware-127832b8fdec4a81b81d332e68f20d62e609023e.zip |
Have systems loiter at the last waypoint
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r-- | src/modules/mavlink/waypoints.c | 4 |
1 files changed, 2 insertions, 2 deletions
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c index 12d82ccc2..c6c2eac68 100644 --- a/src/modules/mavlink/waypoints.c +++ b/src/modules/mavlink/waypoints.c @@ -428,8 +428,8 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_ /* the last waypoint was reached, if auto continue is * activated keep the system loitering there. */ - cur_wp->MAV_CMD_NAV_LOITER_UNLIM; - cur_wp->param3 = 15.0f // XXX magic number 15 m loiter radius + cur_wp->command = 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) |