From e29b6c30368bdd17b901347d4dc18a26bac27b25 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Nov 2024 18:17:28 +1100 Subject: [PATCH] ArduCopter: create and use a singleton for SRV_Channels avoid creation of static pointers to objects held within SRV_Channels --- ArduCopter/Copter.cpp | 2 +- ArduCopter/compassmot.cpp | 2 +- ArduCopter/esc_calibration.cpp | 8 ++++---- ArduCopter/motors.cpp | 2 +- ArduCopter/radio.cpp | 2 +- 5 files changed, 8 insertions(+), 8 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 417468160c..84e31f3ebb 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -727,7 +727,7 @@ void Copter::one_hz_loop() } // update assigned functions and enable auxiliary servos - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); #if HAL_LOGGING_ENABLED // log terrain data diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 703f5cf722..c0d26041c0 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -148,7 +148,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) // pass through throttle to motors SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f); - SRV_Channels::push(); + AP::srv().push(); // read some compass values compass.read(); diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index b4c5c11906..722127898e 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -97,7 +97,7 @@ void Copter::esc_calibration_passthrough() // pass through to motors SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f); - SRV_Channels::push(); + AP::srv().push(); } #endif // FRAME_CONFIG != HELI_FRAME } @@ -114,14 +114,14 @@ void Copter::esc_calibration_auto() // raise throttle to maximum SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(1.0f); - SRV_Channels::push(); + AP::srv().push(); // delay for 5 seconds while outputting pulses uint32_t tstart = millis(); while (millis() - tstart < 5000) { SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(1.0f); - SRV_Channels::push(); + AP::srv().push(); esc_calibration_notify(); hal.scheduler->delay(3); } @@ -130,7 +130,7 @@ void Copter::esc_calibration_auto() while(1) { SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(0.0f); - SRV_Channels::push(); + AP::srv().push(); esc_calibration_notify(); hal.scheduler->delay(3); } diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index e382cb5941..328eb83150 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -181,7 +181,7 @@ void Copter::motors_output() } // push all channels - SRV_Channels::push(); + AP::srv().push(); } // check for pilot stick input to trigger lost vehicle alarm diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index b92178d098..9873d1a284 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -45,7 +45,7 @@ void Copter::init_rc_out() motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get()); // enable aux servos to cope with multiple output channels per motor - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); // update rate must be set after motors->init() to allow for motor mapping motors->set_update_rate(g.rc_speed);