aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-09-08 20:05:49 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-09-08 20:05:49 +0200
commit690d29078fe5c1478c5f455fe1046731be663b79 (patch)
treeef7635c001b61fa41ca4f05fcc4f5d6f3fa07e8a /src/modules/mavlink
parentc3bb6960e6f85d07d65fefdfebfdc0650e81aa92 (diff)
parent751c026469f1504e94f46884a641a2838a4015ad (diff)
downloadpx4-firmware-690d29078fe5c1478c5f455fe1046731be663b79.tar.gz
px4-firmware-690d29078fe5c1478c5f455fe1046731be663b79.tar.bz2
px4-firmware-690d29078fe5c1478c5f455fe1046731be663b79.zip
Merge branch 'master' of github.com:PX4/Firmware
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/missionlib.c6
-rw-r--r--src/modules/mavlink/waypoints.c6
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)