mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
7b6f1225ba
commit
07c3435f9d
@ -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
|
||||
|
@ -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 );
|
||||
|
@ -40,7 +40,7 @@ private:
|
||||
|
||||
float skid_turn_rate;
|
||||
|
||||
float calc_yaw_rate(float steering);
|
||||
float calc_yaw_rate(float steering) const;
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
@ -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<ARRAY_SIZE(soc_table); i++) {
|
||||
|
@ -45,7 +45,7 @@ private:
|
||||
// 10Hz filter for battery voltage
|
||||
LowPassFilterFloat voltage_filter{10};
|
||||
|
||||
float get_resting_voltage(float charge_pct);
|
||||
float get_resting_voltage(float charge_pct) const;
|
||||
void set_initial_SoC(float voltage);
|
||||
};
|
||||
}
|
||||
|
@ -101,7 +101,7 @@ void Gripper_EPM::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
|
||||
bool Gripper_EPM::should_report()
|
||||
bool Gripper_EPM::should_report() const
|
||||
{
|
||||
if (AP_HAL::micros64() - last_report_us < report_interval) {
|
||||
return false;
|
||||
@ -114,7 +114,7 @@ bool Gripper_EPM::should_report()
|
||||
return false;
|
||||
}
|
||||
|
||||
float Gripper_EPM::tesla()
|
||||
float Gripper_EPM::tesla() const
|
||||
{
|
||||
// https://en.wikipedia.org/wiki/Orders_of_magnitude_(magnetic_field)
|
||||
// 200N lifting capacity ~= 2.5T
|
||||
|
@ -58,12 +58,12 @@ private:
|
||||
|
||||
uint64_t last_update_us;
|
||||
|
||||
bool should_report();
|
||||
bool should_report() const;
|
||||
|
||||
void update_from_demand();
|
||||
void update_servobased(int16_t gripper_pwm);
|
||||
|
||||
float tesla();
|
||||
float tesla() const;
|
||||
|
||||
float demand;
|
||||
};
|
||||
|
@ -114,7 +114,7 @@ void Gripper_Servo::update(const struct sitl_input &input)
|
||||
last_update_us = now;
|
||||
}
|
||||
|
||||
bool Gripper_Servo::should_report()
|
||||
bool Gripper_Servo::should_report() const
|
||||
{
|
||||
if (AP_HAL::micros64() - last_report_us < report_interval) {
|
||||
return false;
|
||||
|
@ -58,7 +58,7 @@ private:
|
||||
|
||||
uint64_t last_update_us;
|
||||
|
||||
bool should_report();
|
||||
bool should_report() const;
|
||||
|
||||
// dangle load from a string:
|
||||
const float string_length = 2.0f; // metres
|
||||
|
@ -255,7 +255,7 @@ bool JSBSim::start_JSBSim(void)
|
||||
/*
|
||||
check for stdout from JSBSim
|
||||
*/
|
||||
void JSBSim::check_stdout(void)
|
||||
void JSBSim::check_stdout(void) const
|
||||
{
|
||||
char line[100];
|
||||
ssize_t ret = ::read(jsbsim_stdout, line, sizeof(line));
|
||||
@ -269,7 +269,7 @@ void JSBSim::check_stdout(void)
|
||||
/*
|
||||
a simple function to wait for a string on jsbsim_stdout
|
||||
*/
|
||||
bool JSBSim::expect(const char *str)
|
||||
bool JSBSim::expect(const char *str) const
|
||||
{
|
||||
const char *basestr = str;
|
||||
while (*str) {
|
||||
|
@ -74,8 +74,8 @@ private:
|
||||
bool open_fdm_socket(void);
|
||||
void send_servos(const struct sitl_input &input);
|
||||
void recv_fdm(const struct sitl_input &input);
|
||||
void check_stdout(void);
|
||||
bool expect(const char *str);
|
||||
void check_stdout(void) const;
|
||||
bool expect(const char *str) const;
|
||||
|
||||
void drain_control_socket();
|
||||
};
|
||||
|
@ -121,7 +121,7 @@ void Motor::calculate_forces(const struct sitl_input &input,
|
||||
/*
|
||||
update and return current value of a servo. Calculated as 1000..2000
|
||||
*/
|
||||
uint16_t Motor::update_servo(uint16_t demand, uint64_t time_usec, float &last_value)
|
||||
uint16_t Motor::update_servo(uint16_t demand, uint64_t time_usec, float &last_value) const
|
||||
{
|
||||
if (servo_rate <= 0) {
|
||||
return demand;
|
||||
|
@ -79,7 +79,7 @@ public:
|
||||
float effective_prop_area,
|
||||
float voltage);
|
||||
|
||||
uint16_t update_servo(uint16_t demand, uint64_t time_usec, float &last_value);
|
||||
uint16_t update_servo(uint16_t demand, uint64_t time_usec, float &last_value) const;
|
||||
|
||||
// get current
|
||||
float get_current(void) const;
|
||||
|
@ -60,7 +60,7 @@ void Parachute::update(const struct sitl_input &input)
|
||||
last_update_us = now;
|
||||
}
|
||||
|
||||
bool Parachute::should_report()
|
||||
bool Parachute::should_report() const
|
||||
{
|
||||
if (AP_HAL::micros64() - last_report_us < report_interval) {
|
||||
return false;
|
||||
|
@ -51,7 +51,7 @@ public:
|
||||
|
||||
uint64_t last_update_us;
|
||||
|
||||
bool should_report();
|
||||
bool should_report() const;
|
||||
bool zero_report_done = false;
|
||||
};
|
||||
|
||||
|
@ -42,7 +42,7 @@ SimRover::SimRover(const char *frame_str) :
|
||||
/*
|
||||
return turning circle (diameter) in meters for steering angle proportion in degrees
|
||||
*/
|
||||
float SimRover::turn_circle(float steering)
|
||||
float SimRover::turn_circle(float steering) const
|
||||
{
|
||||
if (fabsf(steering) < 1.0e-6) {
|
||||
return 0;
|
||||
|
@ -45,7 +45,7 @@ private:
|
||||
float skid_turn_rate = 140.0f;
|
||||
bool skid_steering;
|
||||
|
||||
float turn_circle(float steering);
|
||||
float turn_circle(float steering) const;
|
||||
float calc_yaw_rate(float steering, float speed);
|
||||
float calc_lat_accel(float steering_angle, float speed);
|
||||
};
|
||||
|
@ -75,7 +75,7 @@ bool SerialDevice::init_sitl_pointer()
|
||||
}
|
||||
|
||||
|
||||
ssize_t SerialDevice::read_from_autopilot(char *buffer, const size_t size)
|
||||
ssize_t SerialDevice::read_from_autopilot(char *buffer, const size_t size) const
|
||||
{
|
||||
const ssize_t ret = ::read(read_fd_my_end, buffer, size);
|
||||
// if (ret > 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: (");
|
||||
|
@ -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:
|
||||
|
||||
|
@ -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.
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user