mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Copter: inform dataflash of vehicle arm state
This commit is contained in:
parent
2c8a0a9123
commit
f9802204df
@ -137,6 +137,9 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
|
||||
return false;
|
||||
}
|
||||
|
||||
// let dataflash know that we're armed (it may open logs e.g.)
|
||||
DataFlash_Class::instance()->set_vehicle_armed(true);
|
||||
|
||||
// disable cpu failsafe because initialising everything takes a while
|
||||
failsafe_disable();
|
||||
|
||||
@ -254,6 +257,7 @@ void Copter::init_disarm_motors()
|
||||
if (!DataFlash.log_while_disarmed()) {
|
||||
DataFlash.EnableWrites(false);
|
||||
}
|
||||
DataFlash_Class::instance()->set_vehicle_armed(false);
|
||||
|
||||
// disable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
|
Loading…
Reference in New Issue
Block a user