mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
ArduSub: DCM handles centrifugal correction application internally now
This commit is contained in:
parent
000b410daa
commit
f35a94a730
@ -126,8 +126,6 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// enable gps velocity based centrefugal force compensation
|
|
||||||
ahrs.set_correct_centrifugal(true);
|
|
||||||
hal.util->set_soft_armed(true);
|
hal.util->set_soft_armed(true);
|
||||||
|
|
||||||
// enable output to motors
|
// enable output to motors
|
||||||
@ -187,8 +185,6 @@ bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks
|
|||||||
|
|
||||||
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);
|
||||||
|
|
||||||
// clear input holds
|
// clear input holds
|
||||||
|
@ -688,8 +688,6 @@ void Sub::load_parameters()
|
|||||||
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