mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove rangefinder support of control loops
The rangefinder handling doesn't handle sonar glitches like locking on to reflections very well. We will remove the rangefinder as an input to the controllers until we can do a more robust implementation.
This commit is contained in:
parent
3193ecc9af
commit
54bfd1f751
|
@ -94,10 +94,6 @@ void Sub::althold_run()
|
|||
if (ap.at_bottom) {
|
||||
pos_control.relax_alt_hold_controllers(); // clear velocity and position targets
|
||||
pos_control.set_alt_target(inertial_nav.get_altitude() + 10.0f); // set target to 10 cm above bottom
|
||||
} else if (rangefinder_alt_ok()) {
|
||||
// if rangefinder is ok, use surface tracking
|
||||
float target_climb_rate = get_surface_tracking_climb_rate(0, pos_control.get_alt_target(), G_Dt);
|
||||
pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
|
||||
}
|
||||
|
||||
// Detects a zero derivative
|
||||
|
|
|
@ -83,11 +83,6 @@ void Sub::circle_run()
|
|||
attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), circle_nav.get_yaw(), true, get_smoothing_gain());
|
||||
}
|
||||
|
||||
// adjust climb rate using rangefinder
|
||||
if (rangefinder_alt_ok()) {
|
||||
// if rangefinder is ok, use surface tracking
|
||||
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
// update altitude target and call position controller
|
||||
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt, false);
|
||||
pos_control.update_z_controller();
|
||||
|
|
|
@ -112,12 +112,6 @@ void Sub::poshold_run()
|
|||
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
|
||||
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
|
||||
// adjust climb rate using rangefinder
|
||||
if (rangefinder_alt_ok()) {
|
||||
// if rangefinder is ok, use surface tracking
|
||||
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
||||
// call z axis position controller
|
||||
if (ap.at_bottom) {
|
||||
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); // clear velocity and position targets, and integrator
|
||||
|
|
Loading…
Reference in New Issue