mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: remove special uLanding protocol type
Old protocol will be changed to Lidar on library init
This commit is contained in:
parent
398d0d1f37
commit
972264637c
|
@ -55,7 +55,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, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 12:Aerotenna uLanding, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @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, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink),
|
||||
|
@ -70,7 +70,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, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 12:Aerotenna uLanding, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @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, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SerialProtocol_MAVLink),
|
||||
|
@ -85,7 +85,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, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 12:Aerotenna uLanding, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @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, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS),
|
||||
|
@ -100,7 +100,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, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 12:Aerotenna uLanding, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @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, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS),
|
||||
|
@ -115,7 +115,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, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 12:Aerotenna uLanding, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @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, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
|
||||
|
@ -222,11 +222,7 @@ void AP_SerialManager::init()
|
|||
AP_SERIALMANAGER_SToRM32_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_Aerotenna_uLanding:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud = AP_SERIALMANAGER_ULANDING_BAUD / 1000; // update baud param in case user looks at it
|
||||
state[i].uart->begin(map_baudrate(state[i].baud),
|
||||
AP_SERIALMANAGER_ULANDING_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_ULANDING_BUFSIZE_TX);
|
||||
state[i].protocol.set_and_save(SerialProtocol_Lidar);
|
||||
break;
|
||||
case SerialProtocol_Volz:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
|
|
|
@ -63,12 +63,6 @@
|
|||
#define AP_SERIALMANAGER_SToRM32_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX 128
|
||||
|
||||
// Aerotenne uLanding Altimeter
|
||||
// Note that size of UART FIFO is 128 for Altera-OcPoc board
|
||||
#define AP_SERIALMANAGER_ULANDING_BAUD 115200
|
||||
#define AP_SERIALMANAGER_ULANDING_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_ULANDING_BUFSIZE_TX 128
|
||||
|
||||
#define AP_SERIALMANAGER_VOLZ_BAUD 115
|
||||
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128
|
||||
|
@ -101,7 +95,7 @@ public:
|
|||
SerialProtocol_Lidar = 9,
|
||||
SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
|
||||
SerialProtocol_Lidar360 = 11, // Lightware SF40C, TeraRanger Tower or RPLidarA2
|
||||
SerialProtocol_Aerotenna_uLanding = 12, // Ulanding support
|
||||
SerialProtocol_Aerotenna_uLanding = 12, // Ulanding support - deprecated, users should use Lidar
|
||||
SerialProtocol_Beacon = 13,
|
||||
SerialProtocol_Volz = 14, // Volz servo protocol
|
||||
SerialProtocol_Sbus1 = 15
|
||||
|
|
Loading…
Reference in New Issue