Copter: move enabled parameter into compass library
This commit is contained in:
parent
39db4eb871
commit
2040580ce7
@ -305,7 +305,7 @@ void Copter::update_batt_compass(void)
|
|||||||
// read battery before compass because it may be used for motor interference compensation
|
// read battery before compass because it may be used for motor interference compensation
|
||||||
battery.read();
|
battery.read();
|
||||||
|
|
||||||
if(g.compass_enabled) {
|
if(AP::compass().enabled()) {
|
||||||
// update compass with throttle value - used for compassmot
|
// update compass with throttle value - used for compassmot
|
||||||
compass.set_throttle(motors->get_throttle());
|
compass.set_throttle(motors->get_throttle());
|
||||||
compass.set_voltage(battery.voltage());
|
compass.set_voltage(battery.voltage());
|
||||||
|
@ -786,7 +786,6 @@ private:
|
|||||||
void read_rangefinder(void);
|
void read_rangefinder(void);
|
||||||
bool rangefinder_alt_ok();
|
bool rangefinder_alt_ok();
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
void init_compass();
|
|
||||||
void init_compass_location();
|
void init_compass_location();
|
||||||
void init_optflow();
|
void init_optflow();
|
||||||
void update_optical_flow(void);
|
void update_optical_flow(void);
|
||||||
|
@ -34,7 +34,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
|||||||
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||||
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
||||||
|
|
||||||
if (copter.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;
|
||||||
}
|
}
|
||||||
@ -129,7 +129,7 @@ void GCS_Copter::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 (copter.g.compass_enabled && compass.healthy() && ahrs.use_compass()) {
|
if (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.is_healthy()) {
|
if (gps.is_healthy()) {
|
||||||
|
@ -185,13 +185,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),
|
GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),
|
||||||
|
|
||||||
// @Param: MAG_ENABLE
|
|
||||||
// @DisplayName: Compass enable/disable
|
|
||||||
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass
|
|
||||||
// @Values: 0:Disabled,1:Enabled
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
|
||||||
|
|
||||||
// @Param: SUPER_SIMPLE
|
// @Param: SUPER_SIMPLE
|
||||||
// @DisplayName: Super Simple Mode
|
// @DisplayName: Super Simple Mode
|
||||||
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
|
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
|
||||||
|
@ -227,7 +227,7 @@ public:
|
|||||||
k_param_curr_amp_per_volt, // deprecated - can be deleted
|
k_param_curr_amp_per_volt, // deprecated - can be deleted
|
||||||
k_param_input_voltage, // deprecated - can be deleted
|
k_param_input_voltage, // deprecated - can be deleted
|
||||||
k_param_pack_capacity, // deprecated - can be deleted
|
k_param_pack_capacity, // deprecated - can be deleted
|
||||||
k_param_compass_enabled,
|
k_param_compass_enabled_deprecated,
|
||||||
k_param_compass,
|
k_param_compass,
|
||||||
k_param_rangefinder_enabled_old, // deprecated
|
k_param_rangefinder_enabled_old, // deprecated
|
||||||
k_param_frame_type,
|
k_param_frame_type,
|
||||||
@ -389,7 +389,6 @@ public:
|
|||||||
AP_Int8 failsafe_gcs; // ground station failsafe behavior
|
AP_Int8 failsafe_gcs; // ground station failsafe behavior
|
||||||
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
||||||
|
|
||||||
AP_Int8 compass_enabled;
|
|
||||||
AP_Int8 super_simple;
|
AP_Int8 super_simple;
|
||||||
AP_Int16 rtl_alt_final;
|
AP_Int16 rtl_alt_final;
|
||||||
AP_Int16 rtl_climb_min; // rtl minimum climb in cm
|
AP_Int16 rtl_climb_min; // rtl minimum climb in cm
|
||||||
|
@ -41,7 +41,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
|
GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
|
||||||
|
|
||||||
// check compass is enabled
|
// check compass is enabled
|
||||||
if (!g.compass_enabled) {
|
if (!AP::compass().enabled()) {
|
||||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
|
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
|
||||||
ap.compass_mot = false;
|
ap.compass_mot = false;
|
||||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||||
|
@ -85,23 +85,6 @@ void Copter::rpm_update(void)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialise compass
|
|
||||||
void Copter::init_compass()
|
|
||||||
{
|
|
||||||
if (!g.compass_enabled) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
compass.init();
|
|
||||||
if (!compass.read()) {
|
|
||||||
// make sure we don't pass a broken compass to DCM
|
|
||||||
hal.console->printf("COMPASS INIT ERROR\n");
|
|
||||||
AP::logger().Write_Error(LogErrorSubsystem::COMPASS, LogErrorCode::FAILED_TO_INITIALISE);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
ahrs.set_compass(&compass);
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
initialise compass's location used for declination
|
initialise compass's location used for declination
|
||||||
*/
|
*/
|
||||||
|
@ -6,7 +6,7 @@ void Copter::report_compass()
|
|||||||
hal.console->printf("Compass\n");
|
hal.console->printf("Compass\n");
|
||||||
print_divider();
|
print_divider();
|
||||||
|
|
||||||
print_enabled(g.compass_enabled);
|
print_enabled(AP::compass().enabled());
|
||||||
|
|
||||||
// mag declination
|
// mag declination
|
||||||
hal.console->printf("Mag Dec: %4.4f\n",
|
hal.console->printf("Mag Dec: %4.4f\n",
|
||||||
|
@ -137,7 +137,7 @@ void Copter::init_ardupilot()
|
|||||||
gps.set_log_gps_bit(MASK_LOG_GPS);
|
gps.set_log_gps_bit(MASK_LOG_GPS);
|
||||||
gps.init(serial_manager);
|
gps.init(serial_manager);
|
||||||
|
|
||||||
init_compass();
|
AP::compass().init();
|
||||||
|
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
// make optflow available to AHRS
|
// make optflow available to AHRS
|
||||||
|
Loading…
Reference in New Issue
Block a user