mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Copter: changes for compass healthy API
This commit is contained in:
parent
563e5f71ff
commit
d265e54043
@ -182,7 +182,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||||||
|
|
||||||
// default to all healthy except compass, gps and receiver which we set individually
|
// default to all healthy except compass, gps and receiver which we set individually
|
||||||
control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS & ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
|
control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS & ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
|
||||||
if (g.compass_enabled && compass.healthy && ahrs.use_compass()) {
|
if (g.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 (g_gps != NULL && g_gps->status() > GPS::NO_GPS && !gps_glitch.glitching()) {
|
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS && !gps_glitch.glitching()) {
|
||||||
|
@ -248,7 +248,7 @@ static void pre_arm_checks(bool display_failure)
|
|||||||
// check Compass
|
// check Compass
|
||||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_COMPASS)) {
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_COMPASS)) {
|
||||||
// check the compass is healthy
|
// check the compass is healthy
|
||||||
if(!compass.healthy) {
|
if(!compass.healthy()) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not healthy"));
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not healthy"));
|
||||||
}
|
}
|
||||||
|
@ -183,7 +183,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv)
|
|||||||
compass.read();
|
compass.read();
|
||||||
|
|
||||||
// exit immediately if the compass is not healthy
|
// exit immediately if the compass is not healthy
|
||||||
if( !compass.healthy ) {
|
if( !compass.healthy() ) {
|
||||||
cliSerial->print_P(PSTR("check compass\n"));
|
cliSerial->print_P(PSTR("check compass\n"));
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -208,7 +208,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv)
|
|||||||
last_run_time = millis();
|
last_run_time = millis();
|
||||||
|
|
||||||
// main run while there is no user input and the compass is healthy
|
// main run while there is no user input and the compass is healthy
|
||||||
while(!cliSerial->available() && compass.healthy) {
|
while(!cliSerial->available() && compass.healthy()) {
|
||||||
|
|
||||||
// 50hz loop
|
// 50hz loop
|
||||||
if( millis() - last_run_time > 20 ) {
|
if( millis() - last_run_time > 20 ) {
|
||||||
|
@ -141,7 +141,7 @@ test_compass(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
counter++;
|
counter++;
|
||||||
if (counter>20) {
|
if (counter>20) {
|
||||||
if (compass.healthy) {
|
if (compass.healthy()) {
|
||||||
const Vector3f &mag_ofs = compass.get_offsets();
|
const Vector3f &mag_ofs = compass.get_offsets();
|
||||||
const Vector3f &mag = compass.get_field();
|
const Vector3f &mag = compass.get_field();
|
||||||
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
|
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
|
||||||
|
Loading…
Reference in New Issue
Block a user