2015-01-19 09:32:24 -04:00
/*
2016-04-23 18:02:53 -03:00
Please contribute your ideas ! See http : //dev.ardupilot.org for details
2015-01-19 09:32:24 -04:00
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
/*
SerialManager allows defining the protocol and baud rates for the available
serial ports and provides helper functions so objects ( like a gimbal ) can
find which serial port they should use
*/
2015-08-11 03:28:45 -03:00
# include <AP_HAL/AP_HAL.h>
2019-03-22 22:21:52 -03:00
# include <AP_Math/AP_Math.h>
2019-08-27 04:41:21 -03:00
# include <AP_RCProtocol/AP_RCProtocol.h>
2015-08-11 03:28:45 -03:00
# include "AP_SerialManager.h"
2015-01-19 09:32:24 -04:00
extern const AP_HAL : : HAL & hal ;
2019-08-27 04:41:21 -03:00
# ifdef HAL_SERIAL2_PROTOCOL
# define SERIAL2_PROTOCOL HAL_SERIAL2_PROTOCOL
# else
# define SERIAL2_PROTOCOL SerialProtocol_MAVLink
# endif
# ifndef HAL_SERIAL3_PROTOCOL
# define SERIAL3_PROTOCOL SerialProtocol_GPS
# else
# define SERIAL3_PROTOCOL HAL_SERIAL3_PROTOCOL
# endif
# ifndef HAL_SERIAL4_PROTOCOL
# define SERIAL4_PROTOCOL SerialProtocol_GPS
# else
# define SERIAL4_PROTOCOL HAL_SERIAL4_PROTOCOL
# endif
2018-02-04 00:42:38 -04:00
# ifdef HAL_SERIAL5_PROTOCOL
# define SERIAL5_PROTOCOL HAL_SERIAL5_PROTOCOL
# define SERIAL5_BAUD HAL_SERIAL5_BAUD
2016-04-13 08:24:42 -03:00
# else
2016-04-19 00:48:57 -03:00
# define SERIAL5_PROTOCOL SerialProtocol_None
# define SERIAL5_BAUD AP_SERIALMANAGER_MAVLINK_BAUD / 1000
2016-04-13 08:24:42 -03:00
# endif
2018-06-27 08:33:24 -03:00
# ifndef HAL_SERIAL6_PROTOCOL
# define SERIAL6_PROTOCOL SerialProtocol_None
# define SERIAL6_BAUD AP_SERIALMANAGER_MAVLINK_BAUD / 1000
2019-04-20 03:13:23 -03:00
# else
# define SERIAL6_PROTOCOL HAL_SERIAL6_PROTOCOL
# define SERIAL6_BAUD HAL_SERIAL6_BAUD
2018-06-27 08:33:24 -03:00
# endif
2019-07-12 01:59:02 -03:00
# ifndef HAL_SERIAL7_PROTOCOL
# define SERIAL7_PROTOCOL SerialProtocol_None
# define SERIAL7_BAUD AP_SERIALMANAGER_MAVLINK_BAUD / 1000
# else
# define SERIAL7_PROTOCOL HAL_SERIAL7_PROTOCOL
# define SERIAL7_BAUD HAL_SERIAL7_BAUD
# endif
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_SerialManager : : var_info [ ] = {
2015-01-19 09:32:24 -04:00
// @Param: 0_BAUD
// @DisplayName: Serial0 baud rate
2019-01-19 02:32:03 -04:00
// @Description: The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
2019-01-08 10:44:46 -04:00
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,460:460800,500:500000,921:921600,1500:1500000
2015-01-19 09:32:24 -04:00
// @User: Standard
AP_GROUPINFO ( " 0_BAUD " , 0 , AP_SerialManager , state [ 0 ] . baud , AP_SERIALMANAGER_CONSOLE_BAUD / 1000 ) ,
2016-05-16 00:34:32 -03:00
// @Param: 0_PROTOCOL
// @DisplayName: Console protocol selection
// @Description: Control what protocol to use on the console.
// @Values: 1:MAVlink1, 2:MAVLink2
// @User: Standard
2017-05-12 10:36:55 -03:00
// @RebootRequired: True
2018-07-18 00:19:38 -03:00
AP_GROUPINFO ( " 0_PROTOCOL " , 11 , AP_SerialManager , state [ 0 ] . protocol , SerialProtocol_MAVLink2 ) ,
2016-05-16 00:34:32 -03:00
2015-01-19 09:32:24 -04:00
// @Param: 1_PROTOCOL
// @DisplayName: Telem1 protocol selection
2015-02-23 19:19:42 -04:00
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
2019-08-27 04:41:21 -03:00
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
2015-01-19 09:32:24 -04:00
// @User: Standard
2017-05-12 10:36:55 -03:00
// @RebootRequired: True
2016-10-20 17:55:02 -03:00
AP_GROUPINFO ( " 1_PROTOCOL " , 1 , AP_SerialManager , state [ 1 ] . protocol , SerialProtocol_MAVLink ) ,
2015-01-19 09:32:24 -04:00
// @Param: 1_BAUD
// @DisplayName: Telem1 Baud Rate
2019-01-19 02:32:03 -04:00
// @Description: The baud rate used on the Telem1 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
2019-01-08 10:44:46 -04:00
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
2015-01-19 09:32:24 -04:00
// @User: Standard
AP_GROUPINFO ( " 1_BAUD " , 2 , AP_SerialManager , state [ 1 ] . baud , AP_SERIALMANAGER_MAVLINK_BAUD / 1000 ) ,
// @Param: 2_PROTOCOL
// @DisplayName: Telemetry 2 protocol selection
2015-02-23 19:19:42 -04:00
// @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
2019-08-27 04:41:21 -03:00
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
2016-10-26 07:42:50 -03:00
// @User: Standard
2017-05-12 10:36:55 -03:00
// @RebootRequired: True
2019-08-27 04:41:21 -03:00
AP_GROUPINFO ( " 2_PROTOCOL " , 3 , AP_SerialManager , state [ 2 ] . protocol , SERIAL2_PROTOCOL ) ,
2015-01-19 09:32:24 -04:00
// @Param: 2_BAUD
// @DisplayName: Telemetry 2 Baud Rate
2019-01-19 02:32:03 -04:00
// @Description: The baud rate of the Telem2 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
2019-01-08 10:44:46 -04:00
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
2015-01-19 09:32:24 -04:00
// @User: Standard
AP_GROUPINFO ( " 2_BAUD " , 4 , AP_SerialManager , state [ 2 ] . baud , AP_SERIALMANAGER_MAVLINK_BAUD / 1000 ) ,
// @Param: 3_PROTOCOL
// @DisplayName: Serial 3 (GPS) protocol selection
2015-02-23 19:19:42 -04:00
// @Description: Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
2019-08-27 04:41:21 -03:00
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
2016-10-26 07:42:50 -03:00
// @User: Standard
2017-05-12 10:36:55 -03:00
// @RebootRequired: True
2019-08-27 04:41:21 -03:00
AP_GROUPINFO ( " 3_PROTOCOL " , 5 , AP_SerialManager , state [ 3 ] . protocol , SERIAL3_PROTOCOL ) ,
2015-01-19 09:32:24 -04:00
// @Param: 3_BAUD
// @DisplayName: Serial 3 (GPS) Baud Rate
2019-01-19 02:32:03 -04:00
// @Description: The baud rate used for the Serial 3 (GPS). Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
2019-01-08 10:44:46 -04:00
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
2015-01-19 09:32:24 -04:00
// @User: Standard
AP_GROUPINFO ( " 3_BAUD " , 6 , AP_SerialManager , state [ 3 ] . baud , AP_SERIALMANAGER_GPS_BAUD / 1000 ) ,
// @Param: 4_PROTOCOL
// @DisplayName: Serial4 protocol selection
2015-02-23 19:19:42 -04:00
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
2019-08-27 04:41:21 -03:00
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
2016-10-26 07:42:50 -03:00
// @User: Standard
2017-05-12 10:36:55 -03:00
// @RebootRequired: True
2019-08-27 04:41:21 -03:00
AP_GROUPINFO ( " 4_PROTOCOL " , 7 , AP_SerialManager , state [ 4 ] . protocol , SERIAL4_PROTOCOL ) ,
2015-01-19 09:32:24 -04:00
// @Param: 4_BAUD
// @DisplayName: Serial 4 Baud Rate
2019-01-19 02:32:03 -04:00
// @Description: The baud rate used for Serial4. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
2019-01-08 10:44:46 -04:00
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
2015-01-19 09:32:24 -04:00
// @User: Standard
2016-04-19 00:48:57 -03:00
AP_GROUPINFO ( " 4_BAUD " , 8 , AP_SerialManager , state [ 4 ] . baud , AP_SERIALMANAGER_GPS_BAUD / 1000 ) ,
// @Param: 5_PROTOCOL
2016-04-19 21:03:45 -03:00
// @DisplayName: Serial5 protocol selection
// @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
2019-08-27 04:41:21 -03:00
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
2016-10-26 07:42:50 -03:00
// @User: Standard
2017-05-12 10:36:55 -03:00
// @RebootRequired: True
2016-04-19 00:48:57 -03:00
AP_GROUPINFO ( " 5_PROTOCOL " , 9 , AP_SerialManager , state [ 5 ] . protocol , SERIAL5_PROTOCOL ) ,
// @Param: 5_BAUD
2016-04-19 21:03:45 -03:00
// @DisplayName: Serial 5 Baud Rate
2019-01-19 02:32:03 -04:00
// @Description: The baud rate used for Serial5. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
2019-01-08 10:44:46 -04:00
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
2016-04-19 00:48:57 -03:00
// @User: Standard
AP_GROUPINFO ( " 5_BAUD " , 10 , AP_SerialManager , state [ 5 ] . baud , SERIAL5_BAUD ) ,
2015-01-19 09:32:24 -04:00
2016-05-16 00:34:32 -03:00
// index 11 used by 0_PROTOCOL
2018-06-27 08:33:24 -03:00
// @Param: 6_PROTOCOL
// @DisplayName: Serial6 protocol selection
// @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
2019-08-27 04:41:21 -03:00
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
2018-06-27 08:33:24 -03:00
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 6_PROTOCOL " , 12 , AP_SerialManager , state [ 6 ] . protocol , SERIAL6_PROTOCOL ) ,
// @Param: 6_BAUD
// @DisplayName: Serial 6 Baud Rate
2019-01-19 02:32:03 -04:00
// @Description: The baud rate used for Serial6. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
2019-01-08 10:44:46 -04:00
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
2018-06-27 08:33:24 -03:00
// @User: Standard
AP_GROUPINFO ( " 6_BAUD " , 13 , AP_SerialManager , state [ 6 ] . baud , SERIAL6_BAUD ) ,
2018-11-10 05:45:01 -04:00
// @Param: 1_OPTIONS
// @DisplayName: Telem1 options
2018-11-20 03:26:42 -04:00
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
2018-11-10 05:45:01 -04:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " 1_OPTIONS " , 14 , AP_SerialManager , state [ 1 ] . options , 0 ) ,
// @Param: 2_OPTIONS
// @DisplayName: Telem2 options
2018-11-14 00:42:48 -04:00
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
2018-11-20 03:26:42 -04:00
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
2018-11-10 05:45:01 -04:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " 2_OPTIONS " , 15 , AP_SerialManager , state [ 2 ] . options , 0 ) ,
// @Param: 3_OPTIONS
// @DisplayName: Serial3 options
2018-11-14 00:42:48 -04:00
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
2018-11-20 03:26:42 -04:00
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
2018-11-10 05:45:01 -04:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " 3_OPTIONS " , 16 , AP_SerialManager , state [ 3 ] . options , 0 ) ,
// @Param: 4_OPTIONS
// @DisplayName: Serial4 options
2018-11-14 00:42:48 -04:00
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
2018-11-20 03:26:42 -04:00
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
2018-11-10 05:45:01 -04:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " 4_OPTIONS " , 17 , AP_SerialManager , state [ 4 ] . options , 0 ) ,
// @Param: 5_OPTIONS
// @DisplayName: Serial5 options
2018-11-14 00:42:48 -04:00
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
2018-11-20 03:26:42 -04:00
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
2018-11-10 05:45:01 -04:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " 5_OPTIONS " , 18 , AP_SerialManager , state [ 5 ] . options , 0 ) ,
// @Param: 6_OPTIONS
// @DisplayName: Serial6 options
2018-11-14 00:42:48 -04:00
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
2018-11-20 03:26:42 -04:00
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
2018-11-10 05:45:01 -04:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " 6_OPTIONS " , 19 , AP_SerialManager , state [ 6 ] . options , 0 ) ,
2018-12-19 07:24:57 -04:00
// @Param: _PASS1
// @DisplayName: Serial passthru first port
// @Description: This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
2018-12-29 00:15:45 -04:00
// @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6
2018-12-19 07:24:57 -04:00
// @User: Advanced
AP_GROUPINFO ( " _PASS1 " , 20 , AP_SerialManager , passthru_port1 , 0 ) ,
// @Param: _PASS2
// @DisplayName: Serial passthru second port
// @Description: This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
2018-12-29 00:15:45 -04:00
// @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6
2018-12-19 07:24:57 -04:00
// @User: Advanced
AP_GROUPINFO ( " _PASS2 " , 21 , AP_SerialManager , passthru_port2 , - 1 ) ,
// @Param: _PASSTIMO
// @DisplayName: Serial passthru timeout
// @Description: This sets a timeout for serial pass-through in seconds. When the pass-through is enabled by setting the SERIAL_PASS1 and SERIAL_PASS2 parameters then it remains in effect until no data comes from the first port for SERIAL_PASSTIMO seconds. This allows the port to revent to its normal usage (such as MAVLink connection to a GCS) when it is no longer needed. A value of 0 means no timeout.
// @Range: 0 120
// @Units: s
// @User: Advanced
AP_GROUPINFO ( " _PASSTIMO " , 22 , AP_SerialManager , passthru_timeout , 15 ) ,
2019-07-12 01:59:02 -03:00
// @Param: 7_PROTOCOL
// @DisplayName: Serial7 protocol selection
// @Description: Control what protocol Serial7 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
2019-08-27 04:41:21 -03:00
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
2019-07-12 01:59:02 -03:00
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 7_PROTOCOL " , 23 , AP_SerialManager , state [ 7 ] . protocol , SERIAL7_PROTOCOL ) ,
// @Param: 7_BAUD
// @DisplayName: Serial 7 Baud Rate
// @Description: The baud rate used for Serial7. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,256:256000,500:500000,921:921600,1500:1500000
// @User: Standard
AP_GROUPINFO ( " 7_BAUD " , 24 , AP_SerialManager , state [ 7 ] . baud , SERIAL7_BAUD ) ,
// @Param: 7_OPTIONS
// @DisplayName: Serial7 options
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " 7_OPTIONS " , 25 , AP_SerialManager , state [ 7 ] . options , 0 ) ,
2018-12-19 07:24:57 -04:00
2015-01-19 09:32:24 -04:00
AP_GROUPEND
} ;
2017-11-02 23:27:29 -03:00
// singleton instance
2019-02-10 01:02:55 -04:00
AP_SerialManager * AP_SerialManager : : _singleton ;
2017-11-02 23:27:29 -03:00
2015-01-19 09:32:24 -04:00
// Constructor
AP_SerialManager : : AP_SerialManager ( )
{
2019-02-10 01:02:55 -04:00
_singleton = this ;
2015-01-19 09:32:24 -04:00
// setup parameter defaults
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
// init_console - initialise console at default baud rate
void AP_SerialManager : : init_console ( )
{
// initialise console immediately at default size and baud
state [ 0 ] . uart = hal . uartA ; // serial0, uartA, always console
2015-01-29 00:35:42 -04:00
state [ 0 ] . uart - > begin ( AP_SERIALMANAGER_CONSOLE_BAUD ,
AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX ,
AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX ) ;
2015-01-19 09:32:24 -04:00
}
2017-08-13 02:47:26 -03:00
extern bool g_nsh_should_exit ;
2015-01-19 09:32:24 -04:00
// init - // init - initialise serial ports
void AP_SerialManager : : init ( )
{
2018-12-19 07:24:57 -04:00
// always reset passthru port2 on boot
passthru_port2 . set_and_save_ifchanged ( - 1 ) ;
2015-01-19 09:32:24 -04:00
// initialise pointers to serial ports
state [ 1 ] . uart = hal . uartC ; // serial1, uartC, normally telem1
state [ 2 ] . uart = hal . uartD ; // serial2, uartD, normally telem2
state [ 3 ] . uart = hal . uartB ; // serial3, uartB, normally 1st GPS
state [ 4 ] . uart = hal . uartE ; // serial4, uartE, normally 2nd GPS
2016-04-19 00:48:57 -03:00
state [ 5 ] . uart = hal . uartF ; // serial5
2018-06-27 08:33:24 -03:00
state [ 6 ] . uart = hal . uartG ; // serial6
2019-07-12 01:59:02 -03:00
state [ 7 ] . uart = hal . uartH ; // serial7
2015-01-19 09:32:24 -04:00
2020-01-10 03:52:50 -04:00
# ifdef HAL_OTG1_CONFIG
/*
prevent users from changing USB protocol to other than
MAVLink . This fixes an issue where users trying to get SLCAN
change SERIAL0_PROTOCOL to 22 and find they can no longer connect
*/
if ( state [ 0 ] . protocol ! = SerialProtocol_MAVLink & &
state [ 0 ] . protocol ! = SerialProtocol_MAVLink2 ) {
state [ 0 ] . protocol . set ( SerialProtocol_MAVLink2 ) ;
}
# endif
2016-05-16 00:34:32 -03:00
if ( state [ 0 ] . uart = = nullptr ) {
init_console ( ) ;
}
2015-01-19 09:32:24 -04:00
// initialise serial ports
for ( uint8_t i = 1 ; i < SERIALMANAGER_NUM_PORTS ; i + + ) {
2017-08-13 02:47:26 -03:00
2016-10-30 02:24:21 -03:00
if ( state [ i ] . uart ! = nullptr ) {
2018-11-10 05:45:01 -04:00
// see if special options have been requested
if ( state [ i ] . protocol ! = SerialProtocol_None & & state [ i ] . options ) {
set_options ( i ) ;
}
2015-01-19 09:32:24 -04:00
switch ( state [ i ] . protocol ) {
2016-04-19 00:48:57 -03:00
case SerialProtocol_None :
break ;
2015-01-19 09:32:24 -04:00
case SerialProtocol_Console :
2015-03-27 22:44:43 -03:00
case SerialProtocol_MAVLink :
2015-01-19 09:32:24 -04:00
case SerialProtocol_MAVLink2 :
2015-01-29 00:35:42 -04:00
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ,
AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX ,
AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX ) ;
2015-01-19 09:32:24 -04:00
break ;
2016-05-03 15:35:45 -03:00
case SerialProtocol_FrSky_D :
2016-04-08 16:31:13 -03:00
// Note baudrate is hardcoded to 9600
2016-05-03 15:35:45 -03:00
state [ i ] . baud = AP_SERIALMANAGER_FRSKY_D_BAUD / 1000 ; // update baud param in case user looks at it
// begin is handled by AP_Frsky_telem library
2015-01-19 09:32:24 -04:00
break ;
2016-05-03 15:35:45 -03:00
case SerialProtocol_FrSky_SPort :
2016-05-03 18:29:30 -03:00
case SerialProtocol_FrSky_SPort_Passthrough :
2016-04-08 16:31:13 -03:00
// Note baudrate is hardcoded to 57600
2015-01-19 09:32:24 -04:00
state [ i ] . baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD / 1000 ; // update baud param in case user looks at it
2015-01-27 07:52:37 -04:00
// begin is handled by AP_Frsky_telem library
2015-01-19 09:32:24 -04:00
break ;
case SerialProtocol_GPS :
case SerialProtocol_GPS2 :
2015-01-29 00:35:42 -04:00
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ,
AP_SERIALMANAGER_GPS_BUFSIZE_RX ,
AP_SERIALMANAGER_GPS_BUFSIZE_TX ) ;
2015-01-19 09:32:24 -04:00
break ;
case SerialProtocol_AlexMos :
// Note baudrate is hardcoded to 115200
state [ i ] . baud = AP_SERIALMANAGER_ALEXMOS_BAUD / 1000 ; // update baud param in case user looks at it
2015-05-26 03:57:05 -03:00
state [ i ] . uart - > begin ( AP_SERIALMANAGER_ALEXMOS_BAUD ,
2015-01-29 00:35:42 -04:00
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX ,
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX ) ;
2015-01-19 09:32:24 -04:00
break ;
2015-05-26 03:57:05 -03:00
case SerialProtocol_SToRM32 :
// Note baudrate is hardcoded to 115200
state [ i ] . baud = AP_SERIALMANAGER_SToRM32_BAUD / 1000 ; // update baud param in case user looks at it
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ,
AP_SERIALMANAGER_SToRM32_BUFSIZE_RX ,
AP_SERIALMANAGER_SToRM32_BUFSIZE_TX ) ;
break ;
2016-11-14 17:46:11 -04:00
case SerialProtocol_Aerotenna_uLanding :
2018-02-27 12:00:32 -04:00
state [ i ] . protocol . set_and_save ( SerialProtocol_Rangefinder ) ;
2016-11-14 17:46:11 -04:00
break ;
2017-11-02 23:27:29 -03:00
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
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ,
AP_SERIALMANAGER_VOLZ_BUFSIZE_RX ,
AP_SERIALMANAGER_VOLZ_BUFSIZE_TX ) ;
2018-02-02 23:26:33 -04:00
state [ i ] . uart - > set_unbuffered_writes ( true ) ;
state [ i ] . uart - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
2017-11-02 23:27:29 -03:00
break ;
2017-08-21 17:31:51 -03:00
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 ) ;
2018-01-23 00:23:20 -04:00
state [ i ] . uart - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
2017-08-21 17:31:51 -03:00
break ;
2018-04-02 01:21:20 -03:00
case SerialProtocol_ESCTelemetry :
// ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200
state [ i ] . baud = 115200 ;
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) , 30 , 30 ) ;
state [ i ] . uart - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
break ;
2018-12-18 23:28:18 -04:00
case SerialProtocol_Robotis :
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ,
AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX ,
AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX ) ;
state [ i ] . uart - > set_unbuffered_writes ( true ) ;
state [ i ] . uart - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
break ;
2019-03-02 12:51:38 -04:00
2019-04-20 03:13:23 -03:00
case SerialProtocol_SLCAN :
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ,
AP_SERIALMANAGER_SLCAN_BUFSIZE_RX ,
AP_SERIALMANAGER_SLCAN_BUFSIZE_TX ) ;
break ;
2019-08-27 08:08:34 -03:00
# ifndef HAL_BUILD_AP_PERIPH
2019-08-27 04:41:21 -03:00
case SerialProtocol_RCIN :
AP : : RC ( ) . add_uart ( state [ i ] . uart ) ;
break ;
2019-08-27 08:08:34 -03:00
# endif
2019-08-27 04:41:21 -03:00
2019-03-02 12:51:38 -04:00
default :
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ) ;
2015-01-19 09:32:24 -04:00
}
}
}
}
2018-04-18 03:13:02 -03:00
const AP_SerialManager : : UARTState * AP_SerialManager : : find_protocol_instance ( enum SerialProtocol protocol , uint8_t instance ) const
2015-01-19 09:32:24 -04:00
{
2015-03-27 22:44:43 -03:00
uint8_t found_instance = 0 ;
2015-01-19 09:32:24 -04:00
// search for matching protocol
for ( uint8_t i = 0 ; i < SERIALMANAGER_NUM_PORTS ; i + + ) {
2015-03-27 22:44:43 -03:00
if ( protocol_match ( protocol , ( enum SerialProtocol ) state [ i ] . protocol . get ( ) ) ) {
if ( found_instance = = instance ) {
2018-04-18 03:13:02 -03:00
return & state [ i ] ;
2015-03-27 22:44:43 -03:00
}
found_instance + + ;
2015-01-29 00:35:42 -04:00
}
}
// if we got this far we did not find the uart
2016-10-30 02:24:21 -03:00
return nullptr ;
2015-01-29 00:35:42 -04:00
}
2018-04-18 03:13:02 -03:00
// find_serial - searches available serial ports for the first instance that allows the given protocol
// instance should be zero if searching for the first instance, 1 for the second, etc
// returns uart on success, nullptr if a serial port cannot be found
AP_HAL : : UARTDriver * AP_SerialManager : : find_serial ( enum SerialProtocol protocol , uint8_t instance ) const
{
const struct UARTState * _state = find_protocol_instance ( protocol , instance ) ;
if ( _state = = nullptr ) {
return nullptr ;
}
return _state - > uart ;
}
2015-01-29 00:35:42 -04:00
// find_baudrate - searches available serial ports for the first instance that allows the given protocol
2015-04-06 18:47:11 -03:00
// instance should be zero if searching for the first instance, 1 for the second, etc
2015-01-29 00:35:42 -04:00
// returns baudrate on success, 0 if a serial port cannot be found
2015-04-06 18:47:11 -03:00
uint32_t AP_SerialManager : : find_baudrate ( enum SerialProtocol protocol , uint8_t instance ) const
2015-01-29 00:35:42 -04:00
{
2018-04-18 03:13:02 -03:00
const struct UARTState * _state = find_protocol_instance ( protocol , instance ) ;
if ( _state = = nullptr ) {
return 0 ;
2015-01-19 09:32:24 -04:00
}
2018-07-09 02:16:07 -03:00
return map_baudrate ( _state - > baud ) ;
2015-01-19 09:32:24 -04:00
}
// get_mavlink_channel - provides the mavlink channel associated with a given protocol
2015-03-27 22:44:43 -03:00
// instance should be zero if searching for the first instance, 1 for the second, etc
2015-01-19 09:32:24 -04:00
// returns true if a channel is found, false if not
2015-03-27 22:44:43 -03:00
bool AP_SerialManager : : get_mavlink_channel ( enum SerialProtocol protocol , uint8_t instance , mavlink_channel_t & mav_chan ) const
2015-01-19 09:32:24 -04:00
{
2015-03-27 22:44:43 -03:00
// check for MAVLink
if ( protocol_match ( protocol , SerialProtocol_MAVLink ) ) {
2016-05-16 00:34:32 -03:00
if ( instance < MAVLINK_COMM_NUM_BUFFERS ) {
mav_chan = ( mavlink_channel_t ) ( MAVLINK_COMM_0 + instance ) ;
2015-05-02 09:38:26 -03:00
return true ;
}
2015-01-19 09:32:24 -04:00
}
2015-03-27 22:44:43 -03:00
// report failure
2015-01-19 09:32:24 -04:00
return false ;
}
2016-05-16 00:34:32 -03:00
// get_mavlink_protocol - provides the specific MAVLink protocol for a
// given channel, or SerialProtocol_None if not found
AP_SerialManager : : SerialProtocol AP_SerialManager : : get_mavlink_protocol ( mavlink_channel_t mav_chan ) const
{
uint8_t instance = 0 ;
uint8_t chan_idx = ( uint8_t ) ( mav_chan - MAVLINK_COMM_0 ) ;
for ( uint8_t i = 0 ; i < SERIALMANAGER_NUM_PORTS ; i + + ) {
if ( state [ i ] . protocol = = SerialProtocol_MAVLink | |
state [ i ] . protocol = = SerialProtocol_MAVLink2 ) {
if ( instance = = chan_idx ) {
return ( SerialProtocol ) state [ i ] . protocol . get ( ) ;
}
instance + + ;
}
}
return SerialProtocol_None ;
}
2019-01-04 05:51:05 -04:00
// get_serial_by_id - gets serial by serial id
AP_HAL : : UARTDriver * AP_SerialManager : : get_serial_by_id ( uint8_t id )
{
if ( id < SERIALMANAGER_NUM_PORTS ) {
return state [ id ] . uart ;
}
return nullptr ;
}
2015-01-19 09:32:24 -04:00
// set_blocking_writes_all - sets block_writes on or off for all serial channels
void AP_SerialManager : : set_blocking_writes_all ( bool blocking )
{
// set block_writes for all initialised serial ports
for ( uint8_t i = 0 ; i < SERIALMANAGER_NUM_PORTS ; i + + ) {
2016-10-30 02:24:21 -03:00
if ( state [ i ] . uart ! = nullptr ) {
2015-01-19 09:32:24 -04:00
state [ i ] . uart - > set_blocking_writes ( blocking ) ;
}
}
}
2015-01-29 00:47:36 -04:00
/*
2019-01-19 02:33:55 -04:00
* map from a 16 bit EEPROM baud rate to a real baud rate . For
* stm32 - based boards we can do 1.5 MBit , although 921600 is more
* reliable .
2015-01-29 00:47:36 -04:00
*/
uint32_t AP_SerialManager : : map_baudrate ( int32_t rate ) const
{
if ( rate < = 0 ) {
rate = 57 ;
}
switch ( rate ) {
case 1 : return 1200 ;
case 2 : return 2400 ;
case 4 : return 4800 ;
case 9 : return 9600 ;
case 19 : return 19200 ;
case 38 : return 38400 ;
case 57 : return 57600 ;
case 100 : return 100000 ;
case 111 : return 111100 ;
case 115 : return 115200 ;
case 230 : return 230400 ;
2019-01-08 10:44:46 -04:00
case 256 : return 256000 ;
2015-01-29 00:47:36 -04:00
case 460 : return 460800 ;
case 500 : return 500000 ;
case 921 : return 921600 ;
case 1500 : return 1500000 ;
}
if ( rate > 2000 ) {
// assume it is a direct baudrate. This allows for users to
// set an exact baudrate as long as it is over 2000 baud
return ( uint32_t ) rate ;
}
// otherwise allow any other kbaud rate
return rate * 1000 ;
}
2015-03-27 22:44:43 -03:00
// protocol_match - returns true if the protocols match
bool AP_SerialManager : : protocol_match ( enum SerialProtocol protocol1 , enum SerialProtocol protocol2 ) const
{
// check for obvious match
if ( protocol1 = = protocol2 ) {
return true ;
}
// mavlink match
if ( ( ( protocol1 = = SerialProtocol_MAVLink ) | | ( protocol1 = = SerialProtocol_MAVLink2 ) ) & &
2015-04-06 19:28:03 -03:00
( ( protocol2 = = SerialProtocol_MAVLink ) | | ( protocol2 = = SerialProtocol_MAVLink2 ) ) ) {
2015-03-27 22:44:43 -03:00
return true ;
}
// gps match
if ( ( ( protocol1 = = SerialProtocol_GPS ) | | ( protocol1 = = SerialProtocol_GPS2 ) ) & &
2015-04-06 19:28:03 -03:00
( ( protocol2 = = SerialProtocol_GPS ) | | ( protocol2 = = SerialProtocol_GPS2 ) ) ) {
2015-03-27 22:44:43 -03:00
return true ;
}
return false ;
}
2017-11-20 21:10:02 -04:00
2018-11-10 05:45:01 -04:00
// setup any special options
void AP_SerialManager : : set_options ( uint8_t i )
{
struct UARTState & opt = state [ i ] ;
// pass through to HAL
if ( ! opt . uart - > set_options ( opt . options ) ) {
hal . console - > printf ( " Unable to setup options for Serial%u \n " , i ) ;
}
}
2018-12-19 07:24:57 -04:00
// get the passthru ports if enabled
bool AP_SerialManager : : get_passthru ( AP_HAL : : UARTDriver * & port1 , AP_HAL : : UARTDriver * & port2 , uint8_t & timeout_s ) const
{
if ( passthru_port2 < 0 | |
passthru_port2 > = SERIALMANAGER_NUM_PORTS | |
passthru_port1 < 0 | |
passthru_port1 > = SERIALMANAGER_NUM_PORTS ) {
return false ;
}
port1 = state [ passthru_port1 ] . uart ;
port2 = state [ passthru_port2 ] . uart ;
timeout_s = MAX ( passthru_timeout , 0 ) ;
return true ;
}
// disable passthru by settings SERIAL_PASS2 to -1
void AP_SerialManager : : disable_passthru ( void )
{
passthru_port2 . set_and_notify ( - 1 ) ;
}
2017-11-20 21:10:02 -04:00
namespace AP {
AP_SerialManager & serialmanager ( )
{
2019-02-10 01:02:55 -04:00
return * AP_SerialManager : : get_singleton ( ) ;
2017-11-20 21:10:02 -04:00
}
}