aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/topics/mission.h2
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h12
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h12
-rw-r--r--src/modules/uORB/topics/vehicle_status.h13
4 files changed, 28 insertions, 11 deletions
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index dfc461ae4..4532b329d 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -93,6 +93,8 @@ struct mission_item_s {
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 */
+ int do_jump_repeat_count; /**< how many times the jump should be repeated */
+ int do_jump_current_count; /**< how many times the jump has already been repeated */
};
struct mission_s
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index 34aaa30dd..85e8ef8a5 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -45,7 +45,6 @@
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-#include <navigator/navigator_state.h>
/**
* @addtogroup topics
@@ -74,6 +73,17 @@ struct position_setpoint_s
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
};
+typedef enum {
+ NAV_STATE_NONE_ON_GROUND = 0,
+ NAV_STATE_NONE_IN_AIR,
+ NAV_STATE_AUTO_ON_GROUND,
+ NAV_STATE_LOITER,
+ NAV_STATE_MISSION,
+ NAV_STATE_RTL,
+ NAV_STATE_LAND,
+ NAV_STATE_MAX
+} nav_state_t;
+
/**
* Global position setpoint triplet in WGS84 coordinates.
*
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index adcd028f0..cfab695f8 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -36,7 +36,7 @@
* Definition of the global fused WGS84 position uORB topic.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
@@ -66,16 +66,16 @@ struct vehicle_global_position_s {
bool global_valid; /**< true if position satisfies validity criteria of estimator */
bool baro_valid; /**< true if baro_alt is valid (vel_d is also valid in this case) */
- uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
+ uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
double lat; /**< Latitude in degrees */
double lon; /**< Longitude in degrees */
float alt; /**< Altitude AMSL in meters */
- float vel_n; /**< Ground north velocity, m/s */
- float vel_e; /**< Ground east velocity, m/s */
- float vel_d; /**< Ground downside velocity, m/s */
+ float vel_n; /**< Ground north velocity, m/s */
+ float vel_e; /**< Ground east velocity, m/s */
+ float vel_d; /**< Ground downside velocity, m/s */
float yaw; /**< Yaw in radians -PI..+PI. */
- float baro_alt; /**< Barometric altitude (not raw baro but fused with accelerometer) */
+ float baro_alt; /**< Barometric altitude (not raw baro but fused with accelerometer) */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 48af4c9e2..c1bd828d8 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -54,8 +54,6 @@
#include <stdbool.h>
#include "../uORB.h"
-#include <navigator/navigator_state.h>
-
/**
* @addtogroup topics @{
*/
@@ -93,6 +91,14 @@ typedef enum {
FAILSAFE_STATE_MAX
} failsafe_state_t;
+typedef enum {
+ NAVIGATION_STATE_NONE = 0,
+ NAVIGATION_STATE_MISSION,
+ NAVIGATION_STATE_LOITER,
+ NAVIGATION_STATE_RTL,
+ NAVIGATION_STATE_LAND
+} navigation_state_t;
+
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
@@ -152,8 +158,7 @@ struct vehicle_status_s {
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
main_state_t main_state; /**< main state machine */
- unsigned int set_nav_state; /**< set navigation state machine to specified value */
- uint64_t set_nav_state_timestamp; /**< timestamp of latest change of set_nav_state */
+ navigation_state_t set_nav_state; /**< set navigation state machine to specified value */
arming_state_t arming_state; /**< current arming state */
hil_state_t hil_state; /**< current hil state */
failsafe_state_t failsafe_state; /**< current failsafe state */