aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics/mission.h
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/uORB/topics/mission.h
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/uORB/topics/mission.h')
-rw-r--r--src/modules/uORB/topics/mission.h19
1 files changed, 11 insertions, 8 deletions
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index a39a1e4d7..441efe458 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -46,14 +46,17 @@
#include <stdbool.h>
#include "../uORB.h"
+/* compatible to mavlink MAV_CMD */
enum NAV_CMD {
- NAV_CMD_WAYPOINT = 0,
- NAV_CMD_LOITER_TURN_COUNT,
- NAV_CMD_LOITER_TIME_LIMIT,
- NAV_CMD_LOITER_UNLIMITED,
- NAV_CMD_RETURN_TO_LAUNCH,
- NAV_CMD_LAND,
- NAV_CMD_TAKEOFF
+ NAV_CMD_WAYPOINT=16,
+ NAV_CMD_LOITER_UNLIMITED=17,
+ NAV_CMD_LOITER_TURN_COUNT=18,
+ NAV_CMD_LOITER_TIME_LIMIT=19,
+ NAV_CMD_RETURN_TO_LAUNCH=20,
+ NAV_CMD_LAND=21,
+ NAV_CMD_TAKEOFF=22,
+ NAV_CMD_ROI=80,
+ NAV_CMD_PATHPLANNING=81
};
/**
@@ -76,7 +79,7 @@ struct mission_item_s
float yaw; /**< in radians NED -PI..+PI */
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
- enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
+ enum NAV_CMD nav_cmd; /**< navigation command */
float radius; /**< radius in which the mission is accepted as reached in meters */
float time_inside; /**< time that the MAV should stay inside the radius before advancing in seconds */
bool autocontinue; /**< true if next waypoint should follow after this one */