From 07c3435f9dbfe195f4dd712be07faa87f275e734 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Mon, 1 Feb 2021 13:37:57 -0300 Subject: [PATCH] SITL: Add missing const in member functions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- libraries/SITL/SIM_Aircraft.h | 2 +- libraries/SITL/SIM_BalanceBot.cpp | 2 +- libraries/SITL/SIM_BalanceBot.h | 2 +- libraries/SITL/SIM_Battery.cpp | 2 +- libraries/SITL/SIM_Battery.h | 2 +- libraries/SITL/SIM_Gripper_EPM.cpp | 4 ++-- libraries/SITL/SIM_Gripper_EPM.h | 4 ++-- libraries/SITL/SIM_Gripper_Servo.cpp | 2 +- libraries/SITL/SIM_Gripper_Servo.h | 2 +- libraries/SITL/SIM_JSBSim.cpp | 4 ++-- libraries/SITL/SIM_JSBSim.h | 4 ++-- libraries/SITL/SIM_Motor.cpp | 2 +- libraries/SITL/SIM_Motor.h | 2 +- libraries/SITL/SIM_Parachute.cpp | 2 +- libraries/SITL/SIM_Parachute.h | 2 +- libraries/SITL/SIM_Rover.cpp | 2 +- libraries/SITL/SIM_Rover.h | 2 +- libraries/SITL/SIM_SerialDevice.cpp | 4 ++-- libraries/SITL/SIM_SerialDevice.h | 8 ++++---- libraries/SITL/SIM_Submarine.cpp | 4 ++-- libraries/SITL/SIM_Submarine.h | 4 ++-- libraries/SITL/SIM_Tracker.cpp | 4 ++-- libraries/SITL/SIM_Tracker.h | 4 ++-- libraries/SITL/SITL.cpp | 4 ++-- libraries/SITL/SITL.h | 8 ++++---- 25 files changed, 41 insertions(+), 41 deletions(-) diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 07ed075f92..610ec0c789 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -50,7 +50,7 @@ public: set simulation speedup */ void set_speedup(float speedup); - float get_speedup() { return target_speedup; } + float get_speedup() const { return target_speedup; } /* set instance number diff --git a/libraries/SITL/SIM_BalanceBot.cpp b/libraries/SITL/SIM_BalanceBot.cpp index 0abdc0631c..fd5412ce1b 100644 --- a/libraries/SITL/SIM_BalanceBot.cpp +++ b/libraries/SITL/SIM_BalanceBot.cpp @@ -34,7 +34,7 @@ BalanceBot::BalanceBot(const char *frame_str) : /* return yaw rate in degrees/second given steering_angle */ -float BalanceBot::calc_yaw_rate(float steering) +float BalanceBot::calc_yaw_rate(float steering) const { float wheel_base_length = 0.15f; return steering * degrees( skid_turn_rate/wheel_base_length ); diff --git a/libraries/SITL/SIM_BalanceBot.h b/libraries/SITL/SIM_BalanceBot.h index b3b44c21ff..be7e88ebb8 100644 --- a/libraries/SITL/SIM_BalanceBot.h +++ b/libraries/SITL/SIM_BalanceBot.h @@ -40,7 +40,7 @@ private: float skid_turn_rate; - float calc_yaw_rate(float steering); + float calc_yaw_rate(float steering) const; }; } // namespace SITL diff --git a/libraries/SITL/SIM_Battery.cpp b/libraries/SITL/SIM_Battery.cpp index 34ec483513..ba8a17b263 100644 --- a/libraries/SITL/SIM_Battery.cpp +++ b/libraries/SITL/SIM_Battery.cpp @@ -71,7 +71,7 @@ static const struct { /* use table to get resting voltage from remaining capacity */ -float Battery::get_resting_voltage(float charge_pct) +float Battery::get_resting_voltage(float charge_pct) const { const float max_cell_voltage = soc_table[0].volt_per_cell; for (uint8_t i=1; i 0) { @@ -93,7 +93,7 @@ ssize_t SerialDevice::read_from_autopilot(char *buffer, const size_t size) return ret; } -ssize_t SerialDevice::write_to_autopilot(const char *buffer, const size_t size) +ssize_t SerialDevice::write_to_autopilot(const char *buffer, const size_t size) const { const ssize_t ret = write(fd_my_end, buffer, size); // ::fprintf(stderr, "write to autopilot: ("); diff --git a/libraries/SITL/SIM_SerialDevice.h b/libraries/SITL/SIM_SerialDevice.h index 8492836ad1..b99e7eff8b 100644 --- a/libraries/SITL/SIM_SerialDevice.h +++ b/libraries/SITL/SIM_SerialDevice.h @@ -29,12 +29,12 @@ public: // return fd on which data from the device can be read // to the device can be written - int fd() { return fd_their_end; } + int fd() const { return fd_their_end; } // return fd on which data to the device can be written - int write_fd() { return read_fd_their_end; } + int write_fd() const { return read_fd_their_end; } - ssize_t read_from_autopilot(char *buffer, size_t size); - ssize_t write_to_autopilot(const char *buffer, size_t size); + ssize_t read_from_autopilot(char *buffer, size_t size) const; + ssize_t write_to_autopilot(const char *buffer, size_t size) const; protected: diff --git a/libraries/SITL/SIM_Submarine.cpp b/libraries/SITL/SIM_Submarine.cpp index 29159494bf..69401bf6b2 100644 --- a/libraries/SITL/SIM_Submarine.cpp +++ b/libraries/SITL/SIM_Submarine.cpp @@ -151,7 +151,7 @@ float Submarine::calculate_sea_floor_depth(const Vector3f &/*position*/) * $ F_D = rho * v^2 * A * C_D / 2 $ * rho = water density (kg/m^3), V = velocity (m/s), A = area (m^2), C_D = drag_coefficient */ -void Submarine::calculate_drag_force(const Vector3f &velocity, const Vector3f &drag_coefficient, Vector3f &force) +void Submarine::calculate_drag_force(const Vector3f &velocity, const Vector3f &drag_coefficient, Vector3f &force) const { /** * @brief It's necessary to keep the velocity orientation from the body frame. @@ -182,7 +182,7 @@ void Submarine::calculate_drag_force(const Vector3f &velocity, const Vector3f &d * @param angular_velocity Body frame velocity of fluid * @param drag_coefficient Rotational drag coefficient of body */ -void Submarine::calculate_angular_drag_torque(const Vector3f &angular_velocity, const Vector3f &drag_coefficient, Vector3f &torque) +void Submarine::calculate_angular_drag_torque(const Vector3f &angular_velocity, const Vector3f &drag_coefficient, Vector3f &torque) const { /** * @brief It's necessary to keep the velocity orientation from the body frame. diff --git a/libraries/SITL/SIM_Submarine.h b/libraries/SITL/SIM_Submarine.h index 86ce056bd8..4438892eb2 100644 --- a/libraries/SITL/SIM_Submarine.h +++ b/libraries/SITL/SIM_Submarine.h @@ -96,9 +96,9 @@ protected: // calculate buoyancy float calculate_buoyancy_acceleration(); // calculate drag from velocity and drag coefficient - void calculate_drag_force(const Vector3f &velocity, const Vector3f &drag_coefficient, Vector3f &force); + void calculate_drag_force(const Vector3f &velocity, const Vector3f &drag_coefficient, Vector3f &force) const; // calculate torque water resistance - void calculate_angular_drag_torque(const Vector3f &angular_velocity, const Vector3f &drag_coefficient, Vector3f &torque); + void calculate_angular_drag_torque(const Vector3f &angular_velocity, const Vector3f &drag_coefficient, Vector3f &torque) const; // calculate torque induced by buoyancy foams void calculate_buoyancy_torque(Vector3f &torque); diff --git a/libraries/SITL/SIM_Tracker.cpp b/libraries/SITL/SIM_Tracker.cpp index 910787b597..ab56ca34b0 100644 --- a/libraries/SITL/SIM_Tracker.cpp +++ b/libraries/SITL/SIM_Tracker.cpp @@ -25,7 +25,7 @@ namespace SITL { /* update function for position (normal) servos. */ -void Tracker::update_position_servos(float delta_time, float &yaw_rate, float &pitch_rate) +void Tracker::update_position_servos(float delta_time, float &yaw_rate, float &pitch_rate) const { float pitch_target = pitch_input*pitch_range; float yaw_target = yaw_input*yaw_range; @@ -39,7 +39,7 @@ void Tracker::update_position_servos(float delta_time, float &yaw_rate, float &p These servos either move at a constant rate or are still Returns (yaw_rate,pitch_rate) tuple */ -void Tracker::update_onoff_servos(float &yaw_rate, float &pitch_rate) +void Tracker::update_onoff_servos(float &yaw_rate, float &pitch_rate) const { if (fabsf(yaw_input) < 0.1) { yaw_rate = 0; diff --git a/libraries/SITL/SIM_Tracker.h b/libraries/SITL/SIM_Tracker.h index 4f1083dd84..028fee4217 100644 --- a/libraries/SITL/SIM_Tracker.h +++ b/libraries/SITL/SIM_Tracker.h @@ -52,8 +52,8 @@ private: float yaw_current_relative; float pitch_current_relative; - void update_position_servos(float delta_time, float &yaw_rate, float &pitch_rate); - void update_onoff_servos(float &yaw_rate, float &pitch_rate); + void update_position_servos(float delta_time, float &yaw_rate, float &pitch_rate) const; + void update_onoff_servos(float &yaw_rate, float &pitch_rate) const; }; } // namespace SITL diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 0c1d8078c0..3bad672032 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -396,7 +396,7 @@ const AP_Param::GroupInfo SITL::var_ins[] = { }; /* report SITL state via MAVLink SIMSTATE*/ -void SITL::simstate_send(mavlink_channel_t chan) +void SITL::simstate_send(mavlink_channel_t chan) const { float yaw; @@ -421,7 +421,7 @@ void SITL::simstate_send(mavlink_channel_t chan) } /* report SITL state via MAVLink SIM_STATE */ -void SITL::sim_state_send(mavlink_channel_t chan) +void SITL::sim_state_send(mavlink_channel_t chan) const { // convert to same conventions as DCM float yaw = state.yawDeg; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 24e413ed4b..0c585cb09c 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -376,8 +376,8 @@ public: time_t start_time_UTC; - void simstate_send(mavlink_channel_t chan); - void sim_state_send(mavlink_channel_t chan); + void simstate_send(mavlink_channel_t chan) const; + void sim_state_send(mavlink_channel_t chan) const; void Log_Write_SIMSTATE(); @@ -434,8 +434,8 @@ public: float get_rangefinder(uint8_t instance); // get the apparent wind speed and direction as set by external physics backend - float get_apparent_wind_dir(){return state.wind_vane_apparent.direction;} - float get_apparent_wind_spd(){return state.wind_vane_apparent.speed;} + float get_apparent_wind_dir() const{return state.wind_vane_apparent.direction;} + float get_apparent_wind_spd() const{return state.wind_vane_apparent.speed;} // IMU temperature calibration params AP_Float imu_temp_start;