Browse Source

AP_FrSky_Telem: Make init return false if we failed to init

mission-4.1.18
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
59e62ca2fc
  1. 6
      libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp
  2. 2
      libraries/AP_Frsky_Telem/AP_Frsky_Telem.h

6
libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp

@ -38,7 +38,7 @@ ObjectArray<mavlink_statustext_t> AP_Frsky_Telem::_statustext_queue(FRSKY_TELEM_ @@ -38,7 +38,7 @@ ObjectArray<mavlink_statustext_t> AP_Frsky_Telem::_statustext_queue(FRSKY_TELEM_
/*
* init - perform required initialisation
*/
void AP_Frsky_Telem::init()
bool AP_Frsky_Telem::init()
{
const AP_SerialManager &serial_manager = AP::serialmanager();
@ -65,7 +65,11 @@ void AP_Frsky_Telem::init() @@ -65,7 +65,11 @@ void AP_Frsky_Telem::init()
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);
return true;
}
return false;
}

2
libraries/AP_Frsky_Telem/AP_Frsky_Telem.h

@ -119,7 +119,7 @@ public: @@ -119,7 +119,7 @@ public:
AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete;
// init - perform required initialisation
void init();
bool init();
// add statustext message to FrSky lib message queue
void queue_message(MAV_SEVERITY severity, const char *text);

Loading…
Cancel
Save