mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_Mount: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
bdc14c60fb
commit
cc39e36ee1
@ -337,7 +337,7 @@ Vector3f SoloGimbal::get_ang_vel_dem_roll_tilt(const Quaternion &quatEst)
|
||||
return gimbalRateDemVecTilt;
|
||||
}
|
||||
|
||||
Vector3f SoloGimbal::get_ang_vel_dem_feedforward(const Quaternion &quatEst)
|
||||
Vector3f SoloGimbal::get_ang_vel_dem_feedforward(const Quaternion &quatEst) const
|
||||
{
|
||||
// quaternion demanded at the previous time step
|
||||
static float lastDemY;
|
||||
@ -481,7 +481,7 @@ void SoloGimbal::write_logs()
|
||||
_log_del_vel.zero();
|
||||
}
|
||||
|
||||
bool SoloGimbal::joints_near_limits()
|
||||
bool SoloGimbal::joints_near_limits() const
|
||||
{
|
||||
return fabsf(_measurement.joint_angles.x) > radians(40) || _measurement.joint_angles.y > radians(45) || _measurement.joint_angles.y < -radians(135);
|
||||
}
|
||||
@ -518,7 +518,7 @@ void SoloGimbal::_acal_save_calibrations()
|
||||
_gimbalParams.flash();
|
||||
}
|
||||
|
||||
void SoloGimbal::gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f& joint_rates)
|
||||
void SoloGimbal::gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f& joint_rates) const
|
||||
{
|
||||
float sin_theta = sinf(_measurement.joint_angles.y);
|
||||
float cos_theta = cosf(_measurement.joint_angles.y);
|
||||
@ -533,7 +533,7 @@ void SoloGimbal::gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f
|
||||
joint_rates.z = sec_phi*(ang_vel.z*cos_theta-ang_vel.x*sin_theta);
|
||||
}
|
||||
|
||||
void SoloGimbal::joint_rates_to_gimbal_ang_vel(const Vector3f& joint_rates, Vector3f& ang_vel)
|
||||
void SoloGimbal::joint_rates_to_gimbal_ang_vel(const Vector3f& joint_rates, Vector3f& ang_vel) const
|
||||
{
|
||||
float sin_theta = sinf(_measurement.joint_angles.y);
|
||||
float cos_theta = cosf(_measurement.joint_angles.y);
|
||||
|
@ -66,7 +66,7 @@ public:
|
||||
|
||||
void write_logs();
|
||||
|
||||
float get_log_dt() { return _log_dt; }
|
||||
float get_log_dt() const { return _log_dt; }
|
||||
|
||||
void disable_torque_report() { _gimbalParams.set_param(GMB_PARAM_GMB_SND_TORQUE, 0); }
|
||||
void fetch_params() { _gimbalParams.fetch_params(); }
|
||||
@ -84,12 +84,12 @@ private:
|
||||
|
||||
Vector3f get_ang_vel_dem_yaw(const Quaternion &quatEst);
|
||||
Vector3f get_ang_vel_dem_roll_tilt(const Quaternion &quatEst);
|
||||
Vector3f get_ang_vel_dem_feedforward(const Quaternion &quatEst);
|
||||
Vector3f get_ang_vel_dem_feedforward(const Quaternion &quatEst) const;
|
||||
Vector3f get_ang_vel_dem_gyro_bias();
|
||||
Vector3f get_ang_vel_dem_body_lock();
|
||||
|
||||
void gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f& joint_rates);
|
||||
void joint_rates_to_gimbal_ang_vel(const Vector3f& joint_rates, Vector3f& ang_vel);
|
||||
void gimbal_ang_vel_to_joint_rates(const Vector3f& ang_vel, Vector3f& joint_rates) const;
|
||||
void joint_rates_to_gimbal_ang_vel(const Vector3f& joint_rates, Vector3f& ang_vel) const;
|
||||
|
||||
void readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng);
|
||||
|
||||
@ -100,7 +100,7 @@ private:
|
||||
|
||||
gimbal_mode_t get_mode();
|
||||
|
||||
bool joints_near_limits();
|
||||
bool joints_near_limits() const;
|
||||
|
||||
// private member variables
|
||||
SoloGimbalEKF _ekf; // state of small EKF for gimbal
|
||||
|
Loading…
Reference in New Issue
Block a user