diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-07 11:52:22 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-07 11:52:22 +0200 |
commit | f721c6f7e09c856e03adb047144f3cb8776db656 (patch) | |
tree | 375be4552330693c2507ce6e33df7957116586f2 /src | |
parent | 5111249eb8356b7b05f216b3cf7e6172f659c5c3 (diff) | |
parent | 127832b8fdec4a81b81d332e68f20d62e609023e (diff) | |
download | px4-firmware-f721c6f7e09c856e03adb047144f3cb8776db656.tar.gz px4-firmware-f721c6f7e09c856e03adb047144f3cb8776db656.tar.bz2 px4-firmware-f721c6f7e09c856e03adb047144f3cb8776db656.zip |
Merge branch 'waypoint_loiter' of github.com:PX4/Firmware into fixedwing_l1
Diffstat (limited to 'src')
-rw-r--r-- | src/modules/mavlink/missionlib.c | 6 | ||||
-rw-r--r-- | src/modules/mavlink/waypoints.c | 6 |
2 files changed, 7 insertions, 5 deletions
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..c6c2eac68 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->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) |