mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Copter: stop passing gcs chan into method which wants an object
This commit is contained in:
parent
0b62641a46
commit
f3c1791341
@ -670,7 +670,7 @@ private:
|
|||||||
bool far_from_EKF_origin(const Location& loc);
|
bool far_from_EKF_origin(const Location& loc);
|
||||||
|
|
||||||
// compassmot.cpp
|
// compassmot.cpp
|
||||||
MAV_RESULT mavlink_compassmot(mavlink_channel_t chan);
|
MAV_RESULT mavlink_compassmot(const GCS_MAVLINK &gcs_chan);
|
||||||
|
|
||||||
// crash_check.cpp
|
// crash_check.cpp
|
||||||
void crash_check();
|
void crash_check();
|
||||||
|
@ -539,7 +539,7 @@ MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavli
|
|||||||
{
|
{
|
||||||
if (is_equal(packet.param6,1.0f)) {
|
if (is_equal(packet.param6,1.0f)) {
|
||||||
// compassmot calibration
|
// compassmot calibration
|
||||||
return copter.mavlink_compassmot(chan);
|
return copter.mavlink_compassmot(*this);
|
||||||
}
|
}
|
||||||
|
|
||||||
return GCS_MAVLINK::_handle_command_preflight_calibration(packet);
|
return GCS_MAVLINK::_handle_command_preflight_calibration(packet);
|
||||||
|
@ -5,7 +5,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
// setup_compassmot - sets compass's motor interference parameters
|
// setup_compassmot - sets compass's motor interference parameters
|
||||||
MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
||||||
{
|
{
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// compassmot not implemented for tradheli
|
// compassmot not implemented for tradheli
|
||||||
@ -33,8 +33,6 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
ap.compass_mot = true;
|
ap.compass_mot = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
|
|
||||||
|
|
||||||
// check compass is enabled
|
// check compass is enabled
|
||||||
if (!AP::compass().enabled()) {
|
if (!AP::compass().enabled()) {
|
||||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
|
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
|
||||||
@ -85,7 +83,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// send back initial ACK
|
// send back initial ACK
|
||||||
mavlink_msg_command_ack_send(chan, MAV_CMD_PREFLIGHT_CALIBRATION,0);
|
mavlink_msg_command_ack_send(gcs_chan.get_chan(), MAV_CMD_PREFLIGHT_CALIBRATION,0);
|
||||||
|
|
||||||
// flash leds
|
// flash leds
|
||||||
AP_Notify::flags.esc_calibration = true;
|
AP_Notify::flags.esc_calibration = true;
|
||||||
@ -215,7 +213,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
|
|
||||||
if (AP_HAL::millis() - last_send_time > 500) {
|
if (AP_HAL::millis() - last_send_time > 500) {
|
||||||
last_send_time = AP_HAL::millis();
|
last_send_time = AP_HAL::millis();
|
||||||
mavlink_msg_compassmot_status_send(chan,
|
mavlink_msg_compassmot_status_send(gcs_chan.get_chan(),
|
||||||
channel_throttle->get_control_in(),
|
channel_throttle->get_control_in(),
|
||||||
battery.current_amps(),
|
battery.current_amps(),
|
||||||
interference_pct[compass.get_primary()],
|
interference_pct[compass.get_primary()],
|
||||||
|
Loading…
Reference in New Issue
Block a user