mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added thread name to persistent data
this addes the first 4 bytes of the thread name to persistent data. It also re-arranges the data so that it is more efficiently packed, allowing us to fit the new field
This commit is contained in:
parent
ca16701823
commit
a25ea5addc
|
@ -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:
|
|||
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 internal_errors;
|
||||
uint32_t internal_error_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;
|
||||
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;
|
||||
uint16_t last_mavlink_msgid;
|
||||
uint16_t last_mavlink_cmd;
|
||||
uint16_t semaphore_line;
|
||||
uint16_t fault_line;
|
||||
uint8_t fault_type;
|
||||
uint8_t fault_thd_prio;
|
||||
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
|
||||
|
|
Loading…
Reference in New Issue