APMrover2: compile warnings: float to double. print statements require doubles

This commit is contained in:
Tom Pittenger 2015-05-02 23:01:05 -07:00 committed by Andrew Tridgell
parent c4c47cba66
commit 928a5e0766
5 changed files with 22 additions and 22 deletions

View File

@ -828,7 +828,7 @@ static void update_current_mode(void)
// and throttle gives speed in proportion to cruise speed, up
// to 50% throttle, then uses nudging above that.
float target_speed = channel_throttle->pwm_to_angle() * 0.01 * 2 * g.speed_cruise;
float target_speed = channel_throttle->pwm_to_angle() * 0.01f * 2 * g.speed_cruise;
set_reverse(target_speed < 0);
if (in_reverse) {
target_speed = constrain_float(target_speed, -g.speed_cruise, 0);

View File

@ -677,7 +677,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
// parameter sends
if ((stream_num != STREAM_PARAMS) &&
(waypoint_receiving || _queued_parameter != NULL)) {
rate *= 0.25;
rate *= 0.25f;
}
if (rate <= 0) {

View File

@ -54,7 +54,7 @@ static void read_radio()
channel_throttle->servo_out = channel_throttle->control_in;
if (abs(channel_throttle->servo_out) > 50) {
throttle_nudge = (g.throttle_max - g.throttle_cruise) * ((fabsf(channel_throttle->norm_input())-0.5) / 0.5);
throttle_nudge = (g.throttle_max - g.throttle_cruise) * ((fabsf(channel_throttle->norm_input())-0.5f) / 0.5f);
} else {
throttle_nudge = 0;
}

View File

@ -88,7 +88,7 @@ setup_show(uint8_t argc, const Menu::arg *argv)
cliSerial->printf_P(PSTR("INT32 %s: %ld\n"), argv[1].str, (long)((AP_Int32 *)param)->get());
break;
case AP_PARAM_FLOAT:
cliSerial->printf_P(PSTR("FLOAT %s: %f\n"), argv[1].str, ((AP_Float *)param)->get());
cliSerial->printf_P(PSTR("FLOAT %s: %f\n"), argv[1].str, (double)((AP_Float *)param)->get());
break;
default:
cliSerial->printf_P(PSTR("Unhandled parameter type for %s: %d.\n"), argv[1].str, type);
@ -516,9 +516,9 @@ static void report_compass()
// mag offsets
cliSerial->printf_P(PSTR("Mag offsets: %4.4f, %4.4f, %4.4f\n"),
offsets.x,
offsets.y,
offsets.z);
(double)offsets.x,
(double)offsets.y,
(double)offsets.z);
print_blanks(2);
}
@ -542,9 +542,9 @@ static void
print_PID(PID * pid)
{
cliSerial->printf_P(PSTR("P: %4.3f, I:%4.3f, D:%4.3f, IMAX:%ld\n"),
pid->kP(),
pid->kI(),
pid->kD(),
(double)pid->kP(),
(double)pid->kI(),
(double)pid->kD(),
(long)pid->imax());
}

View File

@ -369,8 +369,8 @@ test_ins(uint8_t argc, const Menu::arg *argv)
(int)ahrs.roll_sensor / 100,
(int)ahrs.pitch_sensor / 100,
(uint16_t)ahrs.yaw_sensor / 100,
gyros.x, gyros.y, gyros.z,
accels.x, accels.y, accels.z);
(double)gyros.x, (double)gyros.y, (double)gyros.z,
(double)accels.x, (double)accels.y, (double)accels.z);
if(cliSerial->available() > 0){
return (0);
}
@ -430,8 +430,8 @@ test_mag(uint8_t argc, const Menu::arg *argv)
const Vector3f mag = compass.get_field();
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
(wrap_360_cd(ToDeg(heading) * 100)) /100,
mag.x, mag.y, mag.z,
mag_ofs.x, mag_ofs.y, mag_ofs.z);
(double)mag.x, (double)mag.y, (double)mag.z,
(double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z);
} else {
cliSerial->println_P(PSTR("compass not healthy"));
}
@ -502,14 +502,14 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
if (now - last_print >= 200) {
cliSerial->printf_P(PSTR("sonar1 dist=%.1f:%.1fcm volt1=%.2f:%.2f sonar2 dist=%.1f:%.1fcm volt2=%.2f:%.2f\n"),
sonar_dist_cm_min,
sonar_dist_cm_max,
voltage_min,
voltage_max,
sonar2_dist_cm_min,
sonar2_dist_cm_max,
voltage2_min,
voltage2_max);
(double)sonar_dist_cm_min,
(double)sonar_dist_cm_max,
(double)voltage_min,
(double)voltage_max,
(double)sonar2_dist_cm_min,
(double)sonar2_dist_cm_max,
(double)voltage2_min,
(double)voltage2_max);
voltage_min = voltage_max = 0.0f;
voltage2_min = voltage2_max = 0.0f;
sonar_dist_cm_min = sonar_dist_cm_max = 0.0f;