SRV_Channel: create and use a singleton for SRV_Channels

avoid creation of static pointers to objects held within SRV_Channels
This commit is contained in:
Peter Barker 2024-11-09 18:17:28 +11:00 committed by Andrew Tridgell
parent c1f04b507e
commit a0eef1039c
3 changed files with 24 additions and 56 deletions

View File

@ -473,7 +473,7 @@ public:
int16_t value, int16_t angle_min, int16_t angle_max); int16_t value, int16_t angle_min, int16_t angle_max);
// assign and enable auxiliary channels // assign and enable auxiliary channels
static void enable_aux_servos(void); void enable_aux_servos(void);
// enable channels by mask // enable channels by mask
static void enable_by_mask(uint32_t mask); static void enable_by_mask(uint32_t mask);
@ -541,7 +541,7 @@ public:
static void cork(); static void cork();
static void push(); void push();
// disable PWM output to a set of channels given by a mask. This is used by the AP_BLHeli code // disable PWM output to a set of channels given by a mask. This is used by the AP_BLHeli code
static void set_disabled_channel_mask(uint32_t mask) { disabled_mask = mask; } static void set_disabled_channel_mask(uint32_t mask) { disabled_mask = mask; }
@ -570,7 +570,7 @@ public:
static void zero_rc_outputs(); static void zero_rc_outputs();
// initialize before any call to push // initialize before any call to push
static void init(uint32_t motor_mask = 0, AP_HAL::RCOutput::output_mode mode = AP_HAL::RCOutput::MODE_PWM_NONE); void init(uint32_t motor_mask = 0, AP_HAL::RCOutput::output_mode mode = AP_HAL::RCOutput::MODE_PWM_NONE);
// return true if a channel is set to type GPIO // return true if a channel is set to type GPIO
static bool is_GPIO(uint8_t channel); static bool is_GPIO(uint8_t channel);
@ -610,30 +610,25 @@ private:
#if AP_VOLZ_ENABLED #if AP_VOLZ_ENABLED
// support for Volz protocol // support for Volz protocol
AP_Volz_Protocol volz; AP_Volz_Protocol volz;
static AP_Volz_Protocol *volz_ptr;
#endif #endif
#if AP_SBUSOUTPUT_ENABLED #if AP_SBUSOUTPUT_ENABLED
// support for SBUS protocol // support for SBUS protocol
AP_SBusOut sbus; AP_SBusOut sbus;
static AP_SBusOut *sbus_ptr;
#endif #endif
#if AP_ROBOTISSERVO_ENABLED #if AP_ROBOTISSERVO_ENABLED
// support for Robotis servo protocol // support for Robotis servo protocol
AP_RobotisServo robotis; AP_RobotisServo robotis;
static AP_RobotisServo *robotis_ptr;
#endif #endif
#if HAL_SUPPORT_RCOUT_SERIAL #if HAL_SUPPORT_RCOUT_SERIAL
// support for BLHeli protocol // support for BLHeli protocol
AP_BLHeli blheli; AP_BLHeli blheli;
static AP_BLHeli *blheli_ptr;
#endif #endif
#if AP_FETTEC_ONEWIRE_ENABLED #if AP_FETTEC_ONEWIRE_ENABLED
AP_FETtecOneWire fetteconwire; AP_FETtecOneWire fetteconwire;
static AP_FETtecOneWire *fetteconwire_ptr;
#endif // AP_FETTEC_ONEWIRE_ENABLED #endif // AP_FETTEC_ONEWIRE_ENABLED
// mask of disabled channels // mask of disabled channels
@ -692,3 +687,7 @@ private:
// semaphore for multi-thread use of override_counter array // semaphore for multi-thread use of override_counter array
HAL_Semaphore override_counter_sem; HAL_Semaphore override_counter_sem;
}; };
namespace AP {
SRV_Channels &srv();
};

View File

@ -270,7 +270,7 @@ void SRV_Channels::enable_aux_servos()
hal.rcout->update_channel_masks(); hal.rcout->update_channel_masks();
#if HAL_SUPPORT_RCOUT_SERIAL #if HAL_SUPPORT_RCOUT_SERIAL
blheli_ptr->update(); blheli.update();
#endif #endif
} }

View File

