Sub: failsafe_xxx -> mainloop_failsafe_xxx

This commit is contained in:
Jacob Walser 2017-04-06 17:58:26 -04:00
parent 6a80fe3c22
commit 23c18335a3
4 changed files with 10 additions and 10 deletions

View File

@ -626,8 +626,8 @@ private:
void failsafe_terrain_check(); void failsafe_terrain_check();
void failsafe_terrain_set_status(bool data_ok); void failsafe_terrain_set_status(bool data_ok);
void failsafe_terrain_on_event(); void failsafe_terrain_on_event();
void failsafe_enable(); void mainloop_failsafe_enable();
void failsafe_disable(); void mainloop_failsafe_disable();
void fence_check(); void fence_check();
void fence_send_mavlink_status(mavlink_channel_t chan); void fence_send_mavlink_status(mavlink_channel_t chan);
bool set_mode(control_mode_t mode, mode_reason_t reason); bool set_mode(control_mode_t mode, mode_reason_t reason);
@ -769,7 +769,7 @@ private:
public: public:
void mavlink_delay_cb(); void mavlink_delay_cb();
void failsafe_check(); void mainloop_failsafe_check();
}; };
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;

View File

@ -11,7 +11,7 @@ static uint32_t failsafe_last_timestamp;
static bool in_failsafe; static bool in_failsafe;
// Enable mainloop lockup failsafe // Enable mainloop lockup failsafe
void Sub::failsafe_enable() void Sub::mainloop_failsafe_enable()
{ {
failsafe_enabled = true; failsafe_enabled = true;
failsafe_last_timestamp = micros(); failsafe_last_timestamp = micros();
@ -19,14 +19,14 @@ void Sub::failsafe_enable()
// Disable mainloop lockup failsafe // Disable mainloop lockup failsafe
// Used when we know we are going to delay the mainloop significantly. // Used when we know we are going to delay the mainloop significantly.
void Sub::failsafe_disable() void Sub::mainloop_failsafe_disable()
{ {
failsafe_enabled = false; failsafe_enabled = false;
} }
// This function is called from the core timer interrupt at 1kHz. // This function is called from the core timer interrupt at 1kHz.
// This checks that the mainloop is running, and has not locked up. // This checks that the mainloop is running, and has not locked up.
void Sub::failsafe_check() void Sub::mainloop_failsafe_check()
{ {
uint32_t tnow = AP_HAL::micros(); uint32_t tnow = AP_HAL::micros();

View File

@ -28,7 +28,7 @@ bool Sub::init_arm_motors(bool arming_from_gcs)
} }
// disable cpu failsafe because initialising everything takes a while // disable cpu failsafe because initialising everything takes a while
failsafe_disable(); mainloop_failsafe_disable();
// notify that arming will occur (we do this early to give plenty of warning) // notify that arming will occur (we do this early to give plenty of warning)
AP_Notify::flags.armed = true; AP_Notify::flags.armed = true;
@ -72,7 +72,7 @@ bool Sub::init_arm_motors(bool arming_from_gcs)
DataFlash.Log_Write_Mode(control_mode, control_mode_reason); DataFlash.Log_Write_Mode(control_mode, control_mode_reason);
// reenable failsafe // reenable failsafe
failsafe_enable(); mainloop_failsafe_enable();
// perf monitor ignores delay due to arming // perf monitor ignores delay due to arming
perf_ignore_this_loop(); perf_ignore_this_loop();

View File

@ -15,7 +15,7 @@ static void mavlink_delay_cb_static()
static void failsafe_check_static() static void failsafe_check_static()
{ {
sub.failsafe_check(); sub.mainloop_failsafe_check();
} }
void Sub::init_ardupilot() void Sub::init_ardupilot()
@ -189,7 +189,7 @@ void Sub::init_ardupilot()
serial_manager.set_blocking_writes_all(false); serial_manager.set_blocking_writes_all(false);
// enable CPU failsafe // enable CPU failsafe
failsafe_enable(); mainloop_failsafe_enable();
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
ins.set_dataflash(&DataFlash); ins.set_dataflash(&DataFlash);