diff --git a/ArduPlane/AP_Arming.h b/ArduPlane/AP_Arming.h index 26b0fb63f8..1a4d4f3628 100644 --- a/ArduPlane/AP_Arming.h +++ b/ArduPlane/AP_Arming.h @@ -28,7 +28,7 @@ public: bool arm(AP_Arming::Method method, bool do_arming_checks=true) override; void update_soft_armed(); - bool get_delay_arming() { return delay_arming; }; + bool get_delay_arming() const { return delay_arming; }; protected: bool ins_checks(bool report) override; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index aa88d6feef..24e0701a3f 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -786,7 +786,7 @@ private: void update_load_factor(void); void adjust_altitude_target(); void setup_glide_slope(void); - int32_t get_RTL_altitude(); + int32_t get_RTL_altitude() const; float relative_ground_altitude(bool use_rangefinder_if_available); void set_target_altitude_current(void); void set_target_altitude_current_adjusted(void); @@ -800,7 +800,7 @@ private: void reset_offset_altitude(void); void set_offset_altitude_location(const Location &loc); bool above_location_current(const Location &loc); - void setup_terrain_target_alt(Location &loc); + void setup_terrain_target_alt(Location &loc) const; int32_t adjusted_altitude_cm(void); int32_t adjusted_relative_altitude_cm(void); float mission_alt_offset(void); @@ -903,7 +903,7 @@ private: // control_modes.cpp void read_control_switch(); - uint8_t readSwitch(void); + uint8_t readSwitch(void) const; void reset_control_switch(); void autotune_start(void); void autotune_restore(void); @@ -924,7 +924,7 @@ private: Vector2l get_fence_point_with_index(uint8_t i) const; void set_fence_point_with_index(const Vector2l &point, unsigned i); void geofence_load(void); - bool geofence_present(void); + bool geofence_present(void) const; void geofence_update_pwm_enabled_state(); bool geofence_set_enabled(bool enable); bool geofence_enabled(void); @@ -1039,13 +1039,13 @@ private: void servos_auto_trim(void); void servos_twin_engine_mix(); void force_flare(); - void throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle); + void throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle) const; void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle); void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func); bool suppress_throttle(void); void update_throttle_hover(); void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in, - SRV_Channel::Aux_servo_function_t func1_out, SRV_Channel::Aux_servo_function_t func2_out); + SRV_Channel::Aux_servo_function_t func1_out, SRV_Channel::Aux_servo_function_t func2_out) const; void flaperon_update(int8_t flap_percent); // is_flying.cpp diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 9a0af4c5b5..abae31545e 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -137,7 +137,7 @@ void Plane::setup_glide_slope(void) /* return RTL altitude as AMSL altitude */ -int32_t Plane::get_RTL_altitude() +int32_t Plane::get_RTL_altitude() const { if (g.RTL_altitude_cm < 0) { return current_loc.alt; @@ -459,7 +459,7 @@ bool Plane::above_location_current(const Location &loc) modify a destination to be setup for terrain following if TERRAIN_FOLLOW is enabled */ -void Plane::setup_terrain_target_alt(Location &loc) +void Plane::setup_terrain_target_alt(Location &loc) const { #if AP_TERRAIN_AVAILABLE if (g.terrain_follow) { diff --git a/ArduPlane/control_modes.cpp b/ArduPlane/control_modes.cpp index 9a21bd0935..2bcb8ca4e0 100644 --- a/ArduPlane/control_modes.cpp +++ b/ArduPlane/control_modes.cpp @@ -146,7 +146,7 @@ void Plane::read_control_switch() #endif } -uint8_t Plane::readSwitch(void) +uint8_t Plane::readSwitch(void) const { uint16_t pulsewidth = RC_Channels::get_radio_in(g.flight_mode_channel - 1); if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition diff --git a/ArduPlane/geofence.cpp b/ArduPlane/geofence.cpp index 4ad76208f4..f5bcdc7794 100644 --- a/ArduPlane/geofence.cpp +++ b/ArduPlane/geofence.cpp @@ -145,7 +145,7 @@ void Plane::geofence_disable_and_send_error_msg(const char *errorMsg) * return true if a geo-fence has been uploaded and * FENCE_ACTION is 1 (not necessarily enabled) */ -bool Plane::geofence_present(void) +bool Plane::geofence_present(void) const { //require at least a return point and a triangle //to define a geofence area: diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index 886a22aff2..62f25577ac 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -382,7 +382,7 @@ public: void navigate() override; - bool get_target_heading_cd(int32_t &target_heading); + bool get_target_heading_cd(int32_t &target_heading) const; bool does_auto_throttle() const override { return true; } diff --git a/ArduPlane/mode_cruise.cpp b/ArduPlane/mode_cruise.cpp index a1223c5358..4b3b76b250 100644 --- a/ArduPlane/mode_cruise.cpp +++ b/ArduPlane/mode_cruise.cpp @@ -69,7 +69,7 @@ void ModeCruise::navigate() } } -bool ModeCruise::get_target_heading_cd(int32_t &target_heading) +bool ModeCruise::get_target_heading_cd(int32_t &target_heading) const { target_heading = locked_heading_cd; return locked_heading; diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index b5deae7836..dd55f89e07 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2328,7 +2328,7 @@ bool QuadPlane::init_mode(void) /* handle a MAVLink DO_VTOL_TRANSITION */ -bool QuadPlane::handle_do_vtol_transition(enum MAV_VTOL_STATE state) +bool QuadPlane::handle_do_vtol_transition(enum MAV_VTOL_STATE state) const { if (!available()) { gcs().send_text(MAV_SEVERITY_NOTICE, "VTOL not available"); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 717991d272..0a343672fe 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -89,7 +89,7 @@ public: */ bool in_tailsitter_vtol_transition(uint32_t now = 0) const; - bool handle_do_vtol_transition(enum MAV_VTOL_STATE state); + bool handle_do_vtol_transition(enum MAV_VTOL_STATE state) const; bool do_vtol_takeoff(const AP_Mission::Mission_Command& cmd); bool do_vtol_land(const AP_Mission::Mission_Command& cmd); @@ -568,8 +568,8 @@ private: bool is_motor_tilting(uint8_t motor) const { return (((uint8_t)tilt.tilt_mask.get()) & (1U<= g2.fwd_thr_batt_voltage_max || !is_positive(g2.fwd_thr_batt_voltage_max)) { diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 534f926676..05df5cdf88 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -9,7 +9,7 @@ /* calculate maximum tilt change as a proportion from 0 to 1 of tilt */ -float QuadPlane::tilt_max_change(bool up) +float QuadPlane::tilt_max_change(bool up) const { float rate; if (up || tilt.max_rate_down_dps <= 0) { @@ -310,7 +310,7 @@ void QuadPlane::tilt_compensate(float *thrust, uint8_t num_motors) /* return true if the rotors are fully tilted forward */ -bool QuadPlane::tiltrotor_fully_fwd(void) +bool QuadPlane::tiltrotor_fully_fwd(void) const { if (tilt.tilt_mask <= 0) { return false;