mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
GCS_MAVLink: stop pointlessly passing serial manager around
This commit is contained in:
parent
45fab82345
commit
ca449cd979
@ -297,7 +297,7 @@ public:
|
|||||||
void update_receive(uint32_t max_time_us=1000);
|
void update_receive(uint32_t max_time_us=1000);
|
||||||
void update_send();
|
void update_send();
|
||||||
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
|
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
|
||||||
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
|
void setup_uart(AP_SerialManager::SerialProtocol protocol, uint8_t instance);
|
||||||
void send_message(enum ap_message id);
|
void send_message(enum ap_message id);
|
||||||
void send_text(MAV_SEVERITY severity, const char *fmt, ...) const;
|
void send_text(MAV_SEVERITY severity, const char *fmt, ...) const;
|
||||||
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list) const;
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list) const;
|
||||||
@ -964,7 +964,7 @@ public:
|
|||||||
|
|
||||||
void update_send();
|
void update_send();
|
||||||
void update_receive();
|
void update_receive();
|
||||||
virtual void setup_uarts(AP_SerialManager &serial_manager);
|
virtual void setup_uarts();
|
||||||
|
|
||||||
bool out_of_time() const {
|
bool out_of_time() const {
|
||||||
return _out_of_time;
|
return _out_of_time;
|
||||||
|
@ -105,10 +105,10 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
|
|||||||
setup a UART, handling begin() and init()
|
setup a UART, handling begin() and init()
|
||||||
*/
|
*/
|
||||||
void
|
void
|
||||||
GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance)
|
GCS_MAVLINK::setup_uart(AP_SerialManager::SerialProtocol protocol, uint8_t instance)
|
||||||
{
|
{
|
||||||
// search for serial port
|
// search for serial port
|
||||||
|
const AP_SerialManager& serial_manager = AP::serialmanager();
|
||||||
AP_HAL::UARTDriver *uart;
|
AP_HAL::UARTDriver *uart;
|
||||||
uart = serial_manager.find_serial(protocol, instance);
|
uart = serial_manager.find_serial(protocol, instance);
|
||||||
if (uart == nullptr) {
|
if (uart == nullptr) {
|
||||||
@ -2270,10 +2270,10 @@ void GCS::send_mission_item_reached_message(uint16_t mission_index)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS::setup_uarts(AP_SerialManager &serial_manager)
|
void GCS::setup_uarts()
|
||||||
{
|
{
|
||||||
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||||
chan(i).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
chan(i).setup_uart(AP_SerialManager::SerialProtocol_MAVLink, i);
|
||||||
}
|
}
|
||||||
|
|
||||||
frsky.init();
|
frsky.init();
|
||||||
|
Loading…
Reference in New Issue
Block a user