Browse Source

SRV_Channels: unify singleton naming to _singleton and get_singleton()

master
Tom Pittenger 6 years ago committed by Tom Pittenger
parent
commit
9e3cf3ad33
  1. 2
      libraries/SRV_Channel/SRV_Channel.h
  2. 2
      libraries/SRV_Channel/SRV_Channel_aux.cpp
  3. 4
      libraries/SRV_Channel/SRV_Channels.cpp

2
libraries/SRV_Channel/SRV_Channel.h

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

2
libraries/SRV_Channel/SRV_Channel_aux.cpp

@ -153,7 +153,7 @@ void SRV_Channels::update_aux_servo_function(void)
/// Should be called after the the servo functions have been initialized /// Should be called after the the servo functions have been initialized
void SRV_Channels::enable_aux_servos() 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(); update_aux_servo_function();

4
libraries/SRV_Channel/SRV_Channels.cpp

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

Loading…
Cancel
Save