mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 07:53:57 -04:00
Plane: Fix compile warnings
- const values declared as default double - This is the first pass in fixing the warnings, trying to catch some low hanging fruit. All const double values are changed to float. For example: 1.0 is now 1.0f. - Only except is in location.pde where some double stuff is happening - I did not change the exponentials 1e7 type stuff which should be 1e7f. A different commit
This commit is contained in:
parent
1f58cb9980
commit
bd9b573969
@ -396,7 +396,7 @@ static struct {
|
||||
// This is used to scale GPS values for EEPROM storage
|
||||
// 10^7 times Decimal GPS means 1 == 1cm
|
||||
// This approximation makes calculations integer and it's easy to read
|
||||
static const float t7 = 10000000.0;
|
||||
static const float t7 = 10000000.0f;
|
||||
// We use atan2 and other trig techniques to calaculate angles
|
||||
// A counter used to count down valid gps fixes to allow the gps estimate to settle
|
||||
// before recording our home position (and executing a ground start if we booted with an air start)
|
||||
|
@ -22,7 +22,7 @@ static float get_speed_scaler(void)
|
||||
} else {
|
||||
speed_scaler = 2.0;
|
||||
}
|
||||
speed_scaler = constrain_float(speed_scaler, 0.5, 2.0);
|
||||
speed_scaler = constrain_float(speed_scaler, 0.5f, 2.0f);
|
||||
} else {
|
||||
if (channel_throttle->servo_out > 0) {
|
||||
speed_scaler = 0.5f + ((float)THROTTLE_CRUISE / channel_throttle->servo_out / 2.0f); // First order taylor expansion of square root
|
||||
@ -31,7 +31,7 @@ static float get_speed_scaler(void)
|
||||
speed_scaler = 1.67f;
|
||||
}
|
||||
// This case is constrained tighter as we don't have real speed info
|
||||
speed_scaler = constrain_float(speed_scaler, 0.6, 1.67);
|
||||
speed_scaler = constrain_float(speed_scaler, 0.6f, 1.67f);
|
||||
}
|
||||
return speed_scaler;
|
||||
}
|
||||
@ -588,7 +588,7 @@ static bool suppress_throttle(void)
|
||||
// we're more than 10m from the home altitude
|
||||
throttle_suppressed = false;
|
||||
gcs_send_text_fmt(PSTR("Throttle unsuppressed - altitude %.2f"),
|
||||
relative_altitude_abs_cm()*0.01f);
|
||||
(float)(relative_altitude_abs_cm()*0.01f));
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -109,7 +109,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
|
||||
chan,
|
||||
millis(),
|
||||
ahrs.roll,
|
||||
ahrs.pitch - radians(g.pitch_trim_cd*0.01),
|
||||
ahrs.pitch - radians(g.pitch_trim_cd*0.01f),
|
||||
ahrs.yaw,
|
||||
omega.x,
|
||||
omega.y,
|
||||
@ -341,12 +341,12 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_nav_controller_output_send(
|
||||
chan,
|
||||
nav_roll_cd * 0.01,
|
||||
nav_pitch_cd * 0.01,
|
||||
nav_roll_cd * 0.01f,
|
||||
nav_pitch_cd * 0.01f,
|
||||
nav_controller->nav_bearing_cd() * 0.01f,
|
||||
nav_controller->target_bearing_cd() * 0.01f,
|
||||
auto_state.wp_distance,
|
||||
altitude_error_cm * 0.01,
|
||||
altitude_error_cm * 0.01f,
|
||||
airspeed_error_cm,
|
||||
nav_controller->crosstrack_error());
|
||||
}
|
||||
@ -417,7 +417,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
gps.ground_speed(),
|
||||
(ahrs.yaw_sensor / 100) % 360,
|
||||
throttle_percentage(),
|
||||
current_loc.alt / 100.0,
|
||||
current_loc.alt / 100.0f,
|
||||
barometer.get_climb_rate());
|
||||
}
|
||||
|
||||
|
@ -500,7 +500,6 @@ static void Log_Write_Performance() {}
|
||||
static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) {}
|
||||
static void Log_Write_Attitude() {}
|
||||
static void Log_Write_Control_Tuning() {}
|
||||
static void Log_Write_Mode(uint8_t mode) {}
|
||||
static void Log_Write_GPS(uint8_t instance) {}
|
||||
static void Log_Write_IMU() {}
|
||||
static void Log_Write_RC() {}
|
||||
|
@ -442,7 +442,7 @@ static float height_above_target(void)
|
||||
{
|
||||
float target_alt = next_WP_loc.alt*0.01;
|
||||
if (!next_WP_loc.flags.relative_alt) {
|
||||
target_alt -= ahrs.get_home().alt*0.01;
|
||||
target_alt -= ahrs.get_home().alt*0.01f;
|
||||
}
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
|
@ -386,7 +386,7 @@ static bool verify_takeoff()
|
||||
// course. This keeps wings level until we are ready to
|
||||
// rotate, and also allows us to cope with arbitary
|
||||
// compass errors for auto takeoff
|
||||
float takeoff_course = wrap_PI(radians(gps.ground_course_cd()*0.01)) - steer_state.locked_course_err;
|
||||
float takeoff_course = wrap_PI(radians(gps.ground_course_cd()*0.01f)) - steer_state.locked_course_err;
|
||||
takeoff_course = wrap_PI(takeoff_course);
|
||||
steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100);
|
||||
gcs_send_text_fmt(PSTR("Holding course %ld at %.1fm/s (%.1f)"),
|
||||
@ -531,10 +531,10 @@ static bool verify_continue_and_change_alt()
|
||||
}
|
||||
|
||||
// Is the next_WP less than 200 m away?
|
||||
if (get_distance(current_loc, next_WP_loc) < 200.f) {
|
||||
if (get_distance(current_loc, next_WP_loc) < 200.0f) {
|
||||
//push another 300 m down the line
|
||||
int32_t next_wp_bearing_cd = get_bearing_cd(prev_WP_loc, next_WP_loc);
|
||||
location_update(next_WP_loc, next_wp_bearing_cd * 0.01f, 300.f);
|
||||
location_update(next_WP_loc, next_wp_bearing_cd * 0.01f, 300.0f);
|
||||
}
|
||||
|
||||
//keep flying the same course
|
||||
|
@ -323,7 +323,7 @@
|
||||
#define PITCH_MIN_CENTIDEGREE PITCH_MIN * 100
|
||||
|
||||
#ifndef RUDDER_MIX
|
||||
# define RUDDER_MIX 0.5
|
||||
# define RUDDER_MIX 0.5f
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -237,7 +237,7 @@ static bool geofence_check_minalt(void)
|
||||
if (g.fence_minalt == 0) {
|
||||
return false;
|
||||
}
|
||||
return (adjusted_altitude_cm() < (g.fence_minalt*100.0) + home.alt);
|
||||
return (adjusted_altitude_cm() < (g.fence_minalt*100.0f) + home.alt);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -251,7 +251,7 @@ static bool geofence_check_maxalt(void)
|
||||
if (g.fence_maxalt == 0) {
|
||||
return false;
|
||||
}
|
||||
return (adjusted_altitude_cm() > (g.fence_maxalt*100.0) + home.alt);
|
||||
return (adjusted_altitude_cm() > (g.fence_maxalt*100.0f) + home.alt);
|
||||
}
|
||||
|
||||
|
||||
@ -361,14 +361,14 @@ static void geofence_check(bool altitude_check_only)
|
||||
} else { //return to fence return point, not a rally point
|
||||
if (g.fence_retalt > 0) {
|
||||
//fly to the return point using fence_retalt
|
||||
guided_WP_loc.alt = home.alt + 100.0*g.fence_retalt;
|
||||
guided_WP_loc.alt = home.alt + 100.0f*g.fence_retalt;
|
||||
} else if (g.fence_minalt >= g.fence_maxalt) {
|
||||
// invalid min/max, use RTL_altitude
|
||||
guided_WP_loc.alt = home.alt + g.RTL_altitude_cm;
|
||||
} else {
|
||||
// fly to the return point, with an altitude half way between
|
||||
// min and max
|
||||
guided_WP_loc.alt = home.alt + 100.0*(g.fence_minalt + g.fence_maxalt)/2;
|
||||
guided_WP_loc.alt = home.alt + 100.0f*(g.fence_minalt + g.fence_maxalt)/2;
|
||||
}
|
||||
guided_WP_loc.options = 0;
|
||||
guided_WP_loc.lat = geofence_state->boundary[0].x;
|
||||
|
@ -37,7 +37,7 @@ static bool auto_takeoff_check(void)
|
||||
|
||||
// Check for launch acceleration or timer started. NOTE: relies on TECS 50Hz processing
|
||||
if (!launchTimerStarted &&
|
||||
g.takeoff_throttle_min_accel != 0.0 &&
|
||||
g.takeoff_throttle_min_accel != 0.0f &&
|
||||
SpdHgt_Controller->get_VXdot() < g.takeoff_throttle_min_accel) {
|
||||
goto no_launch;
|
||||
}
|
||||
@ -65,7 +65,7 @@ static bool auto_takeoff_check(void)
|
||||
}
|
||||
|
||||
// Check ground speed and time delay
|
||||
if (((gps.ground_speed() > g.takeoff_throttle_min_speed || g.takeoff_throttle_min_speed == 0.0)) &&
|
||||
if (((gps.ground_speed() > g.takeoff_throttle_min_speed || g.takeoff_throttle_min_speed == 0.0f)) &&
|
||||
((now - last_tkoff_arm_time) >= wait_time_ms)) {
|
||||
gcs_send_text_fmt(PSTR("Triggered AUTO, GPSspd = %.1f"), gps.ground_speed());
|
||||
launchTimerStarted = false;
|
||||
|
Loading…
Reference in New Issue
Block a user