aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/uORB/topics')
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h44
-rw-r--r--src/modules/uORB/topics/rc_channels.h19
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h5
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h2
-rw-r--r--src/modules/uORB/topics/vehicle_status.h5
5 files changed, 50 insertions, 25 deletions
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index a23d89cd2..910b8a623 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -64,22 +64,40 @@ struct manual_control_setpoint_s {
/**
* Any of the channels may not be available and be set to NaN
* to indicate that it does not contain valid data.
+ * The variable names follow the definition of the
+ * MANUAL_CONTROL mavlink message.
+ * The default range is from -1 to 1 (mavlink message -1000 to 1000)
+ * The range for the z variable is defined from 0 to 1. (The z field of
+ * the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
*/
- float roll; /**< ailerons roll / roll rate input, -1..1 */
- float pitch; /**< elevator / pitch / pitch rate, -1..1 */
- float yaw; /**< rudder / yaw rate / yaw, -1..1 */
- float throttle; /**< throttle / collective thrust / altitude, 0..1 */
+ float x; /**< stick position in x direction -1..1
+ in general corresponds to forward/back motion or pitch of vehicle,
+ in general a positive value means forward or negative pitch and
+ a negative value means backward or positive pitch */
+ float y; /**< stick position in y direction -1..1
+ in general corresponds to right/left motion or roll of vehicle,
+ in general a positive value means right or positive roll and
+ a negative value means left or negative roll */
+ float z; /**< throttle stick position 0..1
+ in general corresponds to up/down motion or thrust of vehicle,
+ in general the value corresponds to the demanded throttle by the user,
+ if the input is used for setting the setpoint of a vertical position
+ controller any value > 0.5 means up and any value < 0.5 means down */
+ float r; /**< yaw stick/twist positon, -1..1
+ in general corresponds to the righthand rotation around the vertical
+ (downwards) axis of the vehicle */
float flaps; /**< flap position */
- float aux1; /**< default function: camera yaw / azimuth */
- float aux2; /**< default function: camera pitch / tilt */
- float aux3; /**< default function: camera trigger */
- float aux4; /**< default function: camera roll */
- float aux5; /**< default function: payload drop */
+ float aux1; /**< default function: camera yaw / azimuth */
+ float aux2; /**< default function: camera pitch / tilt */
+ float aux3; /**< default function: camera trigger */
+ float aux4; /**< default function: camera roll */
+ float aux5; /**< default function: payload drop */
- switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
- switch_pos_t return_switch; /**< land 2 position switch (mandatory): land, no effect */
- switch_pos_t assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
- switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
+ switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */
+ switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
+ switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
+ switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
+ switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
}; /**< manual control inputs */
/**
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index c168b2fac..370c54442 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -45,12 +45,12 @@
/**
* The number of RC channel inputs supported.
* Current (Q4/2013) radios support up to 18 channels,
- * leaving at a sane value of 15.
+ * leaving at a sane value of 16.
* This number can be greater then number of RC channels,
* because single RC channel can be mapped to multiple
* functions, e.g. for various mode switches.
*/
-#define RC_CHANNELS_MAPPED_MAX 15
+#define RC_CHANNELS_MAPPED_MAX 16
/**
* This defines the mapping of the RC functions.
@@ -64,15 +64,16 @@ enum RC_CHANNELS_FUNCTION {
YAW = 3,
MODE = 4,
RETURN = 5,
- ASSISTED = 6,
+ POSCTL = 6,
LOITER = 7,
OFFBOARD_MODE = 8,
- FLAPS = 9,
- AUX_1 = 10,
- AUX_2 = 11,
- AUX_3 = 12,
- AUX_4 = 13,
- AUX_5 = 14,
+ ACRO = 9,
+ FLAPS = 10,
+ AUX_1 = 11,
+ AUX_2 = 12,
+ AUX_3 = 13,
+ AUX_4 = 14,
+ AUX_5 = 15,
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index a75810278..bbacb733a 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -68,6 +68,9 @@ struct vehicle_gps_position_s {
float eph; /**< GPS HDOP horizontal dilution of position in m */
float epv; /**< GPS VDOP horizontal dilution of position in m */
+ unsigned noise_per_ms; /**< */
+ unsigned jamming_indicator; /**< */
+
uint64_t timestamp_velocity; /**< Timestamp for velocity informations */
float vel_m_s; /**< GPS ground speed (m/s) */
float vel_n_m_s; /**< GPS ground speed in m/s */
@@ -85,7 +88,7 @@ struct vehicle_gps_position_s {
uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
- uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */
+ uint8_t satellite_snr[20]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
bool satellite_info_available; /**< 0 for no info, 1 for info available */
};
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index a15303ea4..5d39c897d 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -83,6 +83,8 @@ struct vehicle_local_position_s {
float dist_bottom_rate; /**< Distance to bottom surface (ground) change rate */
uint64_t surface_bottom_timestamp; /**< Time when new bottom surface found */
bool dist_bottom_valid; /**< true if distance to bottom surface is valid */
+ float eph;
+ float epv;
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index c6fe937ef..d902dc49e 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -61,9 +61,10 @@
/* main state machine */
typedef enum {
MAIN_STATE_MANUAL = 0,
- MAIN_STATE_SEATBELT,
- MAIN_STATE_EASY,
+ MAIN_STATE_ALTCTL,
+ MAIN_STATE_POSCTL,
MAIN_STATE_AUTO,
+ MAIN_STATE_ACRO,
MAIN_STATE_MAX
} main_state_t;