aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2013-12-23 13:38:13 +0100
committerThomas Gubler <thomasgubler@gmail.com>2013-12-23 13:40:56 +0100
commitb7652986d9cc0fe3edc765e3485b696b4b639b03 (patch)
tree857df4ef585453196f9ea18e6e998120bb98f3a9 /src/modules/mavlink
parentfcdb77d8ef8e0278eb9f8fc1cdf7c39d000c66c2 (diff)
downloadpx4-firmware-b7652986d9cc0fe3edc765e3485b696b4b639b03.tar.gz
px4-firmware-b7652986d9cc0fe3edc765e3485b696b4b639b03.tar.bz2
px4-firmware-b7652986d9cc0fe3edc765e3485b696b4b639b03.zip
add minimal pitch field to mission item
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/waypoints.c11
1 files changed, 10 insertions, 1 deletions
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index 52a580d5b..b72086a7f 100644
--- a/src/modules/mavlink/waypoints.c
+++ b/src/modules/mavlink/waypoints.c
@@ -103,11 +103,20 @@ int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavli
return MAV_MISSION_ERROR;
}
+ switch (mavlink_mission_item->command) {
+ case MAV_CMD_NAV_TAKEOFF:
+ mission_item->pitch_min = mavlink_mission_item->param1;
+ break;
+ default:
+ mission_item->radius = mavlink_mission_item->param1;
+ break;
+ }
+
mission_item->yaw = _wrap_pi(mavlink_mission_item->param4*M_DEG_TO_RAD_F);
mission_item->loiter_radius = fabsf(mavlink_mission_item->param3);
mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
mission_item->nav_cmd = mavlink_mission_item->command;
- mission_item->radius = mavlink_mission_item->param1;
+
mission_item->time_inside = mavlink_mission_item->param2 / 1e3f; /* from milliseconds to seconds */
mission_item->autocontinue = mavlink_mission_item->autocontinue;
mission_item->index = mavlink_mission_item->seq;