Plane: move enabled parameter into compass library

This commit is contained in:
Peter Barker 2019-03-24 14:27:03 +11:00 committed by Andrew Tridgell
parent 2040580ce7
commit 73707077b5
5 changed files with 8 additions and 30 deletions

View File

@ -198,7 +198,7 @@ void Plane::update_speed_height(void)
*/ */
void Plane::update_compass(void) void Plane::update_compass(void)
{ {
if (g.compass_enabled && compass.read()) { if (AP::compass().enabled() && compass.read()) {
ahrs.set_compass(&compass); ahrs.set_compass(&compass);
if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) { if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) {
logger.Write_Compass(); logger.Write_Compass();
@ -310,7 +310,7 @@ void Plane::one_second_loop()
void Plane::compass_save() void Plane::compass_save()
{ {
if (g.compass_enabled && if (AP::compass().enabled() &&
compass.get_learn_type() >= Compass::LEARN_INTERNAL && compass.get_learn_type() >= Compass::LEARN_INTERNAL &&
!hal.util->get_soft_armed()) { !hal.util->get_soft_armed()) {
/* /*
@ -388,7 +388,7 @@ void Plane::update_GPS_10Hz(void)
next_WP_loc = prev_WP_loc = home; next_WP_loc = prev_WP_loc = home;
if (g.compass_enabled) { if (AP::compass().enabled()) {
// Set compass declination automatically // Set compass declination automatically
const Location &loc = gps.location(); const Location &loc = gps.location();
compass.set_initial_location(loc.lat, loc.lng); compass.set_initial_location(loc.lat, loc.lng);

View File

@ -4,7 +4,7 @@
void GCS_Plane::update_vehicle_sensor_status_flags(void) void GCS_Plane::update_vehicle_sensor_status_flags(void)
{ {
// first what sensors/controllers we have // first what sensors/controllers we have
if (plane.g.compass_enabled) { if (AP::compass().enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
} }
@ -113,7 +113,7 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
AP_AHRS &ahrs = AP::ahrs(); AP_AHRS &ahrs = AP::ahrs();
const Compass &compass = AP::compass(); const Compass &compass = AP::compass();
if (plane.g.compass_enabled && compass.healthy() && ahrs.use_compass()) { if (AP::compass().enabled() && compass.healthy() && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG; control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
} }
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.is_healthy()) { if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.is_healthy()) {

View File

@ -760,13 +760,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: User // @User: User
GSCALAR(FBWB_min_altitude_cm, "ALT_HOLD_FBWCM", ALT_HOLD_FBW_CM), GSCALAR(FBWB_min_altitude_cm, "ALT_HOLD_FBWCM", ALT_HOLD_FBW_CM),
// @Param: MAG_ENABLE
// @DisplayName: Enable Compass
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
GSCALAR(compass_enabled, "MAG_ENABLE", 1),
// @Param: FLAP_IN_CHANNEL // @Param: FLAP_IN_CHANNEL
// @DisplayName: Flap input channel // @DisplayName: Flap input channel
// @Description: An RC input channel to use for flaps control. If this is set to a RC channel number then that channel will be used for manual flaps control. When enabled, the percentage of flaps is taken as the percentage travel from the TRIM value of the channel to the MIN value of the channel. A value above the TRIM values will give inverse flaps (spoilers). This option needs to be enabled in conjunction with a FUNCTION setting on an output channel to one of the flap functions. When a FLAP_IN_CHANNEL is combined with auto-flaps the higher of the two flap percentages is taken. // @Description: An RC input channel to use for flaps control. If this is set to a RC channel number then that channel will be used for manual flaps control. When enabled, the percentage of flaps is taken as the percentage travel from the TRIM value of the channel to the MIN value of the channel. A value above the TRIM values will give inverse flaps (spoilers). This option needs to be enabled in conjunction with a FUNCTION setting on an output channel to one of the flap functions. When a FLAP_IN_CHANNEL is combined with auto-flaps the higher of the two flap percentages is taken.

View File

@ -186,7 +186,7 @@ public:
k_param_imu = 130, // unused k_param_imu = 130, // unused
k_param_altitude_mix, // deprecated k_param_altitude_mix, // deprecated
k_param_compass_enabled, k_param_compass_enabled_deprecated,
k_param_compass, k_param_compass,
k_param_battery_monitoring, // unused k_param_battery_monitoring, // unused
k_param_volt_div_ratio, // unused k_param_volt_div_ratio, // unused
@ -461,7 +461,6 @@ public:
AP_Int8 hil_mode; AP_Int8 hil_mode;
#endif #endif
AP_Int8 compass_enabled;
AP_Int8 flap_1_percent; AP_Int8 flap_1_percent;
AP_Int8 flap_1_speed; AP_Int8 flap_1_speed;
AP_Int8 flap_2_percent; AP_Int8 flap_2_percent;

View File

@ -107,21 +107,7 @@ void Plane::init_ardupilot()
// initialise airspeed sensor // initialise airspeed sensor
airspeed.init(); airspeed.init();
if (g.compass_enabled==true) { AP::compass().init();
compass.init();
bool compass_ok = compass.read();
#if HIL_SUPPORT
if (g.hil_mode != 0) {
compass_ok = true;
}
#endif
if (!compass_ok) {
hal.console->printf("Compass initialisation failed!\n");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
}
}
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
// make optflow available to libraries // make optflow available to libraries