aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-11-22 21:21:30 +0100
committerJulian Oes <julian@oes.ch>2013-11-22 21:21:30 +0100
commit01df715f946afc1cec79d33cba970ad15c62ec73 (patch)
treeef42c322fb2bce4a1bdc0a84aa613d947c8d53c5 /src/modules/mavlink
parent1da7599541d33b8ffb0c8764bb505f1d5e6018b9 (diff)
downloadpx4-firmware-01df715f946afc1cec79d33cba970ad15c62ec73.tar.gz
px4-firmware-01df715f946afc1cec79d33cba970ad15c62ec73.tar.bz2
px4-firmware-01df715f946afc1cec79d33cba970ad15c62ec73.zip
Mission topic: make nav_cmd compatible to the mavlink command
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/waypoints.c4
1 files changed, 2 insertions, 2 deletions
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index a9ee26eac..8e4bbce36 100644
--- a/src/modules/mavlink/waypoints.c
+++ b/src/modules/mavlink/waypoints.c
@@ -78,7 +78,7 @@ void map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavl
mission_item->yaw = 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 = NAV_CMD_WAYPOINT; // TODO correct
+ 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;
@@ -93,7 +93,7 @@ void map_mission_item_to_mavlink_mission_item(const struct mission_item_s *missi
mavlink_mission_item->z = mission_item->altitude;
mavlink_mission_item->param4 = mission_item->yaw*M_RAD_TO_DEG_F;
mavlink_mission_item->param3 = mission_item->loiter_radius*(float)mission_item->loiter_direction;
- mavlink_mission_item->command = MAV_CMD_NAV_WAYPOINT; // TODO add
+ mavlink_mission_item->command = mission_item->nav_cmd;
mavlink_mission_item->param1 = mission_item->radius;
mavlink_mission_item->param2 = mission_item->time_inside * 1e3f; /* from seconds to milliseconds */
mavlink_mission_item->autocontinue = mission_item->autocontinue;