Browse Source

ArduSub: DCM handles centrifugal correction application internally now

gps-1.3.1
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
f35a94a730
  1. 4
      ArduSub/AP_Arming_Sub.cpp
  2. 2
      ArduSub/Parameters.cpp

4
ArduSub/AP_Arming_Sub.cpp

@ -126,8 +126,6 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks) @@ -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);
// enable output to motors
@ -187,8 +185,6 @@ bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks @@ -187,8 +185,6 @@ bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks
AP::logger().set_vehicle_armed(false);
// disable gps velocity based centrefugal force compensation
ahrs.set_correct_centrifugal(false);
hal.util->set_soft_armed(false);
// clear input holds

2
ArduSub/Parameters.cpp

@ -688,8 +688,6 @@ void Sub::load_parameters() @@ -688,8 +688,6 @@ void Sub::load_parameters()
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);
if (!g.format_version.load() ||

Loading…
Cancel
Save