@ -32,7 +32,6 @@ AP_Frsky_Telem::AP_Frsky_Telem(AP_AHRS &ahrs, const AP_BattMonitor &battery, con
@@ -32,7 +32,6 @@ AP_Frsky_Telem::AP_Frsky_Telem(AP_AHRS &ahrs, const AP_BattMonitor &battery, con
/*
* init - perform required initialisation
* for Copter
*/
void AP_Frsky_Telem : : init ( const AP_SerialManager & serial_manager , const char * firmware_str , const uint8_t mav_type , AP_Float * fs_batt_voltage , AP_Float * fs_batt_mah , uint32_t * ap_value )
{
@ -47,58 +46,17 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi
@@ -47,58 +46,17 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi
queue_message ( MAV_SEVERITY_INFO , firmware_str ) ;
// save main parameters locally
_params . mav_type = mav_type ; // frame type (see MAV_TYPE in Mavlink definition file common.h)
if ( fs_batt_voltage ! = nullptr ) {
_params . fs_batt_voltage = fs_batt_voltage ; // failsafe battery voltage in volts
_params . fs_batt_mah = fs_batt_mah ; // failsafe reserve capacity in mAh
_ap . value = ap_value ; // ap bit-field
}
if ( _port ! = NULL ) {
hal . scheduler - > register_io_process ( FUNCTOR_BIND_MEMBER ( & AP_Frsky_Telem : : tick , void ) ) ;
// we don't want flow control for either protocol
_port - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
}
}
/*
* init - perform required initialisation
* for Plane
*/
void AP_Frsky_Telem : : init ( const AP_SerialManager & serial_manager , const char * firmware_str , const uint8_t mav_type , AP_Float * fs_batt_voltage , AP_Float * fs_batt_mah )
{
// check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
if ( ( _port = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_FrSky_D , 0 ) ) ) {
_protocol = AP_SerialManager : : SerialProtocol_FrSky_D ; // FrSky D protocol (D-receivers)
} else if ( ( _port = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_FrSky_SPort , 0 ) ) ) {
_protocol = AP_SerialManager : : SerialProtocol_FrSky_SPort ; // FrSky SPort protocol (X-receivers)
} else if ( ( _port = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_FrSky_SPort_Passthrough , 0 ) ) ) {
_protocol = AP_SerialManager : : SerialProtocol_FrSky_SPort_Passthrough ; // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
// add firmware and frame info to message queue
queue_message ( MAV_SEVERITY_INFO , firmware_str ) ;
// save main parameters locally
_params . mav_type = mav_type ; // frame type (see MAV_TYPE in Mavlink definition file common.h)
_params . fs_batt_voltage = fs_batt_voltage ; // failsafe battery voltage in volts
if ( fs_batt_mah ! = nullptr ) {
_params . fs_batt_mah = fs_batt_mah ; // failsafe reserve capacity in mAh
* _ap . value = 0 ; // ap bit-field
}
if ( _port ! = NULL ) {
hal . scheduler - > register_io_process ( FUNCTOR_BIND_MEMBER ( & AP_Frsky_Telem : : tick , void ) ) ;
// we don't want flow control for either protocol
_port - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
}
if ( ap_value ! = nullptr ) {
_ap . value = ap_value ; // ap bit-field
} else {
* _ap . value = 0 ;
}
/*
* init - perform required initialisation
* for Rover
*/
void AP_Frsky_Telem : : init ( const AP_SerialManager & serial_manager )
{
// check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
if ( ( _port = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_FrSky_D , 0 ) ) ) {
_protocol = AP_SerialManager : : SerialProtocol_FrSky_D ; // FrSky D protocol (D-receivers)
} else if ( ( _port = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_FrSky_SPort , 0 ) ) ) {
_protocol = AP_SerialManager : : SerialProtocol_FrSky_SPort ; // FrSky SPort protocol (X-receivers)
}
if ( _port ! = NULL ) {
@ -108,6 +66,7 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager)
@@ -108,6 +66,7 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager)
}
}
/*
* send telemetry data
* for FrSky SPort Passthrough ( OpenTX ) protocol ( X - receivers )