diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 11dcce6ab4..a167b0732e 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -202,16 +202,16 @@ private: void init_servos(); void update_pitch_servo(float pitch); void update_pitch_position_servo(void); - void update_pitch_onoff_servo(float pitch); + void update_pitch_onoff_servo(float pitch) const; void update_pitch_cr_servo(float pitch); void update_yaw_servo(float yaw); void update_yaw_position_servo(void); - void update_yaw_onoff_servo(float yaw); + void update_yaw_onoff_servo(float yaw) const; void update_yaw_cr_servo(float yaw); // system.cpp void init_ardupilot() override; - bool get_home_eeprom(struct Location &loc); + bool get_home_eeprom(struct Location &loc) const; bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED; bool set_home(const Location &temp) WARN_IF_UNUSED; void prepare_servos(); @@ -231,7 +231,7 @@ private: void tracking_update_position(const mavlink_global_position_int_t &msg); void tracking_update_pressure(const mavlink_scaled_pressure_t &msg); void tracking_manual_control(const mavlink_manual_control_t &msg); - void update_armed_disarmed(); + void update_armed_disarmed() const; // Arming/Disarming management class AP_Arming_Tracker arming; diff --git a/AntennaTracker/servos.cpp b/AntennaTracker/servos.cpp index a845111f63..508da8f450 100644 --- a/AntennaTracker/servos.cpp +++ b/AntennaTracker/servos.cpp @@ -101,7 +101,7 @@ void Tracker::update_pitch_position_servo() update the pitch (elevation) servo. The aim is to drive the boards ahrs pitch to the requested pitch, so the board (and therefore the antenna) will be pointing at the target */ -void Tracker::update_pitch_onoff_servo(float pitch) +void Tracker::update_pitch_onoff_servo(float pitch) const { int32_t pitch_min_cd = g.pitch_min*100; int32_t pitch_max_cd = g.pitch_max*100; @@ -217,7 +217,7 @@ void Tracker::update_yaw_position_servo() yaw to the requested yaw, so the board (and therefore the antenna) will be pointing at the target */ -void Tracker::update_yaw_onoff_servo(float yaw) +void Tracker::update_yaw_onoff_servo(float yaw) const { float acceptable_error = g.onoff_yaw_rate * g.onoff_yaw_mintime; if (fabsf(nav_status.angle_error_yaw * 0.01f) < acceptable_error) { diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index c30e1540f1..114cf7e526 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -97,7 +97,7 @@ void Tracker::init_ardupilot() /* fetch HOME from EEPROM */ -bool Tracker::get_home_eeprom(struct Location &loc) +bool Tracker::get_home_eeprom(struct Location &loc) const { // Find out proper location in memory by using the start_byte position + the index // -------------------------------------------------------------------------------- diff --git a/AntennaTracker/tracking.cpp b/AntennaTracker/tracking.cpp index 884250d4aa..6ca73f569e 100644 --- a/AntennaTracker/tracking.cpp +++ b/AntennaTracker/tracking.cpp @@ -187,7 +187,7 @@ void Tracker::tracking_manual_control(const mavlink_manual_control_t &msg) /** update_armed_disarmed - set armed LED if we have received a position update within the last 5 seconds */ -void Tracker::update_armed_disarmed() +void Tracker::update_armed_disarmed() const { if (vehicle.last_update_ms != 0 && (AP_HAL::millis() - vehicle.last_update_ms) < TRACKING_TIMEOUT_MS) { AP_Notify::flags.armed = true;