mirror of https://github.com/ArduPilot/ardupilot
Copter: fix references to position error
This commit is contained in:
parent
7c14f4de0d
commit
a29e2d8920
|
@ -564,7 +564,7 @@ void Mode::land_run_vertical_control(bool pause_descent)
|
|||
const float precland_min_descent_speed = 10.0f;
|
||||
|
||||
float max_descent_speed = abs(g.land_speed)*0.5f;
|
||||
float land_slowdown = MAX(0.0f, pos_control->get_horizontal_error()*(max_descent_speed/precland_acceptable_error));
|
||||
float land_slowdown = MAX(0.0f, pos_control->get_pos_error_xy()*(max_descent_speed/precland_acceptable_error));
|
||||
cmb_rate = MIN(-precland_min_descent_speed, -max_descent_speed+land_slowdown);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -789,7 +789,7 @@ uint32_t ModeGuided::wp_distance() const
|
|||
return wp_nav->get_wp_distance_to_destination();
|
||||
break;
|
||||
case Guided_PosVel:
|
||||
return pos_control->get_distance_to_target();
|
||||
return pos_control->get_pos_error_xy();
|
||||
break;
|
||||
default:
|
||||
return 0;
|
||||
|
|
|
@ -288,6 +288,6 @@ bool ModeThrow::throw_height_good()
|
|||
bool ModeThrow::throw_position_good()
|
||||
{
|
||||
// check that our horizontal position error is within 50cm
|
||||
return (pos_control->get_horizontal_error() < 50.0f);
|
||||
return (pos_control->get_pos_error_xy() < 50.0f);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue