mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_SerialManager: generalise SToRM32 serial protocol desc and enum
This commit is contained in:
parent
237a3782a3
commit
e672a75776
@ -11,7 +11,7 @@ void AP_Mount_SToRM32_serial::init()
|
||||
{
|
||||
const AP_SerialManager& serial_manager = AP::serialmanager();
|
||||
|
||||
_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_SToRM32, 0);
|
||||
_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0);
|
||||
if (_port) {
|
||||
_initialised = true;
|
||||
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
||||
|
@ -28,7 +28,7 @@ void AP_Mount_Siyi::init()
|
||||
{
|
||||
const AP_SerialManager& serial_manager = AP::serialmanager();
|
||||
|
||||
_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_SToRM32, 0);
|
||||
_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0);
|
||||
if (_uart != nullptr) {
|
||||
_initialised = true;
|
||||
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
||||
|
@ -148,7 +148,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: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:Gimbal, 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
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, DEFAULT_SERIAL1_PROTOCOL),
|
||||
@ -454,12 +454,12 @@ void AP_SerialManager::init()
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_SToRM32:
|
||||
case SerialProtocol_Gimbal:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_SToRM32_BAUD / 1000); // update baud param in case user looks at it
|
||||
state[i].baud.set_and_default(AP_SERIALMANAGER_GIMBAL_BAUD / 1000); // update baud param in case user looks at it
|
||||
uart->begin(state[i].baudrate(),
|
||||
AP_SERIALMANAGER_SToRM32_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_SToRM32_BUFSIZE_TX);
|
||||
AP_SERIALMANAGER_GIMBAL_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_Aerotenna_USD1:
|
||||
state[i].protocol.set_and_save(SerialProtocol_Rangefinder);
|
||||
|
@ -85,9 +85,9 @@
|
||||
#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128
|
||||
|
||||
#define AP_SERIALMANAGER_SToRM32_BAUD 115200
|
||||
#define AP_SERIALMANAGER_SToRM32_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_SToRM32_BUFSIZE_TX 128
|
||||
#define AP_SERIALMANAGER_GIMBAL_BAUD 115200
|
||||
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_RX 128
|
||||
#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128
|
||||
|
||||
#define AP_SERIALMANAGER_VOLZ_BAUD 115
|
||||
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
|
||||
@ -132,7 +132,7 @@ public:
|
||||
SerialProtocol_GPS = 5,
|
||||
SerialProtocol_GPS2 = 6, // do not use - use GPS and provide instance of 1
|
||||
SerialProtocol_AlexMos = 7,
|
||||
SerialProtocol_SToRM32 = 8,
|
||||
SerialProtocol_Gimbal = 8, // SToRM32, Siyi custom serial protocols
|
||||
SerialProtocol_Rangefinder = 9,
|
||||
SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
|
||||
SerialProtocol_Lidar360 = 11, // Lightware SF40C, TeraRanger Tower or RPLidarA2
|
||||
|
Loading…
Reference in New Issue
Block a user