mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_SerialManager: syntax and minor lib rework
This commit is contained in:
parent
de2a7013b4
commit
5066a5bc73
@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 1_PROTOCOL
|
||||
// @DisplayName: Telem1 protocol selection
|
||||
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||
// @Values: -1:None, 1:MAVlink1, 2:MAVLink2, 3:Frsky D-PORT, 4:Frsky S-PORT, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @Values: -1:None, 1:Mavlink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink),
|
||||
|
||||
@ -67,7 +67,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 2_PROTOCOL
|
||||
// @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.
|
||||
// @Values: -1:None, 1:MAVlink1, 2:MAVLink2, 3:Frsky D-PORT, 4:Frsky S-PORT, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @Values: -1:None, 1:Mavlink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SerialProtocol_MAVLink),
|
||||
|
||||
@ -81,7 +81,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 3_PROTOCOL
|
||||
// @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.
|
||||
// @Values: -1:None, 1:MAVlink1, 2:MAVLink2, 3:Frsky D-PORT, 4:Frsky S-PORT, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @Values: -1:None, 1:Mavlink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS),
|
||||
|
||||
@ -95,7 +95,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 4_PROTOCOL
|
||||
// @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.
|
||||
// @Values: -1:None, 1:MAVlink1, 2:MAVLink2, 3:Frsky D-PORT, 4:Frsky S-PORT, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @Values: -1:None, 1:Mavlink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS),
|
||||
|
||||
@ -109,7 +109,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 5_PROTOCOL
|
||||
// @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.
|
||||
// @Values: -1:None, 1:MAVlink1, 2:MAVLink2, 3:Frsky D-PORT, 4:Frsky S-PORT, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @Values: -1:None, 1:Mavlink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
|
||||
|
||||
@ -169,14 +169,12 @@ void AP_SerialManager::init()
|
||||
AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_FRSky_DPort:
|
||||
case SerialProtocol_FrSky_D:
|
||||
// Note baudrate is hardcoded to 9600
|
||||
state[i].baud = AP_SERIALMANAGER_FRSKY_DPORT_BAUD/1000; // update baud param in case user looks at it
|
||||
state[i].uart->begin(AP_SERIALMANAGER_FRSKY_DPORT_BAUD,
|
||||
AP_SERIALMANAGER_FRSKY_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_FRSKY_BUFSIZE_TX);
|
||||
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
|
||||
break;
|
||||
case SerialProtocol_FRSky_SPort:
|
||||
case SerialProtocol_FrSky_SPort:
|
||||
// Note baudrate is hardcoded to 57600
|
||||
state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it
|
||||
// begin is handled by AP_Frsky_telem library
|
||||
|
@ -43,8 +43,8 @@
|
||||
#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256
|
||||
|
||||
// mavlink default baud rates, use default buffer sizes
|
||||
#define AP_SERIALMANAGER_FRSKY_DPORT_BAUD 9600
|
||||
// FrSky default baud rates, use default buffer sizes
|
||||
#define AP_SERIALMANAGER_FRSKY_D_BAUD 9600
|
||||
#define AP_SERIALMANAGER_FRSKY_SPORT_BAUD 57600
|
||||
#define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX 0
|
||||
#define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX 0
|
||||
@ -73,11 +73,11 @@ public:
|
||||
SerialProtocol_None = -1,
|
||||
SerialProtocol_Console = 0, // unused
|
||||
SerialProtocol_MAVLink = 1,
|
||||
SerialProtocol_MAVLink2 = 2, // do not use - use MAVLink and provide instance of 1
|
||||
SerialProtocol_FRSky_DPort = 3,
|
||||
SerialProtocol_FRSky_SPort = 4,
|
||||
SerialProtocol_MAVLink2 = 2, // do not use - use MAVLink and provide instance of 1
|
||||
SerialProtocol_FrSky_D = 3, // FrSky D protocol (D-receivers)
|
||||
SerialProtocol_FrSky_SPort = 4, // FrSky SPort protocol (X-receivers)
|
||||
SerialProtocol_GPS = 5,
|
||||
SerialProtocol_GPS2 = 6, // do not use - use GPS and provide instance of 1
|
||||
SerialProtocol_GPS2 = 6, // do not use - use GPS and provide instance of 1
|
||||
SerialProtocol_AlexMos = 7,
|
||||
SerialProtocol_SToRM32 = 8,
|
||||
SerialProtocol_Lidar = 9,
|
||||
|
Loading…
Reference in New Issue
Block a user