SRV_Channels: unify singleton naming to _singleton and get_singleton()

This commit is contained in:
Tom Pittenger 2019-02-09 20:59:44 -08:00 committed by Tom Pittenger
parent ee97f0dccd
commit 9e3cf3ad33
3 changed files with 4 additions and 4 deletions

View File

@ -471,7 +471,7 @@ private:
// this static arrangement is to avoid having static objects in AP_Param tables
static SRV_Channel *channels;
static SRV_Channels *instance;
static SRV_Channels *_singleton;
// support for Volz protocol
AP_Volz_Protocol volz;

View File

@ -153,7 +153,7 @@ void SRV_Channels::update_aux_servo_function(void)
/// Should be called after the the servo functions have been initialized
void SRV_Channels::enable_aux_servos()
{
hal.rcout->set_default_rate(uint16_t(instance->default_rate.get()));
hal.rcout->set_default_rate(uint16_t(_singleton->default_rate.get()));
update_aux_servo_function();

View File

@ -36,7 +36,7 @@
extern const AP_HAL::HAL& hal;
SRV_Channel *SRV_Channels::channels;
SRV_Channels *SRV_Channels::instance;
SRV_Channels *SRV_Channels::_singleton;
AP_Volz_Protocol *SRV_Channels::volz_ptr;
AP_SBusOut *SRV_Channels::sbus_ptr;
AP_RobotisServo *SRV_Channels::robotis_ptr;
@ -160,7 +160,7 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
*/
SRV_Channels::SRV_Channels(void)
{
instance = this;
_singleton = this;
channels = obj_channels;
// set defaults from the parameter table