@ -42,7 +42,7 @@ public:
@@ -42,7 +42,7 @@ public:
// commands
virtual bool run_debug_shell ( AP_HAL : : BetterStream * stream ) = 0 ;
enum safety_state {
enum safety_state : uint8_t {
SAFETY_NONE , SAFETY_DISARMED , SAFETY_ARMED
} ;
@ -55,24 +55,25 @@ public:
@@ -55,24 +55,25 @@ public:
struct PersistentData {
float roll_rad , pitch_rad , yaw_rad ; // attitude
int32_t home_lat , home_lon , home_alt_cm ; // home position
bool armed ; // true if vehicle was armed
enum safety_state safety_state ;
uint32_t fault_addr ;
uint32_t fault_icsr ;
uint32_t fault_lr ;
uint32_t internal_errors ;
uint32_t internal_error_count ;
uint32_t spi_count ;
uint32_t i2c_count ;
uint32_t i2c_isr_count ;
uint16_t waypoint_num ;
int8_t scheduler_task ;
uint16_t last_mavlink_msgid ;
uint16_t last_mavlink_cmd ;
uint16_t semaphore_line ;
uint32_t spi_count ;
uint32_t i2c_count ;
uint32_t i2c_isr_count ;
uint16_t fault_line ;
uint8_t fault_type ;
uint8_t fault_thd_prio ;
uint32_t fault_addr ;
uint32_t fault_icsr ;
uint32_t fault_lr ;
char thread_name4 [ 4 ] ;
int8_t scheduler_task ;
bool armed ; // true if vehicle was armed
enum safety_state safety_state ;
} ;
struct PersistentData persistent_data ;
// last_persistent_data is only filled in if we've suffered a watchdog reset