mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: no need to fabs() get_default_speed_down() as it does fabs already
This commit is contained in:
parent
9342ded2bb
commit
f7f63b715f
@ -1075,7 +1075,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
|
||||
climb_rate_or_thrust = (packet.thrust - 0.5f) * 2.0f * copter.wp_nav->get_default_speed_up();
|
||||
} else {
|
||||
// descend at up to WPNAV_SPEED_DN
|
||||
climb_rate_or_thrust = (0.5f - packet.thrust) * 2.0f * -fabsf(copter.wp_nav->get_default_speed_down());
|
||||
climb_rate_or_thrust = (0.5f - packet.thrust) * 2.0f * -copter.wp_nav->get_default_speed_down();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -820,7 +820,7 @@ void ModeGuided::angle_control_run()
|
||||
float climb_rate_cms = 0.0f;
|
||||
if (!guided_angle_state.use_thrust) {
|
||||
// constrain climb rate
|
||||
climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -fabsf(wp_nav->get_default_speed_down()), wp_nav->get_default_speed_up());
|
||||
climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up());
|
||||
|
||||
// get avoidance adjusted climb rate
|
||||
climb_rate_cms = get_avoidance_adjusted_climbrate(climb_rate_cms);
|
||||
|
Loading…
Reference in New Issue
Block a user