mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
GCS_MAVLink: pass link object in place of channel to compass cal
Also eliminate intermediate function as just adding noise
This commit is contained in:
parent
01a713a812
commit
cf0b7cf016
@ -396,7 +396,6 @@ protected:
|
|||||||
virtual void send_global_position_int();
|
virtual void send_global_position_int();
|
||||||
|
|
||||||
// message sending functions:
|
// message sending functions:
|
||||||
bool try_send_compass_message(enum ap_message id);
|
|
||||||
bool try_send_mission_message(enum ap_message id);
|
bool try_send_mission_message(enum ap_message id);
|
||||||
void send_hwstatus();
|
void send_hwstatus();
|
||||||
void handle_data_packet(const mavlink_message_t &msg);
|
void handle_data_packet(const mavlink_message_t &msg);
|
||||||
|
@ -3757,26 +3757,6 @@ void GCS_MAVLINK::handle_command_int(const mavlink_message_t &msg)
|
|||||||
hal.util->persistent_data.last_mavlink_cmd = 0;
|
hal.util->persistent_data.last_mavlink_cmd = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool GCS_MAVLINK::try_send_compass_message(const enum ap_message id)
|
|
||||||
{
|
|
||||||
Compass &compass = AP::compass();
|
|
||||||
bool ret = true;
|
|
||||||
switch (id) {
|
|
||||||
case MSG_MAG_CAL_PROGRESS:
|
|
||||||
compass.send_mag_cal_progress(chan);
|
|
||||||
ret = true;;
|
|
||||||
break;
|
|
||||||
case MSG_MAG_CAL_REPORT:
|
|
||||||
compass.send_mag_cal_report(chan);
|
|
||||||
ret = true;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
ret = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) {
|
void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) {
|
||||||
MissionItemProtocol *prot = get_prot_for_mission_type(type);
|
MissionItemProtocol *prot = get_prot_for_mission_type(type);
|
||||||
if (prot == nullptr) {
|
if (prot == nullptr) {
|
||||||
@ -4053,8 +4033,10 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_MAG_CAL_PROGRESS:
|
case MSG_MAG_CAL_PROGRESS:
|
||||||
|
ret = AP::compass().send_mag_cal_progress(*this);
|
||||||
|
break;
|
||||||
case MSG_MAG_CAL_REPORT:
|
case MSG_MAG_CAL_REPORT:
|
||||||
ret = try_send_compass_message(id);
|
ret = AP::compass().send_mag_cal_report(*this);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_BATTERY_STATUS:
|
case MSG_BATTERY_STATUS:
|
||||||
|
Loading…
Reference in New Issue
Block a user