From 3587d7f2536822de15fb56f731781d37482f20c0 Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Mon, 21 Aug 2017 14:31:51 -0600 Subject: [PATCH] AP_SerialManager: add SBUS1 serial output support --- libraries/AP_SerialManager/AP_SerialManager.cpp | 10 +++++++++- libraries/AP_SerialManager/AP_SerialManager.h | 6 ++++++ 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index a569fe3c65..ff8c3b6052 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -225,7 +225,6 @@ void AP_SerialManager::init() AP_SERIALMANAGER_ULANDING_BUFSIZE_RX, AP_SERIALMANAGER_ULANDING_BUFSIZE_TX); break; - case SerialProtocol_Volz: // Note baudrate is hardcoded to 115200 state[i].baud = AP_SERIALMANAGER_VOLZ_BAUD; // update baud param in case user looks at it @@ -233,6 +232,15 @@ void AP_SerialManager::init() AP_SERIALMANAGER_VOLZ_BUFSIZE_RX, AP_SERIALMANAGER_VOLZ_BUFSIZE_TX); break; + case SerialProtocol_Sbus1: + state[i].baud = AP_SERIALMANAGER_SBUS1_BAUD / 1000; // update baud param in case user looks at it + state[i].uart->begin(map_baudrate(state[i].baud), + AP_SERIALMANAGER_SBUS1_BUFSIZE_RX, + AP_SERIALMANAGER_SBUS1_BUFSIZE_TX); + state[i].uart->configure_parity(2); // enable even parity + state[i].uart->set_stop_bits(2); + state[i].uart->set_unbuffered_writes(true); + break; } } } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index aaba1800e5..8c9d34fdef 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -73,6 +73,11 @@ #define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128 #define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128 +// SBUS servo outputs +#define AP_SERIALMANAGER_SBUS1_BAUD 100000 +#define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16 +#define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32 + class AP_SerialManager { public: @@ -93,6 +98,7 @@ public: SerialProtocol_Aerotenna_uLanding = 12, // Ulanding support SerialProtocol_Beacon = 13, SerialProtocol_Volz = 14, // Volz servo protocol + SerialProtocol_Sbus1 = 15 }; // get singleton instance