aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-12-27 18:27:08 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-12-27 18:27:08 +0100
commitf5bad08bd0f4e0f6506deeac9d369b2b9c2d9e32 (patch)
tree9da695a79082b70360260c669f27ff8fa4470b35 /apps/uORB
parent61d7e1d28552ddd7652b1d1b888c51a2eae78967 (diff)
downloadpx4-firmware-f5bad08bd0f4e0f6506deeac9d369b2b9c2d9e32.tar.gz
px4-firmware-f5bad08bd0f4e0f6506deeac9d369b2b9c2d9e32.tar.bz2
px4-firmware-f5bad08bd0f4e0f6506deeac9d369b2b9c2d9e32.zip
Cleaned up control mode state machine / flight mode / navigation state machine still needs a bit cleaning up
Diffstat (limited to 'apps/uORB')
-rw-r--r--apps/uORB/topics/manual_control_setpoint.h40
-rw-r--r--apps/uORB/topics/rc_channels.h34
-rw-r--r--apps/uORB/topics/vehicle_status.h33
3 files changed, 63 insertions, 44 deletions
diff --git a/apps/uORB/topics/manual_control_setpoint.h b/apps/uORB/topics/manual_control_setpoint.h
index 1368cb716..261a8a4ad 100644
--- a/apps/uORB/topics/manual_control_setpoint.h
+++ b/apps/uORB/topics/manual_control_setpoint.h
@@ -48,29 +48,33 @@
* @{
*/
-enum MANUAL_CONTROL_MODE
-{
- MANUAL_CONTROL_MODE_DIRECT = 0,
- MANUAL_CONTROL_MODE_ATT_YAW_RATE = 1,
- MANUAL_CONTROL_MODE_ATT_YAW_POS = 2,
- MANUAL_CONTROL_MODE_MULTIROTOR_SIMPLE = 3 /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
-};
-
struct manual_control_setpoint_s {
uint64_t timestamp;
- enum MANUAL_CONTROL_MODE mode; /**< The current control inputs mode */
- float roll; /**< ailerons roll / roll rate input */
- float pitch; /**< elevator / pitch / pitch rate */
- float yaw; /**< rudder / yaw rate / yaw */
- float throttle; /**< throttle / collective thrust / altitude */
+ float roll; /**< ailerons roll / roll rate input */
+ float pitch; /**< elevator / pitch / pitch rate */
+ float yaw; /**< rudder / yaw rate / yaw */
+ float throttle; /**< throttle / collective thrust / altitude */
+
+ float manual_override_switch; /**< manual override mode (mandatory) */
+ float auto_mode_switch; /**< auto mode switch (mandatory) */
+
+ /**
+ * Any of the channels below may not be available and be set to NaN
+ * to indicate that it does not contain valid data.
+ */
+ float manual_mode_switch; /**< manual mode (man, sas, alt) switch (optional) */
+ float manual_sas_switch; /**< sas mode (rates / attitude) switch (optional) */
+ float return_to_launch_switch; /**< return to launch switch (0 = disabled, 1 = enabled) */
+ float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
- float override_mode_switch;
+ float flaps; /**< flap position */
- float aux1_cam_pan_flaps;
- float aux2_cam_tilt;
- float aux3_cam_zoom;
- float aux4_cam_roll;
+ 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 */
}; /**< manual control inputs */
diff --git a/apps/uORB/topics/rc_channels.h b/apps/uORB/topics/rc_channels.h
index fef6ef2b3..9dd54df91 100644
--- a/apps/uORB/topics/rc_channels.h
+++ b/apps/uORB/topics/rc_channels.h
@@ -50,6 +50,13 @@
* @{
*/
+/**
+ * The number of RC channel inputs supported.
+ * Current (Q1/2013) radios support up to 18 channels,
+ * leaving at a sane value of 14.
+ */
+#define RC_CHANNELS_MAX 14
+
/**
* This defines the mapping of the RC functions.
* The value assigned to the specific function corresponds to the entry of
@@ -62,14 +69,18 @@ enum RC_CHANNELS_FUNCTION
PITCH = 2,
YAW = 3,
OVERRIDE = 4,
- FUNC_0 = 5,
- FUNC_1 = 6,
- FUNC_2 = 7,
- FUNC_3 = 8,
- FUNC_4 = 9,
- FUNC_5 = 10,
- FUNC_6 = 11,
- RC_CHANNELS_FUNCTION_MAX = 12
+ AUTO_MODE = 5,
+ MANUAL_MODE = 6,
+ SAS_MODE = 7,
+ RTL = 8,
+ OFFBOARD_MODE = 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. */
};
struct rc_channels_s {
@@ -78,14 +89,13 @@ struct rc_channels_s {
uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
struct {
float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
- } chan[RC_CHANNELS_FUNCTION_MAX];
- uint8_t chan_count; /**< maximum number of valid channels */
+ } chan[RC_CHANNELS_MAX];
+ uint8_t chan_count; /**< number of valid channels */
/*String array to store the names of the functions*/
char function_name[RC_CHANNELS_FUNCTION_MAX][20];
- uint8_t function[RC_CHANNELS_FUNCTION_MAX];
+ int8_t function[RC_CHANNELS_FUNCTION_MAX];
uint8_t rssi; /**< Overall receive signal strength */
- bool is_valid; /**< Inputs are valid, no timeout */
}; /**< radio control channels. */
/**
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index 738ca644f..ed3fed1ab 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -87,16 +87,23 @@ enum VEHICLE_MODE_FLAG {
}; /**< Same as MAV_MODE_FLAG of MAVLink 1.0 protocol */
enum VEHICLE_FLIGHT_MODE {
- VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, same as VEHICLE_FLIGHT_MODE_ATTITUDE for multirotors */
- VEHICLE_FLIGHT_MODE_ATTITUDE, /**< attitude or rate stabilization, as defined by VEHICLE_ATTITUDE_MODE */
- VEHICLE_FLIGHT_MODE_STABILIZED, /**< attitude or rate stabilization plus velocity or position stabilization */
- VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */
+ VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, exact mode determined by VEHICLE_MANUAL_CONTROL_MODE */
+ VEHICLE_FLIGHT_MODE_STAB, /**< attitude or rate stabilization plus velocity or position stabilization */
+ VEHICLE_FLIGHT_MODE_HOLD, /**< hold current position (hover or loiter around position when switched) */
+ VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */
};
-enum VEHICLE_ATTITUDE_MODE {
- VEHICLE_ATTITUDE_MODE_DIRECT, /**< no attitude control, direct stick input mixing (only fixed wing) */
- VEHICLE_ATTITUDE_MODE_RATES, /**< body rates control mode */
- VEHICLE_ATTITUDE_MODE_ATTITUDE /**< tait-bryan attitude control mode */
+enum VEHICLE_MANUAL_CONTROL_MODE {
+ VEHICLE_MANUAL_CONTROL_MODE_DIRECT = 0, /**< no attitude control, direct stick input mixing (only fixed wing) */
+ VEHICLE_MANUAL_CONTROL_MODE_RATES, /**< body rates control mode */
+ VEHICLE_MANUAL_CONTROL_MODE_SAS /**< stability augmented system (SAS) mode */
+};
+
+enum VEHICLE_MANUAL_SAS_MODE {
+ VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS = 0, /**< roll, pitch and yaw absolute */
+ VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE, /**< roll and pitch absolute, yaw rate */
+ VEHICLE_MANUAL_SAS_MODE_SIMPLE, /**< simple mode (includes altitude hold) */
+ VEHICLE_MANUAL_SAS_MODE_ALTITUDE /**< altitude hold */
};
/**
@@ -115,12 +122,10 @@ struct vehicle_status_s
commander_state_machine_t state_machine; /**< current flight state, main state machine */
enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
- enum VEHICLE_ATTITUDE_MODE attitute_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
+ enum VEHICLE_MANUAL_CONTROL_MODE manual_control_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
+ enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode; /**< current stabilization mode */
int32_t system_type; /**< system type, inspired by MAVLinks MAV_TYPE enum */
- // uint8_t mode;
-
-
/* system flags - these represent the state predicates */
bool flag_system_armed; /**< true is motors / actuators are armed */
@@ -165,11 +170,11 @@ struct vehicle_status_s
uint16_t errors_count3;
uint16_t errors_count4;
-// bool remote_manual; /**< set to true by the commander when the manual-switch on the remote is set to manual */
bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
bool flag_local_position_valid;
bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
- bool flag_external_manual_override_ok;
+ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
+ bool flag_valid_launch_position; /**< indicates a valid launch position */
};
/**