AP_Compass: Add missing const in member functions

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-01 13:26:27 -03:00 committed by Andrew Tridgell
parent 5375980aa6
commit 842360b5e3
6 changed files with 11 additions and 11 deletions

View File

@ -386,7 +386,7 @@ private:
uint8_t _get_cal_mask();
bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f);
bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false);
bool _auto_reboot() { return _compass_cal_autoreboot; }
bool _auto_reboot() const { return _compass_cal_autoreboot; }
Priority next_cal_progress_idx[MAVLINK_COMM_NUM_BUFFERS];
Priority next_cal_report_idx[MAVLINK_COMM_NUM_BUFFERS];
@ -397,7 +397,7 @@ private:
get mag field with the effects of offsets, diagonals and
off-diagonals removed
*/
bool get_uncorrected_field(uint8_t instance, Vector3f &field);
bool get_uncorrected_field(uint8_t instance, Vector3f &field) const;
#if COMPASS_CAL_ENABLED
//keep track of which calibrators have been saved

View File

@ -244,7 +244,7 @@ bus_error:
* Compensation algorithm got from https://github.com/BoschSensortec/BMM050_driver
* this is not explained in datasheet.
*/
int16_t AP_Compass_BMM150::_compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2)
int16_t AP_Compass_BMM150::_compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2) const
{
int32_t inter = ((int32_t)_dig.xyz1) << 14;
inter /= rhall;
@ -263,7 +263,7 @@ int16_t AP_Compass_BMM150::_compensate_xy(int16_t xy, uint32_t rhall, int32_t tx
return val;
}
int16_t AP_Compass_BMM150::_compensate_z(int16_t z, uint32_t rhall)
int16_t AP_Compass_BMM150::_compensate_z(int16_t z, uint32_t rhall) const
{
int32_t dividend = int32_t(z - _dig.z4) << 15;
int32_t dividend2 = dividend - ((_dig.z3 * (int32_t(rhall) - int32_t(_dig.xyz1))) >> 2);

View File

@ -45,8 +45,8 @@ private:
bool init();
void _update();
bool _load_trim_values();
int16_t _compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2);
int16_t _compensate_z(int16_t z, uint32_t rhall);
int16_t _compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2) const;
int16_t _compensate_z(int16_t z, uint32_t rhall) const;
AP_HAL::OwnPtr<AP_HAL::Device> _dev;

View File

@ -428,7 +428,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
get mag field with the effects of offsets, diagonals and
off-diagonals removed
*/
bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field)
bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const
{
// form eliptical correction matrix and invert it. This is
// needed to remove the effects of the eliptical correction

View File

@ -459,7 +459,7 @@ bool CompassCalibrator::set_status(CompassCalibrator::Status status)
};
}
bool CompassCalibrator::fit_acceptable()
bool CompassCalibrator::fit_acceptable() const
{
if (!isnan(_fitness) &&
_params.radius > FIELD_RADIUS_MIN && _params.radius < FIELD_RADIUS_MAX &&
@ -845,7 +845,7 @@ void CompassCalibrator::AttitudeSample::set_from_ahrs(void)
yaw = constrain_int16(127 * (yaw_rad / M_PI), -127, 127);
}
Matrix3f CompassCalibrator::AttitudeSample::get_rotmat(void)
Matrix3f CompassCalibrator::AttitudeSample::get_rotmat(void) const
{
float roll_rad, pitch_rad, yaw_rad;
roll_rad = roll * (M_PI / 127);

View File

@ -114,7 +114,7 @@ private:
// compact class for approximate attitude, to save memory
class AttitudeSample {
public:
Matrix3f get_rotmat();
Matrix3f get_rotmat() const;
void set_from_ahrs();
private:
int8_t roll;
@ -145,7 +145,7 @@ private:
bool accept_sample(const CompassSample &sample, uint16_t skip_index = UINT16_MAX);
// returns true if fit is acceptable
bool fit_acceptable();
bool fit_acceptable() const;
// clear sample buffer and reset offsets and scaling to their defaults
void reset_state();