mirror of https://github.com/ArduPilot/ardupilot
SITL: fix compile warnings re float constants
This commit is contained in:
parent
1575abff63
commit
91476d78ae
|
@ -33,13 +33,13 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
|||
AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 2),
|
||||
AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 5),
|
||||
AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0),
|
||||
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.2),
|
||||
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.2f),
|
||||
AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
|
||||
AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 1),
|
||||
AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
|
||||
AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
|
||||
AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
|
||||
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0.2),
|
||||
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0.2f),
|
||||
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
|
||||
AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
|
||||
AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),
|
||||
|
@ -47,8 +47,8 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
|||
AP_GROUPINFO("SERVO_RATE", 16, SITL, servo_rate, 0),
|
||||
AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch, 0),
|
||||
AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
|
||||
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6),
|
||||
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5),
|
||||
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6f),
|
||||
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5f),
|
||||
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
|
||||
AP_GROUPINFO("BARO_DRIFT", 22, SITL, baro_drift, 0),
|
||||
AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
|
||||
|
|
Loading…
Reference in New Issue