aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-29 21:21:16 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-29 21:27:44 +0100
commitcf6d89301b774ae019d1d2c089a30a8ed0d7308f (patch)
tree7e56739c95dedf53cfb0bae88e6ba65c88b661c8 /src/modules/uORB/topics
parent01c9092213449c761759bcda11ef9613226be713 (diff)
parent6f559b279e3d03dbf28eff436b41f3b022c5fa82 (diff)
downloadpx4-firmware-cf6d89301b774ae019d1d2c089a30a8ed0d7308f.tar.gz
px4-firmware-cf6d89301b774ae019d1d2c089a30a8ed0d7308f.tar.bz2
px4-firmware-cf6d89301b774ae019d1d2c089a30a8ed0d7308f.zip
Merge branch 'beta' into offboard2
Diffstat (limited to 'src/modules/uORB/topics')
-rw-r--r--src/modules/uORB/topics/home_position.h2
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h (renamed from src/modules/uORB/topics/mission_item_triplet.h)43
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h18
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h27
-rw-r--r--src/modules/uORB/topics/vehicle_status.h18
5 files changed, 60 insertions, 48 deletions
diff --git a/src/modules/uORB/topics/home_position.h b/src/modules/uORB/topics/home_position.h
index 3e2fee84e..08d11abae 100644
--- a/src/modules/uORB/topics/home_position.h
+++ b/src/modules/uORB/topics/home_position.h
@@ -62,7 +62,7 @@ struct home_position_s
//bool altitude_is_relative; // TODO what means home relative altitude? we need clear definition of reference altitude then
double lat; /**< Latitude in degrees */
double lon; /**< Longitude in degrees */
- float altitude; /**< Altitude in meters */
+ float alt; /**< Altitude in meters */
};
/**
diff --git a/src/modules/uORB/topics/mission_item_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index b35eae607..cf1ddfc38 100644
--- a/src/modules/uORB/topics/mission_item_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -45,32 +45,47 @@
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-
-#include "mission.h"
+#include <navigator/navigator_state.h>
/**
* @addtogroup topics
* @{
*/
+enum SETPOINT_TYPE
+{
+ SETPOINT_TYPE_NORMAL = 0, /**< normal setpoint */
+ SETPOINT_TYPE_LOITER, /**< loiter setpoint */
+ SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
+ SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, vehicle must descend until landing */
+ SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
+};
+
+struct position_setpoint_s
+{
+ bool valid; /**< true if setpoint is valid */
+ enum SETPOINT_TYPE type; /**< setpoint type to adjust behavior of position controller */
+ double lat; /**< latitude, in deg */
+ double lon; /**< longitude, in deg */
+ float alt; /**< altitude AMSL, in m */
+ float yaw; /**< yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw */
+ float loiter_radius; /**< loiter radius (only for fixed wing), in m */
+ int8_t loiter_direction; /**< loiter direction: 1 = CW, -1 = CCW */
+ float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
+};
+
/**
* Global position setpoint triplet in WGS84 coordinates.
*
* This are the three next waypoints (or just the next two or one).
*/
-struct mission_item_triplet_s
+struct position_setpoint_triplet_s
{
- bool previous_valid;
- bool current_valid; /**< flag indicating previous mission item is valid */
- bool next_valid; /**< flag indicating next mission item is valid */
-
- struct mission_item_s previous;
- struct mission_item_s current;
- struct mission_item_s next;
+ struct position_setpoint_s previous;
+ struct position_setpoint_s current;
+ struct position_setpoint_s next;
- int previous_index;
- int current_index;
- int next_index;
+ nav_state_t nav_state; /**< navigation state */
};
/**
@@ -78,6 +93,6 @@ struct mission_item_triplet_s
*/
/* register this as object request broker structure */
-ORB_DECLARE(mission_item_triplet);
+ORB_DECLARE(position_setpoint_triplet);
#endif
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 26dcbd985..7cbb37cd8 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -61,22 +61,10 @@
* Encodes the complete system state and is set by the commander app.
*/
-typedef enum {
- NAV_STATE_NONE = 0,
- NAV_STATE_READY,
- NAV_STATE_LOITER,
- NAV_STATE_MISSION,
- NAV_STATE_RTL,
- NAV_STATE_MAX
-} nav_state_t;
-
struct vehicle_control_mode_s
{
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
- main_state_t main_state;
- nav_state_t nav_state;
-
bool flag_armed;
bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
@@ -85,14 +73,14 @@ struct vehicle_control_mode_s
bool flag_system_hil_enabled;
bool flag_control_manual_enabled; /**< true if manual input is mixed in */
- bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ bool flag_control_auto_enabled; /**< true if onboard autopilot should act */
bool flag_control_rates_enabled; /**< true if rates are stabilized */
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
bool flag_control_position_enabled; /**< true if position is controlled */
bool flag_control_altitude_enabled; /**< true if altitude is controlled */
- bool flag_control_climb_rate_enabled; /**< true if climb rate is controlled */
- bool flag_control_flighttermination_enabled; /**< true if flighttermination is enabled */
+ bool flag_control_climb_rate_enabled; /**< true if climb rate is controlled */
+ bool flag_control_termination_enabled; /**< true if flighttermination is enabled */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index 143734e37..ff9e98e1c 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -54,25 +54,28 @@
/**
* Fused global position in WGS84.
*
- * This struct contains the system's believ about its position. It is not the raw GPS
+ * This struct contains global position estimation. It is not the raw GPS
* measurement (@see vehicle_gps_position). This topic is usually published by the position
* estimator, which will take more sources of information into account than just GPS,
* e.g. control inputs of the vehicle in a Kalman-filter implementation.
*/
struct vehicle_global_position_s
{
- uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
- uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
- bool valid; /**< true if position satisfies validity criteria of estimator */
+ uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
- int32_t lat; /**< Latitude in 1E7 degrees */
- int32_t lon; /**< Longitude in 1E7 degrees */
- float alt; /**< Altitude in meters */
- float relative_alt; /**< Altitude above home position in meters, */
- float vx; /**< Ground X velocity, m/s in NED */
- float vy; /**< Ground Y velocity, m/s in NED */
- float vz; /**< Ground Z velocity, m/s in NED */
- float yaw; /**< Compass heading in radians -PI..+PI. */
+ 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 */
+ 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 yaw; /**< Yaw in radians -PI..+PI. */
+
+ 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 d74b696bb..4aea1b083 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -54,6 +54,8 @@
#include <stdbool.h>
#include "../uORB.h"
+#include <navigator/navigator_state.h>
+
/**
* @addtogroup topics @{
*/
@@ -65,6 +67,7 @@ typedef enum {
MAIN_STATE_EASY,
MAIN_STATE_AUTO,
MAIN_STATE_OFFBOARD,
+ MAIN_STATE_MAX
} main_state_t;
typedef enum {
@@ -74,7 +77,8 @@ typedef enum {
ARMING_STATE_ARMED_ERROR,
ARMING_STATE_STANDBY_ERROR,
ARMING_STATE_REBOOT,
- ARMING_STATE_IN_AIR_RESTORE
+ ARMING_STATE_IN_AIR_RESTORE,
+ ARMING_STATE_MAX
} arming_state_t;
typedef enum {
@@ -83,9 +87,12 @@ typedef enum {
} hil_state_t;
typedef enum {
- FLIGHTTERMINATION_STATE_OFF = 0,
- FLIGHTTERMINATION_STATE_ON
-} flighttermination_state_t;
+ FAILSAFE_STATE_NORMAL = 0, /**< Normal operation */
+ FAILSAFE_STATE_RTL, /**< Return To Launch */
+ FAILSAFE_STATE_LAND, /**< Land without position control */
+ FAILSAFE_STATE_TERMINATION, /**< Disable motors and use parachute, can't be recovered */
+ FAILSAFE_STATE_MAX
+} failsafe_state_t;
typedef enum {
MODE_SWITCH_MANUAL = 0,
@@ -180,6 +187,7 @@ struct vehicle_status_s
uint64_t set_nav_state_timestamp; /**< timestamp of latest change of set_nav_state */
arming_state_t arming_state; /**< current arming state */
hil_state_t hil_state; /**< current hil state */
+ failsafe_state_t failsafe_state; /**< current failsafe state */
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
@@ -231,8 +239,6 @@ struct vehicle_status_s
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
-
- flighttermination_state_t flighttermination_state;
};
/**