mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
AP_InertialSensor: unify singleton naming to _singleton and get_singleton()
This commit is contained in:
parent
28323147ab
commit
9347e6d36f
@ -455,16 +455,16 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
AP_InertialSensor *AP_InertialSensor::_s_instance = nullptr;
|
||||
AP_InertialSensor *AP_InertialSensor::_singleton = nullptr;
|
||||
|
||||
AP_InertialSensor::AP_InertialSensor() :
|
||||
_board_orientation(ROTATION_NONE),
|
||||
_log_raw_bit(-1)
|
||||
{
|
||||
if (_s_instance) {
|
||||
if (_singleton) {
|
||||
AP_HAL::panic("Too many inertial sensors");
|
||||
}
|
||||
_s_instance = this;
|
||||
_singleton = this;
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
|
||||
_gyro_cal_ok[i] = true;
|
||||
@ -481,12 +481,12 @@ AP_InertialSensor::AP_InertialSensor() :
|
||||
/*
|
||||
* Get the AP_InertialSensor singleton
|
||||
*/
|
||||
AP_InertialSensor *AP_InertialSensor::get_instance()
|
||||
AP_InertialSensor *AP_InertialSensor::get_singleton()
|
||||
{
|
||||
if (!_s_instance) {
|
||||
_s_instance = new AP_InertialSensor();
|
||||
if (!_singleton) {
|
||||
_singleton = new AP_InertialSensor();
|
||||
}
|
||||
return _s_instance;
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
/*
|
||||
@ -1994,7 +1994,7 @@ namespace AP {
|
||||
|
||||
AP_InertialSensor &ins()
|
||||
{
|
||||
return *AP_InertialSensor::get_instance();
|
||||
return *AP_InertialSensor::get_singleton();
|
||||
}
|
||||
|
||||
};
|
||||
|
@ -55,7 +55,7 @@ public:
|
||||
AP_InertialSensor(const AP_InertialSensor &other) = delete;
|
||||
AP_InertialSensor &operator=(const AP_InertialSensor&) = delete;
|
||||
|
||||
static AP_InertialSensor *get_instance();
|
||||
static AP_InertialSensor *get_singleton();
|
||||
|
||||
enum Gyro_Calibration_Timing {
|
||||
GYRO_CAL_NEVER = 0,
|
||||
@ -553,7 +553,7 @@ private:
|
||||
AP_Int8 _acc_body_aligned;
|
||||
AP_Int8 _trim_option;
|
||||
|
||||
static AP_InertialSensor *_s_instance;
|
||||
static AP_InertialSensor *_singleton;
|
||||
AP_AccelCal* _acal;
|
||||
|
||||
AccelCalibrator *_accel_calibrator;
|
||||
|
@ -216,7 +216,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
|
||||
|
||||
void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro)
|
||||
{
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
// should not have been called
|
||||
return;
|
||||
@ -348,7 +348,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_sensor_rate_sample(uint8_t inst
|
||||
|
||||
void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel)
|
||||
{
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
// should not have been called
|
||||
return;
|
||||
@ -465,7 +465,7 @@ bool AP_InertialSensor_Backend::should_log_imu_raw() const
|
||||
// tracker does not set a bit
|
||||
return false;
|
||||
}
|
||||
const AP_Logger *instance = AP_Logger::instance();
|
||||
const AP_Logger *instance = AP_Logger::get_singleton();
|
||||
if (instance == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
@ -176,7 +176,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
|
||||
// avoid flooding AP_Logger's buffer
|
||||
return;
|
||||
}
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
// should not have been called
|
||||
return;
|
||||
@ -250,7 +250,7 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T
|
||||
if (data_write_offset >= _required_count) {
|
||||
return false;
|
||||
}
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user