mirror of https://github.com/ArduPilot/ardupilot
Copter: compile warnings: float to double. print statements require doubles
This commit is contained in:
parent
896c86bcc6
commit
c8bc44fc6e
|
@ -156,7 +156,7 @@
|
|||
#endif
|
||||
|
||||
#ifndef SONAR_GAIN_DEFAULT
|
||||
# define SONAR_GAIN_DEFAULT 0.8 // gain for controlling how quickly sonar range adjusts target altitude (lower means slower reaction)
|
||||
# define SONAR_GAIN_DEFAULT 0.8f // gain for controlling how quickly sonar range adjusts target altitude (lower means slower reaction)
|
||||
#endif
|
||||
|
||||
#ifndef THR_SURFACE_TRACKING_VELZ_MAX
|
||||
|
@ -287,7 +287,7 @@
|
|||
|
||||
// arming check's maximum acceptable vector difference between internal and external compass after vectors are normalized to field length of 1.0
|
||||
#ifndef COMPASS_ACCEPTABLE_VECTOR_DIFF
|
||||
#define COMPASS_ACCEPTABLE_VECTOR_DIFF 0.75 // pre arm compass check will fail if internal vs external compass direction differ by more than 45 degrees
|
||||
#define COMPASS_ACCEPTABLE_VECTOR_DIFF 0.75f // pre arm compass check will fail if internal vs external compass direction differ by more than 45 degrees
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -641,8 +641,8 @@ static void poshold_get_wind_comp_lean_angles(int16_t &roll_angle, int16_t &pitc
|
|||
poshold.wind_comp_timer = 0;
|
||||
|
||||
// convert earth frame desired accelerations to body frame roll and pitch lean angles
|
||||
roll_angle = (float)fast_atan((-poshold.wind_comp_ef.x*ahrs.sin_yaw() + poshold.wind_comp_ef.y*ahrs.cos_yaw())/981)*(18000/M_PI);
|
||||
pitch_angle = (float)fast_atan(-(poshold.wind_comp_ef.x*ahrs.cos_yaw() + poshold.wind_comp_ef.y*ahrs.sin_yaw())/981)*(18000/M_PI);
|
||||
roll_angle = (float)fast_atan((-poshold.wind_comp_ef.x*ahrs.sin_yaw() + poshold.wind_comp_ef.y*ahrs.cos_yaw())/981)*(18000/(float)M_PI);
|
||||
pitch_angle = (float)fast_atan(-(poshold.wind_comp_ef.x*ahrs.cos_yaw() + poshold.wind_comp_ef.y*ahrs.sin_yaw())/981)*(18000/(float)M_PI);
|
||||
}
|
||||
|
||||
// poshold_roll_controller_to_pilot_override - initialises transition from a controller submode (brake or loiter) to a pilot override on roll axis
|
||||
|
|
|
@ -346,7 +346,7 @@ static bool pre_arm_checks(bool display_failure)
|
|||
|
||||
// check for unreasonable mag field length
|
||||
float mag_field = compass.get_field().length();
|
||||
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65 || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35) {
|
||||
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check mag field"));
|
||||
}
|
||||
|
|
|
@ -431,12 +431,12 @@ print_accel_offsets_and_scaling(void)
|
|||
const Vector3f &accel_offsets = ins.get_accel_offsets();
|
||||
const Vector3f &accel_scale = ins.get_accel_scale();
|
||||
cliSerial->printf_P(PSTR("A_off: %4.2f, %4.2f, %4.2f\nA_scale: %4.2f, %4.2f, %4.2f\n"),
|
||||
(float)accel_offsets.x, // Pitch
|
||||
(float)accel_offsets.y, // Roll
|
||||
(float)accel_offsets.z, // YAW
|
||||
(float)accel_scale.x, // Pitch
|
||||
(float)accel_scale.y, // Roll
|
||||
(float)accel_scale.z); // YAW
|
||||
(double)accel_offsets.x, // Pitch
|
||||
(double)accel_offsets.y, // Roll
|
||||
(double)accel_offsets.z, // YAW
|
||||
(double)accel_scale.x, // Pitch
|
||||
(double)accel_scale.y, // Roll
|
||||
(double)accel_scale.z); // YAW
|
||||
}
|
||||
|
||||
static void
|
||||
|
@ -444,9 +444,9 @@ print_gyro_offsets(void)
|
|||
{
|
||||
const Vector3f &gyro_offsets = ins.get_gyro_offsets();
|
||||
cliSerial->printf_P(PSTR("G_off: %4.2f, %4.2f, %4.2f\n"),
|
||||
(float)gyro_offsets.x,
|
||||
(float)gyro_offsets.y,
|
||||
(float)gyro_offsets.z);
|
||||
(double)gyro_offsets.x,
|
||||
(double)gyro_offsets.y,
|
||||
(double)gyro_offsets.z);
|
||||
}
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
@ -461,7 +461,7 @@ static void report_compass()
|
|||
|
||||
// mag declination
|
||||
cliSerial->printf_P(PSTR("Mag Dec: %4.4f\n"),
|
||||
degrees(compass.get_declination()));
|
||||
(double)degrees(compass.get_declination()));
|
||||
|
||||
// mag offsets
|
||||
Vector3f offsets;
|
||||
|
@ -470,9 +470,9 @@ static void report_compass()
|
|||
// mag offsets
|
||||
cliSerial->printf_P(PSTR("Mag%d off: %4.4f, %4.4f, %4.4f\n"),
|
||||
(int)i,
|
||||
offsets.x,
|
||||
offsets.y,
|
||||
offsets.z);
|
||||
(double)offsets.x,
|
||||
(double)offsets.y,
|
||||
(double)offsets.z);
|
||||
}
|
||||
|
||||
// motor compensation
|
||||
|
@ -491,9 +491,9 @@ static void report_compass()
|
|||
motor_compensation = compass.get_motor_compensation(i);
|
||||
cliSerial->printf_P(PSTR("\nComMot%d: %4.2f, %4.2f, %4.2f\n"),
|
||||
(int)i,
|
||||
motor_compensation.x,
|
||||
motor_compensation.y,
|
||||
motor_compensation.z);
|
||||
(double)motor_compensation.x,
|
||||
(double)motor_compensation.y,
|
||||
(double)motor_compensation.z);
|
||||
}
|
||||
}
|
||||
print_blanks(1);
|
||||
|
|
|
@ -63,9 +63,9 @@ test_baro(uint8_t argc, const Menu::arg *argv)
|
|||
cliSerial->println_P(PSTR("not healthy"));
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
|
||||
baro_alt / 100.0,
|
||||
barometer.get_pressure(),
|
||||
barometer.get_temperature());
|
||||
(double)(baro_alt / 100.0f),
|
||||
(double)barometer.get_pressure(),
|
||||
(double)barometer.get_temperature());
|
||||
}
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
|
@ -138,12 +138,12 @@ test_compass(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"));
|
||||
}
|
||||
|
@ -185,9 +185,9 @@ test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
float test = accel.length() / GRAVITY_MSS;
|
||||
|
||||
cliSerial->printf_P(PSTR("a %7.4f %7.4f %7.4f g %7.4f %7.4f %7.4f t %7.4f \n"),
|
||||
accel.x, accel.y, accel.z,
|
||||
gyro.x, gyro.y, gyro.z,
|
||||
test);
|
||||
(double)accel.x, (double)accel.y, (double)accel.z,
|
||||
(double)gyro.x, (double)gyro.y, (double)gyro.z,
|
||||
(double)test);
|
||||
|
||||
delay(40);
|
||||
if(cliSerial->available() > 0) {
|
||||
|
@ -209,8 +209,8 @@ test_optflow(uint8_t argc, const Menu::arg *argv)
|
|||
optflow.update();
|
||||
const Vector2f& flowRate = optflow.flowRate();
|
||||
cliSerial->printf_P(PSTR("flowX : %7.4f\t flowY : %7.4f\t flow qual : %d\n"),
|
||||
flowRate.x,
|
||||
flowRate.y,
|
||||
(double)flowRate.x,
|
||||
(double)flowRate.y,
|
||||
(int)optflow.quality());
|
||||
|
||||
if(cliSerial->available() > 0) {
|
||||
|
|
Loading…
Reference in New Issue