aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-06-21 14:26:40 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-06-21 14:26:40 +0200
commit164f19176e1eb0d5546a5a1b00392917e9a7b87c (patch)
treec632d043db38a11113a5737358826f621ec59441 /src/modules/uORB
parentda2f68a6a09395a8d02a5d39bd3e92d7d0d79911 (diff)
parente0c78e51e3a5768014c73bed5cd087830d602227 (diff)
downloadpx4-firmware-164f19176e1eb0d5546a5a1b00392917e9a7b87c.tar.gz
px4-firmware-164f19176e1eb0d5546a5a1b00392917e9a7b87c.tar.bz2
px4-firmware-164f19176e1eb0d5546a5a1b00392917e9a7b87c.zip
Merge branch 'navigator_rewrite' into dataman_state_nav_rewrite
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/topics/telemetry_status.h1
-rw-r--r--src/modules/uORB/topics/vehicle_status.h31
2 files changed, 16 insertions, 16 deletions
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index 76693c46e..e9e00d76c 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -57,6 +57,7 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
struct telemetry_status_s {
uint64_t timestamp;
+ uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
uint8_t rssi; /**< local signal strength */
uint8_t remote_rssi; /**< remote signal strength */
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 9390ff717..5dc46dacb 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -59,7 +59,9 @@
* @addtogroup topics @{
*/
-/* main state machine */
+/**
+ * Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link.
+ */
typedef enum {
MAIN_STATE_MANUAL = 0,
MAIN_STATE_ALTCTL,
@@ -89,27 +91,22 @@ typedef enum {
HIL_STATE_ON
} hil_state_t;
-typedef enum {
- FAILSAFE_STATE_NORMAL = 0, /**< Normal operation */
- FAILSAFE_STATE_RC_LOSS, /**< Return To Launch on remote control loss */
- FAILSAFE_STATE_DL_LOSS, /**< Return To Launch on datalink loss */
- FAILSAFE_STATE_LAND, /**< Land as safe as possible */
- FAILSAFE_STATE_TERMINATION, /**< Disable motors and use parachute, can't be recovered */
- FAILSAFE_STATE_MAX,
-} failsafe_state_t;
-
+/**
+ * Navigation state, i.e. "what should vehicle do".
+ */
typedef enum {
NAVIGATION_STATE_MANUAL = 0, /**< Manual mode */
- NAVIGATION_STATE_ACRO, /**< Acro mode */
NAVIGATION_STATE_ALTCTL, /**< Altitude control mode */
NAVIGATION_STATE_POSCTL, /**< Position control mode */
NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
- NAVIGATION_STATE_AUTO_RTL, /**< Auto RTL mode */
- NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS, /**< Auto failsafe on RC loss mode */
- NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS, /**< Auto failsafe on datalink loss mode */
+ NAVIGATION_STATE_AUTO_RTL, /**< Auto return to launch mode */
+ NAVIGATION_STATE_AUTO_RTGS, /**< Auto return to groundstation on data link loss */
+ NAVIGATION_STATE_ACRO, /**< Acro mode */
NAVIGATION_STATE_LAND, /**< Land mode */
+ NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
NAVIGATION_STATE_TERMINATION, /**< Termination mode */
+ NAVIGATION_STATE_MAX,
} navigation_state_t;
enum VEHICLE_MODE_FLAG {
@@ -171,10 +168,10 @@ 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 */
- navigation_state_t set_nav_state; /**< set navigation state machine to specified value */
+ navigation_state_t 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 */
+ bool failsafe; /**< true if system is in 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 */
@@ -199,6 +196,8 @@ struct vehicle_status_s {
bool rc_signal_lost; /**< true if RC reception lost */
bool rc_input_blocked; /**< set if RC input should be ignored */
+ bool data_link_lost; /**< datalink to GCS lost */
+
bool offboard_control_signal_found_once;
bool offboard_control_signal_lost;
bool offboard_control_signal_weak;