AP_HAL: added save/restore of attitude in backup registers

This commit is contained in:
Andrew Tridgell 2019-04-21 13:08:29 +10:00
parent 508aae8f2a
commit c63459c237
1 changed files with 6 additions and 0 deletions

View File

@ -29,6 +29,12 @@ public:
// backup home state for restore on watchdog reset
virtual bool get_backup_home_state(int32_t &lat, int32_t &lon, int32_t &alt_cm) const { return false; }
// backup atttude for restore on watchdog reset
virtual void set_backup_attitude(int32_t roll_cd, int32_t pitch_cd, int32_t yaw_cd) const {}
// get watchdog reset attitude
virtual bool get_backup_attitude(int32_t &roll_cd, int32_t &pitch_cd, int32_t &yaw_cd) const { return false; }
virtual const char* get_custom_log_directory() const { return nullptr; }
virtual const char* get_custom_terrain_directory() const { return nullptr; }
virtual const char *get_custom_storage_directory() const { return nullptr; }