mirror of https://github.com/ArduPilot/ardupilot
Rover: add param conversion from MAG_ENABLE to COMPASS_ENABLED
This commit is contained in:
parent
903be58436
commit
d794c0fe53
|
@ -63,7 +63,6 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void)
|
|||
}
|
||||
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
const Compass &compass = AP::compass();
|
||||
|
||||
if (AP::compass().enabled() && AP::compass().healthy(0) && ahrs.use_compass()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
|
|
|
@ -763,6 +763,8 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
|||
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
|
||||
{ Parameters::k_param_throttle_min_old, 0, AP_PARAM_INT8, "MOT_THR_MIN" },
|
||||
{ Parameters::k_param_throttle_max_old, 0, AP_PARAM_INT8, "MOT_THR_MAX" },
|
||||
|
||||
{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },
|
||||
};
|
||||
|
||||
void Rover::load_parameters(void)
|
||||
|
|
Loading…
Reference in New Issue