mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: unify singleton naming to _singleton and get_singleton()
This commit is contained in:
parent
4ece7fd4f0
commit
3bbd80a5de
|
@ -27,7 +27,7 @@
|
|||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// singleton instance
|
||||
AP_Motors *AP_Motors::_instance;
|
||||
AP_Motors *AP_Motors::_singleton;
|
||||
|
||||
// Constructor
|
||||
AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
|
@ -38,7 +38,7 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
|||
_spool_mode(SHUT_DOWN),
|
||||
_air_density_ratio(1.0f)
|
||||
{
|
||||
_instance = this;
|
||||
_singleton = this;
|
||||
|
||||
// setup throttle filtering
|
||||
_throttle_filter.set_cutoff_frequency(0.0f);
|
||||
|
|
|
@ -64,7 +64,7 @@ public:
|
|||
AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
||||
|
||||
// singleton support
|
||||
static AP_Motors *get_instance(void) { return _instance; }
|
||||
static AP_Motors *get_singleton(void) { return _singleton; }
|
||||
|
||||
// check initialisation succeeded
|
||||
bool initialised_ok() const { return _flags.initialised_ok; }
|
||||
|
@ -244,5 +244,5 @@ protected:
|
|||
float _thrust_boost_ratio; // choice between highest and second highest motor output for output mixing (0 ~ 1). Zero is normal operation
|
||||
|
||||
private:
|
||||
static AP_Motors *_instance;
|
||||
static AP_Motors *_singleton;
|
||||
};
|
||||
|
|
|
@ -118,7 +118,7 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mav
|
|||
_gimbal.update_target(_angle_ef_target_rad);
|
||||
_gimbal.receive_feedback(chan,msg);
|
||||
|
||||
AP_Logger *df = AP_Logger::instance();
|
||||
AP_Logger *df = AP_Logger::get_singleton();
|
||||
if (df == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -383,7 +383,7 @@ void SoloGimbal::update_target(const Vector3f &newTarget)
|
|||
|
||||
void SoloGimbal::write_logs()
|
||||
{
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -185,7 +185,7 @@ void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t *msg)
|
|||
mavlink_param_value_t packet;
|
||||
mavlink_msg_param_value_decode(msg, &packet);
|
||||
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
AP_Logger *dataflash = AP_Logger::get_singleton();
|
||||
if (dataflash != nullptr) {
|
||||
dataflash->Write_Parameter(packet.param_id, packet.param_value);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue