mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Frsky_Telem: use SerialManager for init
This commit is contained in:
parent
ebf5f98dbd
commit
d16f787bd0
@ -23,15 +23,21 @@
|
||||
#include <AP_Frsky_Telem.h>
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
void AP_Frsky_Telem::init(AP_HAL::UARTDriver *port, enum FrSkyProtocol protocol)
|
||||
void AP_Frsky_Telem::init(const AP_SerialManager& serial_manager)
|
||||
{
|
||||
if (port == NULL) {
|
||||
return;
|
||||
// initialise port to null
|
||||
_port = NULL;
|
||||
|
||||
// check for FRSky_DPort
|
||||
AP_SerialManager::serial_state frsky_serial;
|
||||
if (serial_manager.find_serial(AP_SerialManager::SerialProtocol_FRSky_DPort, frsky_serial)) {
|
||||
_port = frsky_serial.uart;
|
||||
_protocol = FrSkyDPORT;
|
||||
}
|
||||
_port = port;
|
||||
_protocol = protocol;
|
||||
if (_protocol == FrSkySPORT) {
|
||||
_port->begin(57600);
|
||||
// check for FRSky_SPort
|
||||
if (serial_manager.find_serial(AP_SerialManager::SerialProtocol_FRSky_SPort, frsky_serial)) {
|
||||
_port = frsky_serial.uart;
|
||||
_protocol = FrSkySPORT;
|
||||
_gps_call = 0;
|
||||
_fas_call = 0;
|
||||
_vario_call = 0 ;
|
||||
@ -43,10 +49,10 @@ void AP_Frsky_Telem::init(AP_HAL::UARTDriver *port, enum FrSkyProtocol protocol)
|
||||
_sats_data_ready = false;
|
||||
_sport_status = 0;
|
||||
hal.scheduler->register_io_process(AP_HAL_MEMBERPROC(&AP_Frsky_Telem::sport_tick));
|
||||
} else {
|
||||
// if this is D-port then spec says 9600 baud
|
||||
_port->begin(9600);
|
||||
_initialised = true;
|
||||
}
|
||||
// initialise port ignoring serial ports baud rate parameter
|
||||
if (_port != NULL) {
|
||||
_initialised = true;
|
||||
}
|
||||
}
|
||||
|
||||
@ -459,6 +465,7 @@ void AP_Frsky_Telem::send_hub_frame()
|
||||
*/
|
||||
void AP_Frsky_Telem::send_frames(uint8_t control_mode)
|
||||
{
|
||||
// return immediately if not initialised
|
||||
if (!_initialised) {
|
||||
return;
|
||||
}
|
||||
|
@ -24,6 +24,7 @@
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_BattMonitor.h>
|
||||
#include <AP_SerialManager.h>
|
||||
|
||||
/* FrSky sensor hub data IDs */
|
||||
#define FRSKY_ID_GPS_ALT_BP 0x01
|
||||
@ -77,18 +78,21 @@ class AP_Frsky_Telem
|
||||
public:
|
||||
//constructor
|
||||
AP_Frsky_Telem(AP_AHRS &ahrs, AP_BattMonitor &battery) :
|
||||
_port(NULL),
|
||||
_protocol(FrSkyUnknown),
|
||||
_initialised(false),
|
||||
_ahrs(ahrs),
|
||||
_battery(battery)
|
||||
_ahrs(ahrs),
|
||||
_battery(battery)
|
||||
{}
|
||||
|
||||
// these enums must match up with TELEM2_PROTOCOL in vehicle code
|
||||
enum FrSkyProtocol {
|
||||
FrSkyUnknown = 0,
|
||||
FrSkyDPORT = 2,
|
||||
FrSkySPORT = 3
|
||||
};
|
||||
|
||||
void init(AP_HAL::UARTDriver *port, enum FrSkyProtocol protocol);
|
||||
void init(const AP_SerialManager& serial_manager);
|
||||
void send_frames(uint8_t control_mode);
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user