AP_BLHeli: unify singleton naming to _singleton and get_singleton()

This commit is contained in:
Tom Pittenger 2019-02-10 10:32:48 -08:00 committed by Tom Pittenger
parent ab95c8e5ee
commit 0f311ba04f
2 changed files with 7 additions and 7 deletions

View File

@ -118,14 +118,14 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
AP_GROUPEND
};
AP_BLHeli *AP_BLHeli::singleton;
AP_BLHeli *AP_BLHeli::_singleton;
// constructor
AP_BLHeli::AP_BLHeli(void)
{
// set defaults from the parameter table
AP_Param::setup_object_defaults(this, var_info);
singleton = this;
_singleton = this;
last_control_port = -1;
}
@ -1250,7 +1250,7 @@ void AP_BLHeli::update(void)
plane and copter can use AP_Motors to get an automatic mask
*/
if (channel_auto.get() == 1) {
AP_Motors *motors = AP_Motors::get_instance();
AP_Motors *motors = AP_Motors::get_singleton();
if (motors) {
mask |= motors->get_motor_mask();
}
@ -1273,7 +1273,7 @@ void AP_BLHeli::update(void)
debug("ESC: %u motors mask=0x%04x", num_motors, mask);
if (telem_rate > 0) {
AP_SerialManager *serial_manager = AP_SerialManager::get_instance();
AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
if (serial_manager) {
telem_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_ESCTelemetry,0);
}
@ -1346,7 +1346,7 @@ void AP_BLHeli::read_telemetry_packet(void)
last_telem[last_telem_esc] = td;
last_telem[last_telem_esc].count++;
AP_Logger *df = AP_Logger::instance();
AP_Logger *df = AP_Logger::get_singleton();
if (df && df->logging_enabled()) {
struct log_Esc pkt = {
LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC1_MSG+last_telem_esc)),

View File

@ -59,14 +59,14 @@ public:
bool get_telem_data(uint8_t esc_index, struct telem_data &td);
static AP_BLHeli *get_singleton(void) {
return singleton;
return _singleton;
}
// send ESC telemetry messages over MAVLink
void send_esc_telemetry_mavlink(uint8_t mav_chan);
private:
static AP_BLHeli *singleton;
static AP_BLHeli *_singleton;
// mask of channels to use for BLHeli protocol
AP_Int32 channel_mask;