Browse Source

AP_Tuning: fixed float->double promotion compiler warning

mission-4.1.18
Tom Pittenger 9 years ago
parent
commit
d55401aa18
  1. 4
      libraries/AP_Tuning/AP_Tuning.cpp

4
libraries/AP_Tuning/AP_Tuning.cpp

@ -214,8 +214,8 @@ void AP_Tuning::Log_Write_Parameter_Tuning(float value) @@ -214,8 +214,8 @@ void AP_Tuning::Log_Write_Parameter_Tuning(float value)
AP_HAL::micros64(),
parmset,
current_parm,
value,
center_value);
(double)value,
(double)center_value);
}
/*

Loading…
Cancel
Save