AP_Compass: allow more libraries to compile with no HAL_GCS_ENABLED
This commit is contained in:
parent
ffe46b760e
commit
275a667d41
@ -57,7 +57,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
|
|||||||
|
|
||||||
#if COMPASS_MAX_INSTANCES > 1
|
#if COMPASS_MAX_INSTANCES > 1
|
||||||
if (_priority_did_list[prio] != _priority_did_stored_list[prio]) {
|
if (_priority_did_list[prio] != _priority_did_stored_list[prio]) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -65,14 +65,14 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
|
|||||||
if (_calibrator[prio] == nullptr) {
|
if (_calibrator[prio] == nullptr) {
|
||||||
_calibrator[prio] = new CompassCalibrator();
|
_calibrator[prio] = new CompassCalibrator();
|
||||||
if (_calibrator[prio] == nullptr) {
|
if (_calibrator[prio] == nullptr) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal object not initialised");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal object not initialised");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (option_set(Option::CAL_REQUIRE_GPS)) {
|
if (option_set(Option::CAL_REQUIRE_GPS)) {
|
||||||
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {
|
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -98,7 +98,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
|
|||||||
if (!_cal_thread_started) {
|
if (!_cal_thread_started) {
|
||||||
_cal_requires_reboot = true;
|
_cal_requires_reboot = true;
|
||||||
if (!hal.scheduler->thread_create(FUNCTOR_BIND(this, &Compass::_update_calibration_trampoline, void), "compasscal", 2048, AP_HAL::Scheduler::PRIORITY_IO, 0)) {
|
if (!hal.scheduler->thread_create(FUNCTOR_BIND(this, &Compass::_update_calibration_trampoline, void), "compasscal", 2048, AP_HAL::Scheduler::PRIORITY_IO, 0)) {
|
||||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "CompassCalibrator: Cannot start compass thread.");
|
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "CompassCalibrator: Cannot start compass thread.");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
_cal_thread_started = true;
|
_cal_thread_started = true;
|
||||||
@ -240,6 +240,7 @@ bool Compass::_accept_calibration_mask(uint8_t mask)
|
|||||||
return success;
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link)
|
bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link)
|
||||||
{
|
{
|
||||||
const mavlink_channel_t chan = link.get_chan();
|
const mavlink_channel_t chan = link.get_chan();
|
||||||
@ -329,6 +330,7 @@ bool Compass::send_mag_cal_report(const GCS_MAVLINK& link)
|
|||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
bool Compass::is_calibrating() const
|
bool Compass::is_calibrating() const
|
||||||
{
|
{
|
||||||
@ -379,7 +381,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet)
|
|||||||
case MAV_CMD_DO_START_MAG_CAL: {
|
case MAV_CMD_DO_START_MAG_CAL: {
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
if (hal.util->get_soft_armed()) {
|
if (hal.util->get_soft_armed()) {
|
||||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration");
|
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration");
|
||||||
result = MAV_RESULT_FAILED;
|
result = MAV_RESULT_FAILED;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -508,7 +510,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
|
|||||||
// get AHRS position. If unavailable then try GPS location
|
// get AHRS position. If unavailable then try GPS location
|
||||||
if (!AP::ahrs().get_location(loc)) {
|
if (!AP::ahrs().get_location(loc)) {
|
||||||
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
|
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Mag: no position available");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: no position available");
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
loc = AP::gps().location();
|
loc = AP::gps().location();
|
||||||
@ -522,7 +524,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
|
|||||||
float declination;
|
float declination;
|
||||||
float inclination;
|
float inclination;
|
||||||
if (!AP_Declination::get_mag_field_ef(lat_deg, lon_deg, intensity, declination, inclination)) {
|
if (!AP_Declination::get_mag_field_ef(lat_deg, lon_deg, intensity, declination, inclination)) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Mag: WMM table error");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: WMM table error");
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -547,13 +549,13 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (!healthy(i)) {
|
if (!healthy(i)) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Mag[%u]: unhealthy\n", i);
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: unhealthy\n", i);
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3f measurement;
|
Vector3f measurement;
|
||||||
if (!get_uncorrected_field(i, measurement)) {
|
if (!get_uncorrected_field(i, measurement)) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Mag[%u]: bad uncorrected field", i);
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: bad uncorrected field", i);
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -15,7 +15,7 @@ extern const AP_HAL::HAL &hal;
|
|||||||
CompassLearn::CompassLearn(Compass &_compass) :
|
CompassLearn::CompassLearn(Compass &_compass) :
|
||||||
compass(_compass)
|
compass(_compass)
|
||||||
{
|
{
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: Initialised");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CompassLearn: Initialised");
|
||||||
}
|
}
|
||||||
|
|
||||||
// accuracy threshold applied for GSF yaw estimate
|
// accuracy threshold applied for GSF yaw estimate
|
||||||
@ -64,7 +64,7 @@ void CompassLearn::update(void)
|
|||||||
if (result == MAV_RESULT_ACCEPTED) {
|
if (result == MAV_RESULT_ACCEPTED) {
|
||||||
AP_Notify::flags.compass_cal_running = false;
|
AP_Notify::flags.compass_cal_running = false;
|
||||||
compass.set_learn_type(Compass::LEARN_NONE, true);
|
compass.set_learn_type(Compass::LEARN_NONE, true);
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: Finished");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CompassLearn: Finished");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user