2020-02-10 00:13:22 -04:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
# include "AP_ESC_Telem.h"
# include <AP_HAL/AP_HAL.h>
2021-02-23 18:04:06 -04:00
# include <GCS_MAVLink/GCS.h>
# include <AP_Logger/AP_Logger.h>
2020-02-10 00:13:22 -04:00
2021-02-23 18:04:06 -04:00
# if HAL_WITH_ESC_TELEM
# include <AP_BoardConfig/AP_BoardConfig.h>
//#define ESC_TELEM_DEBUG
2020-02-10 00:13:22 -04:00
extern const AP_HAL : : HAL & hal ;
2022-06-06 01:40:25 -03:00
// table of user settable parameters
const AP_Param : : GroupInfo AP_ESC_Telem : : var_info [ ] = {
// @Param: _MAV_OFS
// @DisplayName: ESC Telemetry mavlink offset
// @Description: Offset to apply to ESC numbers when reporting as ESC_TELEMETRY packets over MAVLink. This allows high numbered motors to be displayed as low numbered ESCs for convenience on GCS displays. A value of 4 would send ESC on output 5 as ESC number 1 in ESC_TELEMETRY packets
// @Increment: 1
// @Range: 0 31
// @User: Standard
AP_GROUPINFO ( " _MAV_OFS " , 1 , AP_ESC_Telem , mavlink_offset , 0 ) ,
AP_GROUPEND
} ;
2020-02-10 00:13:22 -04:00
AP_ESC_Telem : : AP_ESC_Telem ( )
{
if ( _singleton ) {
AP_HAL : : panic ( " Too many AP_ESC_Telem instances " ) ;
}
_singleton = this ;
2022-06-06 01:40:25 -03:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
2020-02-10 00:13:22 -04:00
}
2021-07-05 19:31:40 -03:00
// return the average motor RPM
float AP_ESC_Telem : : get_average_motor_rpm ( uint32_t servo_channel_mask ) const
2021-02-23 18:04:06 -04:00
{
2021-07-05 19:31:40 -03:00
float rpm_avg = 0.0f ;
2021-02-23 18:04:06 -04:00
uint8_t valid_escs = 0 ;
2021-07-05 19:31:40 -03:00
// average the rpm of each motor
2021-02-23 18:04:06 -04:00
for ( uint8_t i = 0 ; i < ESC_TELEM_MAX_ESCS ; i + + ) {
2021-06-03 04:27:27 -03:00
if ( BIT_IS_SET ( servo_channel_mask , i ) ) {
float rpm ;
if ( get_rpm ( i , rpm ) ) {
2021-07-05 19:31:40 -03:00
rpm_avg + = rpm ;
2021-06-03 04:27:27 -03:00
valid_escs + + ;
}
2021-02-23 18:04:06 -04:00
}
}
2021-07-05 19:31:40 -03:00
2021-02-23 18:04:06 -04:00
if ( valid_escs > 0 ) {
2021-07-05 19:31:40 -03:00
rpm_avg / = valid_escs ;
2021-02-23 18:04:06 -04:00
}
2021-07-05 19:31:40 -03:00
return rpm_avg ;
2021-06-03 04:27:27 -03:00
}
2021-02-23 18:04:06 -04:00
// return all the motor frequencies in Hz for dynamic filtering
uint8_t AP_ESC_Telem : : get_motor_frequencies_hz ( uint8_t nfreqs , float * freqs ) const
{
uint8_t valid_escs = 0 ;
// average the rpm of each motor as reported by BLHeli and convert to Hz
for ( uint8_t i = 0 ; i < ESC_TELEM_MAX_ESCS & & i < nfreqs ; i + + ) {
float rpm ;
if ( get_rpm ( i , rpm ) ) {
freqs [ valid_escs + + ] = rpm * ( 1.0f / 60.0f ) ;
}
}
return MIN ( valid_escs , nfreqs ) ;
}
2021-06-22 14:26:49 -03:00
// get mask of ESCs that sent valid telemetry data in the last
// ESC_TELEM_DATA_TIMEOUT_MS
2022-05-15 18:30:16 -03:00
uint32_t AP_ESC_Telem : : get_active_esc_mask ( ) const {
uint32_t ret = 0 ;
2021-06-22 14:26:49 -03:00
const uint32_t now = AP_HAL : : millis ( ) ;
2021-02-23 18:04:06 -04:00
for ( uint8_t i = 0 ; i < ESC_TELEM_MAX_ESCS ; i + + ) {
2021-06-22 14:26:49 -03:00
if ( now - _telem_data [ i ] . last_update_ms > = ESC_TELEM_DATA_TIMEOUT_MS ) {
continue ;
2021-02-23 18:04:06 -04:00
}
2021-06-22 14:26:49 -03:00
if ( _telem_data [ i ] . last_update_ms = = 0 ) {
// have never seen telem from this ESC
continue ;
}
ret | = ( 1U < < i ) ;
2021-02-23 18:04:06 -04:00
}
2021-06-22 14:26:49 -03:00
return ret ;
}
// return number of active ESCs present
uint8_t AP_ESC_Telem : : get_num_active_escs ( ) const {
2022-05-15 18:30:16 -03:00
uint32_t active = get_active_esc_mask ( ) ;
2021-06-22 14:26:49 -03:00
return __builtin_popcount ( active ) ;
2021-02-23 18:04:06 -04:00
}
// get an individual ESC's slewed rpm if available, returns true on success
bool AP_ESC_Telem : : get_rpm ( uint8_t esc_index , float & rpm ) const
{
2021-08-10 19:14:19 -03:00
if ( esc_index > = ESC_TELEM_MAX_ESCS ) {
return false ;
}
2021-02-23 18:04:06 -04:00
const volatile AP_ESC_Telem_Backend : : RpmData & rpmdata = _rpm_data [ esc_index ] ;
2021-08-10 19:14:19 -03:00
if ( is_zero ( rpmdata . update_rate_hz ) ) {
2021-02-23 18:04:06 -04:00
return false ;
}
const uint32_t now = AP_HAL : : micros ( ) ;
if ( rpmdata . last_update_us > 0 & & ( now > = rpmdata . last_update_us )
& & ( now - rpmdata . last_update_us < ESC_RPM_DATA_TIMEOUT_US ) ) {
const float slew = MIN ( 1.0f , ( now - rpmdata . last_update_us ) * rpmdata . update_rate_hz * ( 1.0f / 1e6 f ) ) ;
rpm = ( rpmdata . prev_rpm + ( rpmdata . rpm - rpmdata . prev_rpm ) * slew ) ;
return true ;
}
return false ;
}
// get an individual ESC's raw rpm if available, returns true on success
bool AP_ESC_Telem : : get_raw_rpm ( uint8_t esc_index , float & rpm ) const
{
2021-08-10 19:14:19 -03:00
if ( esc_index > = ESC_TELEM_MAX_ESCS ) {
return false ;
}
2021-02-23 18:04:06 -04:00
const volatile AP_ESC_Telem_Backend : : RpmData & rpmdata = _rpm_data [ esc_index ] ;
const uint32_t now = AP_HAL : : micros ( ) ;
2021-08-10 19:14:19 -03:00
if ( now < rpmdata . last_update_us | | now - rpmdata . last_update_us > ESC_RPM_DATA_TIMEOUT_US ) {
2021-02-23 18:04:06 -04:00
return false ;
}
rpm = rpmdata . rpm ;
return true ;
}
// get an individual ESC's temperature in centi-degrees if available, returns true on success
bool AP_ESC_Telem : : get_temperature ( uint8_t esc_index , int16_t & temp ) const
{
if ( esc_index > = ESC_TELEM_MAX_ESCS
| | AP_HAL : : millis ( ) - _telem_data [ esc_index ] . last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS
| | ! ( _telem_data [ esc_index ] . types & AP_ESC_Telem_Backend : : TelemetryType : : TEMPERATURE ) ) {
return false ;
}
temp = _telem_data [ esc_index ] . temperature_cdeg ;
return true ;
}
// get an individual motor's temperature in centi-degrees if available, returns true on success
bool AP_ESC_Telem : : get_motor_temperature ( uint8_t esc_index , int16_t & temp ) const
{
if ( esc_index > = ESC_TELEM_MAX_ESCS
| | AP_HAL : : millis ( ) - _telem_data [ esc_index ] . last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS
| | ! ( _telem_data [ esc_index ] . types & AP_ESC_Telem_Backend : : TelemetryType : : MOTOR_TEMPERATURE ) ) {
return false ;
}
temp = _telem_data [ esc_index ] . motor_temp_cdeg ;
return true ;
}
2021-07-05 19:37:01 -03:00
// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC
bool AP_ESC_Telem : : get_highest_motor_temperature ( int16_t & temp ) const
{
uint8_t valid_escs = 0 ;
for ( uint8_t i = 0 ; i < ESC_TELEM_MAX_ESCS ; i + + ) {
int16_t temp_temp ;
if ( get_motor_temperature ( i , temp_temp ) ) {
temp = MAX ( temp , temp_temp ) ;
valid_escs + + ;
}
}
return valid_escs > 0 ;
}
2021-02-23 18:04:06 -04:00
// get an individual ESC's current in Ampere if available, returns true on success
bool AP_ESC_Telem : : get_current ( uint8_t esc_index , float & amps ) const
{
if ( esc_index > = ESC_TELEM_MAX_ESCS
| | AP_HAL : : millis ( ) - _telem_data [ esc_index ] . last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS
| | ! ( _telem_data [ esc_index ] . types & AP_ESC_Telem_Backend : : TelemetryType : : CURRENT ) ) {
return false ;
}
amps = _telem_data [ esc_index ] . current ;
return true ;
}
// get an individual ESC's voltage in Volt if available, returns true on success
bool AP_ESC_Telem : : get_voltage ( uint8_t esc_index , float & volts ) const
{
if ( esc_index > = ESC_TELEM_MAX_ESCS
| | AP_HAL : : millis ( ) - _telem_data [ esc_index ] . last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS
| | ! ( _telem_data [ esc_index ] . types & AP_ESC_Telem_Backend : : TelemetryType : : VOLTAGE ) ) {
return false ;
}
volts = _telem_data [ esc_index ] . voltage ;
return true ;
}
// get an individual ESC's energy consumption in milli-Ampere.hour if available, returns true on success
bool AP_ESC_Telem : : get_consumption_mah ( uint8_t esc_index , float & consumption_mah ) const
{
if ( esc_index > = ESC_TELEM_MAX_ESCS
| | AP_HAL : : millis ( ) - _telem_data [ esc_index ] . last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS
| | ! ( _telem_data [ esc_index ] . types & AP_ESC_Telem_Backend : : TelemetryType : : CONSUMPTION ) ) {
return false ;
}
consumption_mah = _telem_data [ esc_index ] . consumption_mah ;
return true ;
}
2020-02-10 00:13:22 -04:00
// get an individual ESC's usage time in seconds if available, returns true on success
2021-02-23 18:04:06 -04:00
bool AP_ESC_Telem : : get_usage_seconds ( uint8_t esc_index , uint32_t & usage_s ) const
{
if ( esc_index > = ESC_TELEM_MAX_ESCS
| | AP_HAL : : millis ( ) - _telem_data [ esc_index ] . last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS
| | ! ( _telem_data [ esc_index ] . types & AP_ESC_Telem_Backend : : TelemetryType : : USAGE ) ) {
return false ;
}
usage_s = _telem_data [ esc_index ] . usage_s ;
return true ;
}
// send ESC telemetry messages over MAVLink
void AP_ESC_Telem : : send_esc_telemetry_mavlink ( uint8_t mav_chan )
{
2021-12-06 22:46:49 -04:00
# if HAL_GCS_ENABLED
2021-06-06 22:02:35 -03:00
if ( ! _have_data ) {
// we've never had any data
return ;
}
2021-02-23 18:04:06 -04:00
uint32_t now = AP_HAL : : millis ( ) ;
uint32_t now_us = AP_HAL : : micros ( ) ;
2022-06-06 01:11:14 -03:00
// loop through groups of 4 ESCs
2022-06-06 01:40:25 -03:00
const uint8_t esc_offset = constrain_int16 ( mavlink_offset , 0 , ESC_TELEM_MAX_ESCS - 1 ) ;
2022-06-06 01:11:14 -03:00
const uint8_t num_idx = ESC_TELEM_MAX_ESCS / 4 ;
for ( uint8_t idx = 0 ; idx < num_idx ; idx + + ) {
const uint8_t i = ( next_idx + idx ) % num_idx ;
2021-02-23 18:04:06 -04:00
// return if no space in output buffer to send mavlink messages
if ( ! HAVE_PAYLOAD_SPACE ( ( mavlink_channel_t ) mav_chan , ESC_TELEMETRY_1_TO_4 ) ) {
2022-06-06 01:11:14 -03:00
// not enough mavlink buffer space, start at this index next time
next_idx = i ;
2021-02-23 18:04:06 -04:00
return ;
}
2022-06-06 01:40:25 -03:00
bool all_stale = true ;
for ( uint8_t j = 0 ; j < 4 ; j + + ) {
const uint8_t esc_id = ( i * 4 + j ) + esc_offset ;
if ( esc_id < ESC_TELEM_MAX_ESCS & &
( now - _telem_data [ esc_id ] . last_update_ms < = ESC_TELEM_DATA_TIMEOUT_MS | |
now_us - _rpm_data [ esc_id ] . last_update_us < = ESC_RPM_DATA_TIMEOUT_US ) ) {
all_stale = false ;
break ;
}
}
if ( all_stale ) {
// skip this group of ESCs if no data to send
2021-02-23 18:04:06 -04:00
continue ;
}
2022-06-06 01:11:14 -03:00
2021-02-23 18:04:06 -04:00
// arrays to hold output
uint8_t temperature [ 4 ] { } ;
uint16_t voltage [ 4 ] { } ;
uint16_t current [ 4 ] { } ;
uint16_t current_tot [ 4 ] { } ;
uint16_t rpm [ 4 ] { } ;
uint16_t count [ 4 ] { } ;
// fill in output arrays
for ( uint8_t j = 0 ; j < 4 ; j + + ) {
2022-06-06 01:40:25 -03:00
const uint8_t esc_id = ( i * 4 + j ) + esc_offset ;
if ( esc_id > = ESC_TELEM_MAX_ESCS ) {
continue ;
}
2021-02-23 18:04:06 -04:00
temperature [ j ] = _telem_data [ esc_id ] . temperature_cdeg / 100 ;
voltage [ j ] = constrain_float ( _telem_data [ esc_id ] . voltage * 100.0f , 0 , UINT16_MAX ) ;
current [ j ] = constrain_float ( _telem_data [ esc_id ] . current * 100.0f , 0 , UINT16_MAX ) ;
current_tot [ j ] = constrain_float ( _telem_data [ esc_id ] . consumption_mah , 0 , UINT16_MAX ) ;
float rpmf = 0.0f ;
if ( get_rpm ( esc_id , rpmf ) ) {
rpm [ j ] = constrain_float ( rpmf , 0 , UINT16_MAX ) ;
} else {
rpm [ j ] = 0 ;
2020-02-10 00:13:22 -04:00
}
2021-02-23 18:04:06 -04:00
count [ j ] = _telem_data [ esc_id ] . count ;
2020-02-10 00:13:22 -04:00
}
2021-02-23 18:04:06 -04:00
2022-06-06 01:11:14 -03:00
// use a function pointer to reduce flash space
typedef void ( * esc_telem_send_fn_t ) ( mavlink_channel_t , const uint8_t * , const uint16_t * , const uint16_t * , const uint16_t * , const uint16_t * , const uint16_t * ) ;
esc_telem_send_fn_t fn = nullptr ;
2021-02-23 18:04:06 -04:00
// send messages
switch ( i ) {
case 0 :
2022-06-06 01:11:14 -03:00
fn = mavlink_msg_esc_telemetry_1_to_4_send ;
2021-02-23 18:04:06 -04:00
break ;
case 1 :
2022-06-06 01:11:14 -03:00
fn = mavlink_msg_esc_telemetry_5_to_8_send ;
2021-02-23 18:04:06 -04:00
break ;
case 2 :
2022-06-06 01:11:14 -03:00
fn = mavlink_msg_esc_telemetry_9_to_12_send ;
break ;
case 3 :
fn = mavlink_msg_esc_telemetry_13_to_16_send ;
2021-02-23 18:04:06 -04:00
break ;
2022-06-06 01:11:14 -03:00
# if ESC_TELEM_MAX_ESCS > 16
case 4 :
fn = mavlink_msg_esc_telemetry_17_to_20_send ;
2021-02-23 18:04:06 -04:00
break ;
2022-06-06 01:11:14 -03:00
case 5 :
fn = mavlink_msg_esc_telemetry_21_to_24_send ;
break ;
case 6 :
fn = mavlink_msg_esc_telemetry_25_to_28_send ;
break ;
case 7 :
fn = mavlink_msg_esc_telemetry_29_to_32_send ;
break ;
# endif
}
if ( fn ! = nullptr ) {
fn ( ( mavlink_channel_t ) mav_chan , temperature , voltage , current , current_tot , rpm , count ) ;
2021-02-23 18:04:06 -04:00
}
}
2022-06-06 01:11:14 -03:00
// we checked for all sends without running out of buffer space,
// start at zero next time
next_idx = 0 ;
2021-12-06 22:46:49 -04:00
# endif // HAL_GCS_ENABLED
2021-02-23 18:04:06 -04:00
}
// record an update to the telemetry data together with timestamp
// this should be called by backends when new telemetry values are available
void AP_ESC_Telem : : update_telem_data ( const uint8_t esc_index , const AP_ESC_Telem_Backend : : TelemetryData & new_data , const uint16_t data_mask )
{
// rpm and telemetry data are not protected by a semaphore even though updated from different threads
// all data is per-ESC and only written from the update thread and read by the user thread
// each element is a primitive type and the timestamp is only updated at the end, thus a caller
// can only get slightly more up-to-date information that perhaps they were expecting or might
// read data that has just gone stale - both of these are safe and avoid the overhead of locking
2021-08-10 19:12:06 -03:00
if ( esc_index > = ESC_TELEM_MAX_ESCS ) {
2021-02-23 18:04:06 -04:00
return ;
}
2021-06-06 22:02:35 -03:00
_have_data = true ;
2021-02-23 18:04:06 -04:00
if ( data_mask & AP_ESC_Telem_Backend : : TelemetryType : : TEMPERATURE ) {
_telem_data [ esc_index ] . temperature_cdeg = new_data . temperature_cdeg ;
2020-02-10 00:13:22 -04:00
}
2021-02-23 18:04:06 -04:00
if ( data_mask & AP_ESC_Telem_Backend : : TelemetryType : : MOTOR_TEMPERATURE ) {
_telem_data [ esc_index ] . motor_temp_cdeg = new_data . motor_temp_cdeg ;
}
if ( data_mask & AP_ESC_Telem_Backend : : TelemetryType : : VOLTAGE ) {
_telem_data [ esc_index ] . voltage = new_data . voltage ;
}
if ( data_mask & AP_ESC_Telem_Backend : : TelemetryType : : CURRENT ) {
_telem_data [ esc_index ] . current = new_data . current ;
}
if ( data_mask & AP_ESC_Telem_Backend : : TelemetryType : : CONSUMPTION ) {
_telem_data [ esc_index ] . consumption_mah = new_data . consumption_mah ;
}
if ( data_mask & AP_ESC_Telem_Backend : : TelemetryType : : USAGE ) {
_telem_data [ esc_index ] . usage_s = new_data . usage_s ;
}
_telem_data [ esc_index ] . count + + ;
_telem_data [ esc_index ] . types | = data_mask ;
_telem_data [ esc_index ] . last_update_ms = AP_HAL : : millis ( ) ;
}
// record an update to the RPM together with timestamp, this allows the notch values to be slewed
// this should be called by backends when new telemetry values are available
void AP_ESC_Telem : : update_rpm ( const uint8_t esc_index , const uint16_t new_rpm , const float error_rate )
{
2021-08-10 19:12:06 -03:00
if ( esc_index > = ESC_TELEM_MAX_ESCS ) {
2021-02-23 18:04:06 -04:00
return ;
}
2021-06-06 22:02:35 -03:00
_have_data = true ;
2021-02-23 18:04:06 -04:00
const uint32_t now = AP_HAL : : micros ( ) ;
volatile AP_ESC_Telem_Backend : : RpmData & rpmdata = _rpm_data [ esc_index ] ;
rpmdata . prev_rpm = rpmdata . rpm ;
rpmdata . rpm = new_rpm ;
if ( now > rpmdata . last_update_us ) { // cope with wrapping
rpmdata . update_rate_hz = 1.0e6 f / ( now - rpmdata . last_update_us ) ;
}
rpmdata . last_update_us = now ;
rpmdata . error_rate = error_rate ;
# ifdef ESC_TELEM_DEBUG
hal . console - > printf ( " RPM: rate=%.1fhz, rpm=%d) \n " , rpmdata . update_rate_hz , new_rpm ) ;
2020-02-10 00:13:22 -04:00
# endif
2021-02-23 18:04:06 -04:00
}
void AP_ESC_Telem : : update ( )
{
AP_Logger * logger = AP_Logger : : get_singleton ( ) ;
2022-01-16 01:58:33 -04:00
// Push received telemetry data into the logging system
2021-02-23 18:04:06 -04:00
if ( logger & & logger - > logging_enabled ( ) ) {
for ( uint8_t i = 0 ; i < ESC_TELEM_MAX_ESCS ; i + + ) {
if ( _telem_data [ i ] . last_update_ms ! = _last_telem_log_ms [ i ]
| | _rpm_data [ i ] . last_update_us ! = _last_rpm_log_us [ i ] ) {
float rpm = 0.0f ;
get_rpm ( i , rpm ) ;
2021-08-17 13:56:35 -03:00
float rawrpm = 0.0f ;
get_raw_rpm ( i , rawrpm ) ;
2021-02-23 18:04:06 -04:00
// Write ESC status messages
// id starts from 0
// rpm is eRPM (rpm * 100)
// voltage is in Volt
// current is in Ampere
// esc_temp is in centi-degrees Celsius
2022-01-29 20:18:52 -04:00
// current_tot is in milli-Ampere hours
2021-02-23 18:04:06 -04:00
// motor_temp is in centi-degrees Celsius
// error_rate is in percentage
const struct log_Esc pkt {
LOG_PACKET_HEADER_INIT ( uint8_t ( LOG_ESC_MSG ) ) ,
time_us : AP_HAL : : micros64 ( ) ,
instance : i ,
rpm : ( int32_t ) rpm * 100 ,
2021-08-17 14:56:45 -03:00
raw_rpm : ( int32_t ) rawrpm * 100 ,
2021-02-23 18:04:06 -04:00
voltage : _telem_data [ i ] . voltage ,
current : _telem_data [ i ] . current ,
esc_temp : _telem_data [ i ] . temperature_cdeg ,
current_tot : _telem_data [ i ] . consumption_mah ,
motor_temp : _telem_data [ i ] . motor_temp_cdeg ,
error_rate : _rpm_data [ i ] . error_rate
} ;
AP : : logger ( ) . WriteBlock ( & pkt , sizeof ( pkt ) ) ;
_last_telem_log_ms [ i ] = _telem_data [ i ] . last_update_ms ;
_last_rpm_log_us [ i ] = _rpm_data [ i ] . last_update_us ;
}
}
}
2020-02-10 00:13:22 -04:00
}
AP_ESC_Telem * AP_ESC_Telem : : _singleton = nullptr ;
/*
2021-02-23 12:16:37 -04:00
* Get the AP_ESC_Telem singleton
2020-02-10 00:13:22 -04:00
*/
AP_ESC_Telem * AP_ESC_Telem : : get_singleton ( )
{
return AP_ESC_Telem : : _singleton ;
}
namespace AP {
AP_ESC_Telem & esc_telem ( )
{
return * AP_ESC_Telem : : get_singleton ( ) ;
}
} ;
2021-02-23 18:04:06 -04:00
# endif