Sub: no need to fabs() get_default_speed_down() as it does fabs already

This commit is contained in:
Andrew Tridgell 2021-09-07 12:53:02 +10:00
parent aad82c1089
commit 88a1a0e861
2 changed files with 2 additions and 2 deletions

View File

@ -576,7 +576,7 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_up(); climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_up();
} else { } else {
// descend at up to WPNAV_SPEED_DN // descend at up to WPNAV_SPEED_DN
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * fabsf(sub.wp_nav.get_default_speed_down()); climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_default_speed_down();
} }
sub.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]), climb_rate_cms); sub.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]), climb_rate_cms);
break; break;

View File

@ -481,7 +481,7 @@ void Sub::guided_angle_control_run()
float yaw_in = wrap_180_cd(guided_angle_state.yaw_cd); float yaw_in = wrap_180_cd(guided_angle_state.yaw_cd);
// constrain climb rate // constrain climb rate
float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -fabsf(wp_nav.get_default_speed_down()), wp_nav.get_default_speed_up()); float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -wp_nav.get_default_speed_down(), wp_nav.get_default_speed_up());
// check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds // check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds
uint32_t tnow = AP_HAL::millis(); uint32_t tnow = AP_HAL::millis();