mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APMrover2: implement on-board compass calibration for APMrover
This commit is contained in:
parent
f4cdf57d8f
commit
b8a9f9ebc5
@ -77,6 +77,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] PROGMEM = {
|
|||||||
SCHED_TASK(compass_accumulate, 1, 900),
|
SCHED_TASK(compass_accumulate, 1, 900),
|
||||||
SCHED_TASK(update_notify, 1, 300),
|
SCHED_TASK(update_notify, 1, 300),
|
||||||
SCHED_TASK(one_second_loop, 50, 3000),
|
SCHED_TASK(one_second_loop, 50, 3000),
|
||||||
|
SCHED_TASK(compass_cal_update, 1, 100),
|
||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
SCHED_TASK(frsky_telemetry_send, 10, 100),
|
SCHED_TASK(frsky_telemetry_send, 10, 100),
|
||||||
#endif
|
#endif
|
||||||
|
@ -589,13 +589,24 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||||||
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
|
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_MAG_CAL_PROGRESS:
|
||||||
|
CHECK_PAYLOAD_SIZE(MAG_CAL_PROGRESS);
|
||||||
|
rover.compass.send_mag_cal_progress(chan);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSG_MAG_CAL_REPORT:
|
||||||
|
CHECK_PAYLOAD_SIZE(MAG_CAL_REPORT);
|
||||||
|
rover.compass.send_mag_cal_report(chan);
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_RETRY_DEFERRED:
|
case MSG_RETRY_DEFERRED:
|
||||||
case MSG_TERRAIN:
|
case MSG_TERRAIN:
|
||||||
case MSG_OPTICAL_FLOW:
|
case MSG_OPTICAL_FLOW:
|
||||||
case MSG_GIMBAL_REPORT:
|
case MSG_GIMBAL_REPORT:
|
||||||
case MSG_RPM:
|
case MSG_RPM:
|
||||||
break; // just here to prevent a warning
|
break; // just here to prevent a warning
|
||||||
}
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
@ -820,6 +831,8 @@ GCS_MAVLINK::data_stream_send(void)
|
|||||||
send_message(MSG_RANGEFINDER);
|
send_message(MSG_RANGEFINDER);
|
||||||
send_message(MSG_SYSTEM_TIME);
|
send_message(MSG_SYSTEM_TIME);
|
||||||
send_message(MSG_BATTERY2);
|
send_message(MSG_BATTERY2);
|
||||||
|
send_message(MSG_MAG_CAL_REPORT);
|
||||||
|
send_message(MSG_MAG_CAL_PROGRESS);
|
||||||
send_message(MSG_MOUNT_STATUS);
|
send_message(MSG_MOUNT_STATUS);
|
||||||
send_message(MSG_EKF_STATUS_REPORT);
|
send_message(MSG_EKF_STATUS_REPORT);
|
||||||
}
|
}
|
||||||
@ -1036,6 +1049,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case MAV_CMD_DO_START_MAG_CAL:
|
||||||
|
case MAV_CMD_DO_ACCEPT_MAG_CAL:
|
||||||
|
case MAV_CMD_DO_CANCEL_MAG_CAL:
|
||||||
|
result = rover.compass.handle_mag_cal_command(packet);
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -372,6 +372,7 @@ private:
|
|||||||
void update_alt();
|
void update_alt();
|
||||||
void gcs_failsafe_check(void);
|
void gcs_failsafe_check(void);
|
||||||
void compass_accumulate(void);
|
void compass_accumulate(void);
|
||||||
|
void compass_cal_update(void);
|
||||||
void update_compass(void);
|
void update_compass(void);
|
||||||
void update_logging1(void);
|
void update_logging1(void);
|
||||||
void update_logging2(void);
|
void update_logging2(void);
|
||||||
|
@ -28,6 +28,13 @@ void Rover::read_receiver_rssi(void)
|
|||||||
receiver_rssi = rssi.read_receiver_rssi_uint8();
|
receiver_rssi = rssi.read_receiver_rssi_uint8();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//Calibrate compass
|
||||||
|
void Rover::compass_cal_update() {
|
||||||
|
if (!hal.util->get_soft_armed()) {
|
||||||
|
compass.compass_cal_update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// read the sonars
|
// read the sonars
|
||||||
void Rover::read_sonars(void)
|
void Rover::read_sonars(void)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user