mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduCopter: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
c98947fe85
commit
ad82e01270
@ -135,7 +135,7 @@ void Copter::rotate_body_frame_to_NE(float &x, float &y)
|
||||
}
|
||||
|
||||
// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
|
||||
uint16_t Copter::get_pilot_speed_dn()
|
||||
uint16_t Copter::get_pilot_speed_dn() const
|
||||
{
|
||||
if (g2.pilot_speed_dn == 0) {
|
||||
return abs(g.pilot_speed_up);
|
||||
|
@ -662,7 +662,7 @@ private:
|
||||
float get_non_takeoff_throttle();
|
||||
void set_accel_throttle_I_from_pilot_throttle();
|
||||
void rotate_body_frame_to_NE(float &x, float &y);
|
||||
uint16_t get_pilot_speed_dn();
|
||||
uint16_t get_pilot_speed_dn() const;
|
||||
|
||||
#if HAL_ADSB_ENABLED
|
||||
// avoidance_adsb.cpp
|
||||
@ -816,8 +816,8 @@ private:
|
||||
void load_parameters(void) override;
|
||||
void convert_pid_parameters(void);
|
||||
void convert_lgr_parameters(void);
|
||||
void convert_tradheli_parameters(void);
|
||||
void convert_fs_options_params(void);
|
||||
void convert_tradheli_parameters(void) const;
|
||||
void convert_fs_options_params(void) const;
|
||||
|
||||
// precision_landing.cpp
|
||||
void init_precland();
|
||||
@ -838,8 +838,8 @@ private:
|
||||
void read_barometer(void);
|
||||
void init_rangefinder(void);
|
||||
void read_rangefinder(void);
|
||||
bool rangefinder_alt_ok();
|
||||
bool rangefinder_up_ok();
|
||||
bool rangefinder_alt_ok() const;
|
||||
bool rangefinder_up_ok() const;
|
||||
void rpm_update();
|
||||
void init_optflow();
|
||||
void update_optical_flow(void);
|
||||
@ -863,7 +863,7 @@ private:
|
||||
bool ekf_alt_ok() const;
|
||||
void update_auto_armed();
|
||||
bool should_log(uint32_t mask);
|
||||
const char* get_frame_string();
|
||||
const char* get_frame_string() const;
|
||||
void allocate_motors(void);
|
||||
bool is_tradheli() const;
|
||||
|
||||
|
@ -1411,7 +1411,7 @@ void Copter::convert_lgr_parameters(void)
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// handle conversion of tradheli parameters from Copter-3.6 to Copter-3.7
|
||||
void Copter::convert_tradheli_parameters(void)
|
||||
void Copter::convert_tradheli_parameters(void) const
|
||||
{
|
||||
if (g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) {
|
||||
// single heli conversion info
|
||||
@ -1585,7 +1585,7 @@ void Copter::convert_tradheli_parameters(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
void Copter::convert_fs_options_params(void)
|
||||
void Copter::convert_fs_options_params(void) const
|
||||
{
|
||||
// If FS_OPTIONS has already been configured and we don't change it.
|
||||
enum ap_var_type ptype;
|
||||
|
@ -474,7 +474,7 @@ private:
|
||||
bool verify_payload_place();
|
||||
bool verify_loiter_unlimited();
|
||||
bool verify_loiter_time(const AP_Mission::Mission_Command& cmd);
|
||||
bool verify_loiter_to_alt();
|
||||
bool verify_loiter_to_alt() const;
|
||||
bool verify_RTL();
|
||||
bool verify_wait_delay();
|
||||
bool verify_within_distance();
|
||||
@ -1068,7 +1068,7 @@ public:
|
||||
RTLState state() { return _state; }
|
||||
|
||||
// this should probably not be exposed
|
||||
bool state_complete() { return _state_complete; }
|
||||
bool state_complete() const { return _state_complete; }
|
||||
|
||||
virtual bool is_landing() const override;
|
||||
|
||||
@ -1278,7 +1278,7 @@ protected:
|
||||
|
||||
private:
|
||||
|
||||
void log_data();
|
||||
void log_data() const;
|
||||
float waveform(float time);
|
||||
|
||||
enum class AxisType {
|
||||
|
@ -1757,7 +1757,7 @@ bool ModeAuto::verify_loiter_time(const AP_Mission::Mission_Command& cmd)
|
||||
|
||||
// verify_loiter_to_alt - check if we have reached both destination
|
||||
// (roughly) and altitude (precisely)
|
||||
bool ModeAuto::verify_loiter_to_alt()
|
||||
bool ModeAuto::verify_loiter_to_alt() const
|
||||
{
|
||||
if (loiter_to_alt.reached_destination_xy &&
|
||||
loiter_to_alt.reached_alt) {
|
||||
|
@ -273,7 +273,7 @@ void ModeSystemId::run()
|
||||
}
|
||||
|
||||
// log system id and attitude
|
||||
void ModeSystemId::log_data()
|
||||
void ModeSystemId::log_data() const
|
||||
{
|
||||
uint8_t index = copter.ahrs.get_primary_gyro_index();
|
||||
Vector3f delta_angle;
|
||||
|
@ -115,13 +115,13 @@ void Copter::read_rangefinder(void)
|
||||
}
|
||||
|
||||
// return true if rangefinder_alt can be used
|
||||
bool Copter::rangefinder_alt_ok()
|
||||
bool Copter::rangefinder_alt_ok() const
|
||||
{
|
||||
return (rangefinder_state.enabled && rangefinder_state.alt_healthy);
|
||||
}
|
||||
|
||||
// return true if rangefinder_alt can be used
|
||||
bool Copter::rangefinder_up_ok()
|
||||
bool Copter::rangefinder_up_ok() const
|
||||
{
|
||||
return (rangefinder_up_state.enabled && rangefinder_up_state.alt_healthy);
|
||||
}
|
||||
|
@ -449,7 +449,7 @@ bool Copter::should_log(uint32_t mask)
|
||||
}
|
||||
|
||||
// return string corresponding to frame_class
|
||||
const char* Copter::get_frame_string()
|
||||
const char* Copter::get_frame_string() const
|
||||
{
|
||||
switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) {
|
||||
case AP_Motors::MOTOR_FRAME_QUAD:
|
||||
|
Loading…
Reference in New Issue
Block a user