mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: fix incorrect float conversion
This commit is contained in:
parent
49096422e7
commit
761c7a0161
|
@ -1062,7 +1062,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
|
|||
{
|
||||
// validate that the vehicle is at least the expected distance away from the loiter point
|
||||
// require an angle total of at least 2 centidegrees, due to special casing of 1 centidegree
|
||||
if (((fabsf(cmd.content.location.get_distance(current_loc) - abs_radius) > 5.0f) &&
|
||||
if (((fabsF(cmd.content.location.get_distance(current_loc) - abs_radius) > 5.0f) &&
|
||||
(cmd.content.location.get_distance(current_loc) < abs_radius)) ||
|
||||
(labs(loiter.sum_cd) < 2)) {
|
||||
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
|
||||
|
@ -1078,7 +1078,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
|
|||
const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));
|
||||
|
||||
// breakout when within 5 degrees of the opposite direction
|
||||
if (fabsf(wrap_PI(ahrs.yaw - breakout_direction_rad)) < radians(5.0f)) {
|
||||
if (fabsF(wrap_PI(ahrs.yaw - breakout_direction_rad)) < radians(5.0f)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");
|
||||
vtol_approach_s.approach_stage = APPROACH_LINE;
|
||||
set_next_WP(cmd.content.location);
|
||||
|
|
|
@ -195,7 +195,7 @@ void ModeQRTL::update_target_altitude()
|
|||
initially approach at RTL_ALT_CM, then drop down to QRTL_ALT based on maximum sink rate from TECS,
|
||||
giving time to lose speed before we transition
|
||||
*/
|
||||
const float radius = MAX(fabsf(plane.aparm.loiter_radius), fabsf(plane.g.rtl_radius));
|
||||
const float radius = MAX(fabsf(float(plane.aparm.loiter_radius)), fabsf(float(plane.g.rtl_radius)));
|
||||
const float rtl_alt_delta = MAX(0, plane.g.RTL_altitude_cm*0.01 - plane.quadplane.qrtl_alt);
|
||||
const float sink_time = rtl_alt_delta / MAX(0.6*plane.TECS_controller.get_max_sinkrate(), 1);
|
||||
const float sink_dist = plane.aparm.airspeed_cruise_cm * 0.01 * sink_time;
|
||||
|
@ -220,7 +220,7 @@ bool ModeQRTL::allows_throttle_nudging() const
|
|||
// Return the radius from destination at which pure VTOL flight should be used, no transition to FW
|
||||
float ModeQRTL::get_VTOL_return_radius() const
|
||||
{
|
||||
return MAX(fabsf(plane.aparm.loiter_radius), fabsf(plane.g.rtl_radius)) * 1.5;
|
||||
return MAX(fabsf(float(plane.aparm.loiter_radius)), fabsf(float(plane.g.rtl_radius))) * 1.5;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -58,7 +58,7 @@ void Plane::loiter_angle_update(void)
|
|||
}
|
||||
}
|
||||
if (terrain_status_ok &&
|
||||
fabsf(altitude_agl - target_altitude.terrain_alt_cm*0.01) < 5) {
|
||||
fabsF(altitude_agl - target_altitude.terrain_alt_cm*0.01) < 5) {
|
||||
reached_target_alt = true;
|
||||
} else
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue