aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-04-09 18:39:23 +0200
committerJulian Oes <julian@oes.ch>2014-04-18 22:05:47 +0200
commit665a2d6a92827e27213d596df7383061636c5dde (patch)
tree22589b84d413bbbc58620746e2025c38db704f1f /src/modules
parentb96669a5314198b88e406fc02940ed2ced291f2b (diff)
downloadpx4-firmware-665a2d6a92827e27213d596df7383061636c5dde.tar.gz
px4-firmware-665a2d6a92827e27213d596df7383061636c5dde.tar.bz2
px4-firmware-665a2d6a92827e27213d596df7383061636c5dde.zip
mavlink and mission topic: added reading in DO_JUMP mission items
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp10
-rw-r--r--src/modules/uORB/topics/mission.h4
2 files changed, 12 insertions, 2 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 1ed3f4001..2dba567b0 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -863,7 +863,10 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
case MAV_CMD_NAV_TAKEOFF:
mission_item->pitch_min = mavlink_mission_item->param2;
break;
-
+ case MAV_CMD_DO_JUMP:
+ mission_item->do_jump_mission_index = mavlink_mission_item->param1;
+ /* TODO: also save param2 (repeat count) */
+ break;
default:
mission_item->acceptance_radius = mavlink_mission_item->param2;
break;
@@ -896,6 +899,11 @@ int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_
mavlink_mission_item->param2 = mission_item->pitch_min;
break;
+ case NAV_CMD_DO_JUMP:
+ mavlink_mission_item->param1 = mission_item->do_jump_mission_index;
+ /* TODO: also save param2 (repeat count) */
+ break;
+
default:
mavlink_mission_item->param2 = mission_item->acceptance_radius;
break;
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 9594c4c6a..1ccdb7181 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -58,7 +58,8 @@ enum NAV_CMD {
NAV_CMD_LAND=21,
NAV_CMD_TAKEOFF=22,
NAV_CMD_ROI=80,
- NAV_CMD_PATHPLANNING=81
+ NAV_CMD_PATHPLANNING=81,
+ NAV_CMD_DO_JUMP=177
};
enum ORIGIN {
@@ -91,6 +92,7 @@ struct mission_item_s {
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
bool autocontinue; /**< true if next waypoint should follow after this one */
enum ORIGIN origin; /**< where the waypoint has been generated */
+ int do_jump_mission_index; /**< the mission index that we want to jump to */
};
struct mission_s