mirror of https://github.com/ArduPilot/ardupilot
fixed apm2beta build with AP_Param
This commit is contained in:
parent
16417b651e
commit
d4305e0ae2
|
@ -179,7 +179,7 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||||
AP_Baro_MS5611 barometer;
|
AP_Baro_MS5611 barometer;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_Compass_HMC5843 compass(Parameters::k_param_compass);
|
AP_Compass_HMC5843 compass;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OPTFLOW_ENABLED
|
#ifdef OPTFLOW_ENABLED
|
||||||
|
|
|
@ -1415,13 +1415,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition);
|
((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition);
|
||||||
} else if (var_type == AP_PARAM_INT16) {
|
} else if (var_type == AP_PARAM_INT16) {
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
Log_Write_Data(3, ((AP_Int16 *)vp)->get());
|
Log_Write_Data(3, (int32_t)((AP_Int16 *)vp)->get());
|
||||||
#endif
|
#endif
|
||||||
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
||||||
((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition);
|
((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition);
|
||||||
} else if (var_type == AP_PARAM_INT8) {
|
} else if (var_type == AP_PARAM_INT8) {
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
Log_Write_Data(4, ((AP_Int8 *)vp)->get());
|
Log_Write_Data(4, (int32_t)((AP_Int8 *)vp)->get());
|
||||||
#endif
|
#endif
|
||||||
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
||||||
((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition);
|
((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition);
|
||||||
|
|
Loading…
Reference in New Issue