From cc0bfcddcbb40745fbd832e8e0479b2b98608f81 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 22 Aug 2016 20:19:55 +0900 Subject: [PATCH] AP_SerialManager: add Lidar360 to protocol list This is used for the proximity sensor --- libraries/AP_SerialManager/AP_SerialManager.cpp | 14 +++++--------- libraries/AP_SerialManager/AP_SerialManager.h | 1 + 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index ed14e1ec02..24bd3a4ab0 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -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, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX) + // @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 // @User: Standard AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2), @@ -67,8 +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, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX) - // @User: Standard + // @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 // @User: Standard AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SerialProtocol_MAVLink), // @Param: 2_BAUD @@ -81,8 +80,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) - // @User: Standard + // @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 // @User: Standard AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS), // @Param: 3_BAUD @@ -95,8 +93,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) - // @User: Standard + // @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 // @User: Standard AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS), // @Param: 4_BAUD @@ -109,8 +106,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) - // @User: Standard + // @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 // @User: Standard AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL), // @Param: 5_BAUD diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 3b653e40f4..3a1e14ce83 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -82,6 +82,7 @@ public: SerialProtocol_SToRM32 = 8, SerialProtocol_Lidar = 9, SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers) + SerialProtocol_Lidar360 = 11, }; // Constructor