@ -41,28 +41,8 @@ extern const AP_HAL::HAL& hal;
SRV_Channel *SRV_Channels::channels; SRV_Channel *SRV_Channels::channels;
SRV_Channels *SRV_Channels::_singleton; SRV_Channels *SRV_Channels::_singleton;
#if AP_VOLZ_ENABLED
AP_Volz_Protocol *SRV_Channels::volz_ptr;
#endif
#if AP_SBUSOUTPUT_ENABLED
AP_SBusOut *SRV_Channels::sbus_ptr;
#endif
#if AP_ROBOTISSERVO_ENABLED
AP_RobotisServo *SRV_Channels::robotis_ptr;
#endif
#if AP_FETTEC_ONEWIRE_ENABLED
AP_FETtecOneWire *SRV_Channels::fetteconwire_ptr;
#endif
uint16_t SRV_Channels::override_counter[NUM_SERVO_CHANNELS]; uint16_t SRV_Channels::override_counter[NUM_SERVO_CHANNELS];
#if HAL_SUPPORT_RCOUT_SERIAL
AP_BLHeli *SRV_Channels::blheli_ptr;
#endif
uint32_t SRV_Channels::disabled_mask; uint32_t SRV_Channels::disabled_mask;
uint32_t SRV_Channels::digital_mask; uint32_t SRV_Channels::digital_mask;
uint32_t SRV_Channels::reversible_mask; uint32_t SRV_Channels::reversible_mask;
@ -379,26 +359,6 @@ SRV_Channels::SRV_Channels(void)
} }
#endif #endif
} }
#if AP_FETTEC_ONEWIRE_ENABLED
fetteconwire_ptr = &fetteconwire;
#endif
#if AP_VOLZ_ENABLED
volz_ptr = &volz;
#endif
#if AP_SBUSOUTPUT_ENABLED
sbus_ptr = &sbus;
#endif
#if AP_ROBOTISSERVO_ENABLED
robotis_ptr = &robotis;
#endif // AP_ROBOTISSERVO_ENABLED
#if HAL_SUPPORT_RCOUT_SERIAL
blheli_ptr = &blheli;
#endif
} }
// SRV_Channels initialization // SRV_Channels initialization
@ -406,7 +366,7 @@ void SRV_Channels::init(uint32_t motor_mask, AP_HAL::RCOutput::output_mode mode)
{ {
// initialize BLHeli late so that all of the masks it might setup don't get trodden on by motor initialization // initialize BLHeli late so that all of the masks it might setup don't get trodden on by motor initialization
#if HAL_SUPPORT_RCOUT_SERIAL #if HAL_SUPPORT_RCOUT_SERIAL
blheli_ptr->init(motor_mask, mode); blheli.init(motor_mask, mode);
#endif #endif
#ifndef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
hal.rcout->set_dshot_rate(_singleton->dshot_rate, AP::scheduler().get_loop_rate_hz()); hal.rcout->set_dshot_rate(_singleton->dshot_rate, AP::scheduler().get_loop_rate_hz());
@ -519,26 +479,26 @@ void SRV_Channels::push()
#if AP_VOLZ_ENABLED #if AP_VOLZ_ENABLED
// give volz library a chance to update // give volz library a chance to update
volz_ptr->update(); volz.update();
#endif #endif
#if AP_SBUSOUTPUT_ENABLED #if AP_SBUSOUTPUT_ENABLED
// give sbus library a chance to update // give sbus library a chance to update
sbus_ptr->update(); sbus.update();
#endif #endif
#if AP_ROBOTISSERVO_ENABLED #if AP_ROBOTISSERVO_ENABLED
// give robotis library a chance to update // give robotis library a chance to update
robotis_ptr->update(); robotis.update();
#endif #endif
#if HAL_SUPPORT_RCOUT_SERIAL #if HAL_SUPPORT_RCOUT_SERIAL
// give blheli telemetry a chance to update // give blheli telemetry a chance to update
blheli_ptr->update_telemetry(); blheli.update_telemetry();
#endif #endif
#if AP_FETTEC_ONEWIRE_ENABLED #if AP_FETTEC_ONEWIRE_ENABLED
fetteconwire_ptr->update(); fetteconwire.update();
#endif #endif
#if AP_KDECAN_ENABLED #if AP_KDECAN_ENABLED
@ -589,7 +549,7 @@ void SRV_Channels::zero_rc_outputs()
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) { for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
hal.rcout->write(i, 0); hal.rcout->write(i, 0);
} }
push(); AP::srv().push();
} }
/* /*
@ -619,3 +579,12 @@ void SRV_Channels::set_emergency_stop(bool state) {
#endif #endif
emergency_stop = state; emergency_stop = state;
} }
namespace AP {
SRV_Channels &srv()
{
return *SRV_Channels::get_singleton();
}
};