Browse Source

GCS_MAVLink: remove pointless protocol parameter to setup_uart

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
a55c40949b
  1. 3
      libraries/GCS_MAVLink/GCS.h
  2. 10
      libraries/GCS_MAVLink/GCS_Common.cpp

3
libraries/GCS_MAVLink/GCS.h

@ -9,7 +9,6 @@ @@ -9,7 +9,6 @@
#include <AP_Mission/AP_Mission.h>
#include <stdint.h>
#include "MAVLink_routing.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_Avoidance/AP_Avoidance.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
@ -297,7 +296,7 @@ public: @@ -297,7 +296,7 @@ public:
void update_receive(uint32_t max_time_us=1000);
void update_send();
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
void setup_uart(AP_SerialManager::SerialProtocol protocol, uint8_t instance);
void setup_uart(uint8_t instance);
void send_message(enum ap_message id);
void send_text(MAV_SEVERITY severity, const char *fmt, ...) const;
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list) const;

10
libraries/GCS_MAVLink/GCS_Common.cpp

@ -28,6 +28,7 @@ @@ -28,6 +28,7 @@
#include <AP_BLHeli/AP_BLHeli.h>
#include <AP_RSSI/AP_RSSI.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_Mount/AP_Mount.h>
#include <AP_Common/AP_FWVersion.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
@ -105,12 +106,13 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) @@ -105,12 +106,13 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
setup a UART, handling begin() and init()
*/
void
GCS_MAVLINK::setup_uart(AP_SerialManager::SerialProtocol protocol, uint8_t instance)
GCS_MAVLINK::setup_uart(uint8_t instance)
{
// search for serial port
const AP_SerialManager& serial_manager = AP::serialmanager();
AP_HAL::UARTDriver *uart;
uart = serial_manager.find_serial(protocol, instance);
const AP_SerialManager::SerialProtocol protocol = AP_SerialManager::SerialProtocol_MAVLink;
AP_HAL::UARTDriver *uart = serial_manager.find_serial(protocol, instance);
if (uart == nullptr) {
// return immediately if not found
return;
@ -2273,7 +2275,7 @@ void GCS::send_mission_item_reached_message(uint16_t mission_index) @@ -2273,7 +2275,7 @@ void GCS::send_mission_item_reached_message(uint16_t mission_index)
void GCS::setup_uarts()
{
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
chan(i).setup_uart(AP_SerialManager::SerialProtocol_MAVLink, i);
chan(i).setup_uart(i);
}
frsky.init();

Loading…
Cancel
Save