mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: normalize SerialManagers ports defaults to allow inclusion in hwdefs
This commit is contained in:
parent
2ddaa65b23
commit
b4f9992ab7
|
@ -28,68 +28,101 @@
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#ifdef HAL_SERIAL1_PROTOCOL
|
#ifndef DEFAULT_SERIAL0_PROTOCOL
|
||||||
#define SERIAL1_PROTOCOL HAL_SERIAL1_PROTOCOL
|
#define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_MAVLink2
|
||||||
#else
|
#endif
|
||||||
#define SERIAL1_PROTOCOL SerialProtocol_MAVLink2
|
#ifndef DEFAULT_SERIAL0_BAUD
|
||||||
|
#define DEFAULT_SERIAL0_BAUD AP_SERIALMANAGER_CONSOLE_BAUD
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_SERIAL2_PROTOCOL
|
#ifndef DEFAULT_SERIAL1_PROTOCOL
|
||||||
#define SERIAL2_PROTOCOL HAL_SERIAL2_PROTOCOL
|
#define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MAVLink2
|
||||||
#else
|
#endif
|
||||||
#define SERIAL2_PROTOCOL SerialProtocol_MAVLink2
|
#ifndef DEFAULT_SERIAL1_BAUD
|
||||||
|
#define DEFAULT_SERIAL1_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
||||||
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL1_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL1_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_SERIAL3_PROTOCOL
|
#ifndef DEFAULT_SERIAL2_PROTOCOL
|
||||||
#define SERIAL3_PROTOCOL SerialProtocol_GPS
|
#define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MAVLink2
|
||||||
#else
|
#endif
|
||||||
#define SERIAL3_PROTOCOL HAL_SERIAL3_PROTOCOL
|
#ifndef DEFAULT_SERIAL2_BAUD
|
||||||
|
#define DEFAULT_SERIAL2_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
||||||
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL2_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL2_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_SERIAL4_PROTOCOL
|
#ifndef DEFAULT_SERIAL3_PROTOCOL
|
||||||
#define SERIAL4_PROTOCOL SerialProtocol_GPS
|
#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS
|
||||||
#else
|
#endif
|
||||||
#define SERIAL4_PROTOCOL HAL_SERIAL4_PROTOCOL
|
#ifndef DEFAULT_SERIAL3_BAUD
|
||||||
|
#define DEFAULT_SERIAL3_BAUD AP_SERIALMANAGER_GPS_BAUD/1000
|
||||||
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL3_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL3_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_SERIAL5_PROTOCOL
|
#ifndef DEFAULT_SERIAL4_PROTOCOL
|
||||||
#define SERIAL5_PROTOCOL HAL_SERIAL5_PROTOCOL
|
#define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS
|
||||||
#define SERIAL5_BAUD HAL_SERIAL5_BAUD
|
#endif
|
||||||
#else
|
#ifndef DEFAULT_SERIAL4_BAUD
|
||||||
#define SERIAL5_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL4_BAUD AP_SERIALMANAGER_GPS_BAUD/1000
|
||||||
#define SERIAL5_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL4_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL4_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_SERIAL6_PROTOCOL
|
#ifndef DEFAULT_SERIAL5_PROTOCOL
|
||||||
#define SERIAL6_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL6_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
#endif
|
||||||
#else
|
#ifndef DEFAULT_SERIAL5_BAUD
|
||||||
#define SERIAL6_PROTOCOL HAL_SERIAL6_PROTOCOL
|
#define DEFAULT_SERIAL5_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
||||||
#define SERIAL6_BAUD HAL_SERIAL6_BAUD
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL5_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL5_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_SERIAL7_PROTOCOL
|
#ifndef DEFAULT_SERIAL6_PROTOCOL
|
||||||
#define SERIAL7_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL7_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
#endif
|
||||||
#else
|
#ifndef DEFAULT_SERIAL6_BAUD
|
||||||
#define SERIAL7_PROTOCOL HAL_SERIAL7_PROTOCOL
|
#define DEFAULT_SERIAL6_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
||||||
#define SERIAL7_BAUD HAL_SERIAL7_BAUD
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL6_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL6_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_SERIAL8_PROTOCOL
|
#ifndef DEFAULT_SERIAL7_PROTOCOL
|
||||||
#define SERIAL8_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL8_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
#endif
|
||||||
#else
|
#ifndef DEFAULT_SERIAL7_BAUD
|
||||||
#define SERIAL8_PROTOCOL HAL_SERIAL8_PROTOCOL
|
#define DEFAULT_SERIAL7_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
||||||
#define SERIAL8_BAUD HAL_SERIAL8_BAUD
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL7_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL7_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_SERIAL9_PROTOCOL
|
#ifndef DEFAULT_SERIAL8_PROTOCOL
|
||||||
#define SERIAL9_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL9_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
#endif
|
||||||
#else
|
#ifndef DEFAULT_SERIAL8_BAUD
|
||||||
#define SERIAL9_PROTOCOL HAL_SERIAL9_PROTOCOL
|
#define DEFAULT_SERIAL8_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
||||||
#define SERIAL9_BAUD HAL_SERIAL9_BAUD
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL8_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL8_OPTIONS 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef DEFAULT_SERIAL9_PROTOCOL
|
||||||
|
#define DEFAULT_SERIAL9_PROTOCOL SerialProtocol_None
|
||||||
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL9_BAUD
|
||||||
|
#define DEFAULT_SERIAL9_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000
|
||||||
|
#endif
|
||||||
|
#ifndef DEFAULT_SERIAL9_OPTIONS
|
||||||
|
#define DEFAULT_SERIAL9_OPTIONS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_BUILD_AP_PERIPH
|
#ifdef HAL_BUILD_AP_PERIPH
|
||||||
|
@ -98,26 +131,26 @@ extern const AP_HAL::HAL& hal;
|
||||||
supported serial device type has it's own parameter within AP_Periph
|
supported serial device type has it's own parameter within AP_Periph
|
||||||
for which port is used.
|
for which port is used.
|
||||||
*/
|
*/
|
||||||
#undef SERIAL0_PROTOCOL
|
#undef DEFAULT_SERIAL0_PROTOCOL
|
||||||
#undef SERIAL1_PROTOCOL
|
#undef DEFAULT_SERIAL1_PROTOCOL
|
||||||
#undef SERIAL2_PROTOCOL
|
#undef DEFAULT_SERIAL2_PROTOCOL
|
||||||
#undef SERIAL3_PROTOCOL
|
#undef DEFAULT_SERIAL3_PROTOCOL
|
||||||
#undef SERIAL4_PROTOCOL
|
#undef DEFAULT_SERIAL4_PROTOCOL
|
||||||
#undef SERIAL5_PROTOCOL
|
#undef DEFAULT_SERIAL5_PROTOCOL
|
||||||
#undef SERIAL6_PROTOCOL
|
#undef DEFAULT_SERIAL6_PROTOCOL
|
||||||
#undef SERIAL7_PROTOCOL
|
#undef DEFAULT_SERIAL7_PROTOCOL
|
||||||
#undef SERIAL8_PROTOCOL
|
#undef DEFAULT_SERIAL8_PROTOCOL
|
||||||
#undef SERIAL9_PROTOCOL
|
#undef DEFAULT_SERIAL9_PROTOCOL
|
||||||
#define SERIAL0_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL1_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL2_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL3_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL4_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL5_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL6_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL7_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL8_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_None
|
||||||
#define SERIAL9_PROTOCOL SerialProtocol_None
|
#define DEFAULT_SERIAL9_PROTOCOL SerialProtocol_None
|
||||||
#endif // HAL_BUILD_AP_PERIPH
|
#endif // HAL_BUILD_AP_PERIPH
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
|
@ -127,7 +160,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @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.
|
// @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.
|
||||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000,2000:2000000
|
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000,2000:2000000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("0_BAUD", 0, AP_SerialManager, state[0].baud, AP_SERIALMANAGER_CONSOLE_BAUD/1000),
|
AP_GROUPINFO("0_BAUD", 0, AP_SerialManager, state[0].baud, DEFAULT_SERIAL0_BAUD/1000),
|
||||||
|
|
||||||
// @Param: 0_PROTOCOL
|
// @Param: 0_PROTOCOL
|
||||||
// @DisplayName: Console protocol selection
|
// @DisplayName: Console protocol selection
|
||||||
|
@ -145,14 +178,14 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @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, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp
|
// @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, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SERIAL1_PROTOCOL),
|
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, DEFAULT_SERIAL1_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 1_BAUD
|
// @Param: 1_BAUD
|
||||||
// @DisplayName: Telem1 Baud Rate
|
// @DisplayName: Telem1 Baud Rate
|
||||||
// @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.
|
// @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.
|
||||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000,2000:2000000
|
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000,2000:2000000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("1_BAUD", 2, AP_SerialManager, state[1].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
|
AP_GROUPINFO("1_BAUD", 2, AP_SerialManager, state[1].baud, DEFAULT_SERIAL1_BAUD),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 2
|
#if SERIALMANAGER_NUM_PORTS > 2
|
||||||
|
@ -160,13 +193,13 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Telemetry 2 protocol selection
|
// @DisplayName: Telemetry 2 protocol selection
|
||||||
// @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SERIAL2_PROTOCOL),
|
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, DEFAULT_SERIAL2_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 2_BAUD
|
// @Param: 2_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Telemetry 2 Baud Rate
|
// @DisplayName: Telemetry 2 Baud Rate
|
||||||
// @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.
|
// @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.
|
||||||
AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
|
AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, DEFAULT_SERIAL2_BAUD),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 3
|
#if SERIALMANAGER_NUM_PORTS > 3
|
||||||
|
@ -174,13 +207,13 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Serial 3 (GPS) protocol selection
|
// @DisplayName: Serial 3 (GPS) protocol selection
|
||||||
// @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.
|
// @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.
|
||||||
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SERIAL3_PROTOCOL),
|
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, DEFAULT_SERIAL3_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 3_BAUD
|
// @Param: 3_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Serial 3 (GPS) Baud Rate
|
// @DisplayName: Serial 3 (GPS) Baud Rate
|
||||||
// @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.
|
// @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.
|
||||||
AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
|
AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, DEFAULT_SERIAL3_BAUD),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 4
|
#if SERIALMANAGER_NUM_PORTS > 4
|
||||||
|
@ -188,13 +221,13 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Serial4 protocol selection
|
// @DisplayName: Serial4 protocol selection
|
||||||
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SERIAL4_PROTOCOL),
|
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, DEFAULT_SERIAL4_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 4_BAUD
|
// @Param: 4_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Serial 4 Baud Rate
|
// @DisplayName: Serial 4 Baud Rate
|
||||||
// @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.
|
// @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.
|
||||||
AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
|
AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, DEFAULT_SERIAL4_BAUD),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 5
|
#if SERIALMANAGER_NUM_PORTS > 5
|
||||||
|
@ -202,13 +235,13 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Serial5 protocol selection
|
// @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.
|
// @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
|
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, DEFAULT_SERIAL5_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 5_BAUD
|
// @Param: 5_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Serial 5 Baud Rate
|
// @DisplayName: Serial 5 Baud Rate
|
||||||
// @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.
|
// @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.
|
||||||
AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD),
|
AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, DEFAULT_SERIAL5_BAUD),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// index 11 used by 0_PROTOCOL
|
// index 11 used by 0_PROTOCOL
|
||||||
|
@ -218,13 +251,13 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Serial6 protocol selection
|
// @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.
|
// @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL),
|
AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, DEFAULT_SERIAL6_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 6_BAUD
|
// @Param: 6_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Serial 6 Baud Rate
|
// @DisplayName: Serial 6 Baud Rate
|
||||||
// @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.
|
// @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.
|
||||||
AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, SERIAL6_BAUD),
|
AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, DEFAULT_SERIAL6_BAUD),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 1
|
#if SERIALMANAGER_NUM_PORTS > 1
|
||||||
|
@ -234,42 +267,42 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO, 12: Ignore Streamrate
|
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:Swap, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO, 12: Ignore Streamrate
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("1_OPTIONS", 14, AP_SerialManager, state[1].options, 0),
|
AP_GROUPINFO("1_OPTIONS", 14, AP_SerialManager, state[1].options, DEFAULT_SERIAL1_OPTIONS),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 2
|
#if SERIALMANAGER_NUM_PORTS > 2
|
||||||
// @Param: 2_OPTIONS
|
// @Param: 2_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
// @DisplayName: Telem2 options
|
// @DisplayName: Telem2 options
|
||||||
AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, 0),
|
AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, DEFAULT_SERIAL2_OPTIONS),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 3
|
#if SERIALMANAGER_NUM_PORTS > 3
|
||||||
// @Param: 3_OPTIONS
|
// @Param: 3_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
// @DisplayName: Serial3 options
|
// @DisplayName: Serial3 options
|
||||||
AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, 0),
|
AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, DEFAULT_SERIAL3_OPTIONS),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 4
|
#if SERIALMANAGER_NUM_PORTS > 4
|
||||||
// @Param: 4_OPTIONS
|
// @Param: 4_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
// @DisplayName: Serial4 options
|
// @DisplayName: Serial4 options
|
||||||
AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, 0),
|
AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, DEFAULT_SERIAL4_OPTIONS),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 5
|
#if SERIALMANAGER_NUM_PORTS > 5
|
||||||
// @Param: 5_OPTIONS
|
// @Param: 5_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
// @DisplayName: Serial5 options
|
// @DisplayName: Serial5 options
|
||||||
AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, 0),
|
AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, DEFAULT_SERIAL5_OPTIONS),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if SERIALMANAGER_NUM_PORTS > 6
|
#if SERIALMANAGER_NUM_PORTS > 6
|
||||||
// @Param: 6_OPTIONS
|
// @Param: 6_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
// @DisplayName: Serial6 options
|
// @DisplayName: Serial6 options
|
||||||
AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, 0),
|
AP_GROUPINFO("6_OPTIONS", 19, AP_SerialManager, state[6].options, DEFAULT_SERIAL6_OPTIONS),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Param: _PASS1
|
// @Param: _PASS1
|
||||||
|
@ -299,13 +332,13 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Serial7 protocol selection
|
// @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.
|
// @Description: Control what protocol Serial7 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
AP_GROUPINFO("7_PROTOCOL", 23, AP_SerialManager, state[7].protocol, SERIAL7_PROTOCOL),
|
AP_GROUPINFO("7_PROTOCOL", 23, AP_SerialManager, state[7].protocol, DEFAULT_SERIAL7_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 7_BAUD
|
// @Param: 7_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Serial 7 Baud Rate
|
// @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.
|
// @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.
|
||||||
AP_GROUPINFO("7_BAUD", 24, AP_SerialManager, state[7].baud, SERIAL7_BAUD),
|
AP_GROUPINFO("7_BAUD", 24, AP_SerialManager, state[7].baud, DEFAULT_SERIAL7_BAUD),
|
||||||
|
|
||||||
// @Param: 7_OPTIONS
|
// @Param: 7_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
|
@ -318,13 +351,13 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Serial8 protocol selection
|
// @DisplayName: Serial8 protocol selection
|
||||||
// @Description: Control what protocol Serial8 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol Serial8 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
AP_GROUPINFO("8_PROTOCOL", 26, AP_SerialManager, state[8].protocol, SERIAL8_PROTOCOL),
|
AP_GROUPINFO("8_PROTOCOL", 26, AP_SerialManager, state[8].protocol, DEFAULT_SERIAL8_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 8_BAUD
|
// @Param: 8_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Serial 8 Baud Rate
|
// @DisplayName: Serial 8 Baud Rate
|
||||||
// @Description: The baud rate used for Serial8. 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.
|
// @Description: The baud rate used for Serial8. 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.
|
||||||
AP_GROUPINFO("8_BAUD", 27, AP_SerialManager, state[8].baud, SERIAL8_BAUD),
|
AP_GROUPINFO("8_BAUD", 27, AP_SerialManager, state[8].baud, DEFAULT_SERIAL8_BAUD),
|
||||||
|
|
||||||
// @Param: 8_OPTIONS
|
// @Param: 8_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
|
@ -337,18 +370,18 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
// @CopyFieldsFrom: SERIAL1_PROTOCOL
|
||||||
// @DisplayName: Serial9 protocol selection
|
// @DisplayName: Serial9 protocol selection
|
||||||
// @Description: Control what protocol Serial9 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol Serial9 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
AP_GROUPINFO("9_PROTOCOL", 29, AP_SerialManager, state[9].protocol, SERIAL9_PROTOCOL),
|
AP_GROUPINFO("9_PROTOCOL", 29, AP_SerialManager, state[9].protocol, DEFAULT_SERIAL9_PROTOCOL),
|
||||||
|
|
||||||
// @Param: 9_BAUD
|
// @Param: 9_BAUD
|
||||||
// @CopyFieldsFrom: SERIAL1_BAUD
|
// @CopyFieldsFrom: SERIAL1_BAUD
|
||||||
// @DisplayName: Serial 9 Baud Rate
|
// @DisplayName: Serial 9 Baud Rate
|
||||||
// @Description: The baud rate used for Serial8. 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.
|
// @Description: The baud rate used for Serial8. 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.
|
||||||
AP_GROUPINFO("9_BAUD", 30, AP_SerialManager, state[9].baud, SERIAL9_BAUD),
|
AP_GROUPINFO("9_BAUD", 30, AP_SerialManager, state[9].baud, DEFAULT_SERIAL9_BAUD),
|
||||||
|
|
||||||
// @Param: 9_OPTIONS
|
// @Param: 9_OPTIONS
|
||||||
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
// @CopyFieldsFrom: SERIAL1_OPTIONS
|
||||||
// @DisplayName: Serial9 options
|
// @DisplayName: Serial9 options
|
||||||
AP_GROUPINFO("9_OPTIONS", 31, AP_SerialManager, state[9].options, 0),
|
AP_GROUPINFO("9_OPTIONS", 31, AP_SerialManager, state[9].options, DEFAULT_SERIAL9_OPTIONS),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -372,7 +405,7 @@ void AP_SerialManager::init_console()
|
||||||
#if SERIALMANAGER_NUM_PORTS > 0
|
#if SERIALMANAGER_NUM_PORTS > 0
|
||||||
if (!init_console_done) {
|
if (!init_console_done) {
|
||||||
init_console_done = true;
|
init_console_done = true;
|
||||||
hal.serial(0)->begin(AP_SERIALMANAGER_CONSOLE_BAUD,
|
hal.serial(0)->begin(DEFAULT_SERIAL0_BAUD,
|
||||||
AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX,
|
AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX,
|
||||||
AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX);
|
AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX);
|
||||||
}
|
}
|
||||||
|
|
|
@ -51,8 +51,8 @@
|
||||||
|
|
||||||
|
|
||||||
// console default baud rates and buffer sizes
|
// console default baud rates and buffer sizes
|
||||||
#ifdef HAL_SERIAL0_BAUD_DEFAULT
|
#ifdef DEFAULT_SERIAL0_BAUD
|
||||||
# define AP_SERIALMANAGER_CONSOLE_BAUD HAL_SERIAL0_BAUD_DEFAULT
|
#define AP_SERIALMANAGER_CONSOLE_BAUD DEFAULT_SERIAL0_BAUD
|
||||||
#else
|
#else
|
||||||
#define AP_SERIALMANAGER_CONSOLE_BAUD 115200
|
#define AP_SERIALMANAGER_CONSOLE_BAUD 115200
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue