mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
ArduCopter: DCM handles centrifugal correction application internally now
This commit is contained in:
parent
608608f32f
commit
000b410daa
@ -842,8 +842,6 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
|
|||||||
copter.g2.smart_rtl.set_home(copter.position_ok());
|
copter.g2.smart_rtl.set_home(copter.position_ok());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// enable gps velocity based centrefugal force compensation
|
|
||||||
ahrs.set_correct_centrifugal(true);
|
|
||||||
hal.util->set_soft_armed(true);
|
hal.util->set_soft_armed(true);
|
||||||
|
|
||||||
#if SPRAYER_ENABLED == ENABLED
|
#if SPRAYER_ENABLED == ENABLED
|
||||||
@ -941,8 +939,6 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
|
|||||||
|
|
||||||
AP::logger().set_vehicle_armed(false);
|
AP::logger().set_vehicle_armed(false);
|
||||||
|
|
||||||
// disable gps velocity based centrefugal force compensation
|
|
||||||
ahrs.set_correct_centrifugal(false);
|
|
||||||
hal.util->set_soft_armed(false);
|
hal.util->set_soft_armed(false);
|
||||||
|
|
||||||
copter.ap.in_arming_delay = false;
|
copter.ap.in_arming_delay = false;
|
||||||
|
@ -1166,8 +1166,6 @@ void Copter::load_parameters(void)
|
|||||||
AP_HAL::panic("Bad var table");
|
AP_HAL::panic("Bad var table");
|
||||||
}
|
}
|
||||||
|
|
||||||
// disable centrifugal force correction, it will be enabled as part of the arming process
|
|
||||||
ahrs.set_correct_centrifugal(false);
|
|
||||||
hal.util->set_soft_armed(false);
|
hal.util->set_soft_armed(false);
|
||||||
|
|
||||||
if (!g.format_version.load() ||
|
if (!g.format_version.load() ||
|
||||||
|
Loading…
Reference in New Issue
Block a user