mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SerialManager: add SToRM32 serial enum and baudrates
This commit is contained in:
parent
544eb8ea3f
commit
69959a4214
@ -160,6 +160,13 @@ void AP_SerialManager::init()
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX);
|
||||
break;
|
||||
case SerialProtocol_SToRM32:
|
||||
// Note baudrate is hardcoded to 115200
|
||||
state[i].baud = AP_SERIALMANAGER_SToRM32_BAUD / 1000; // update baud param in case user looks at it
|
||||
state[i].uart->begin(map_baudrate(state[i].baud),
|
||||
AP_SERIALMANAGER_SToRM32_BUFSIZE_RX,
|
||||
AP_SERIALMANAGER_SToRM32_BUFSIZE_TX);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -58,11 +58,15 @@
|
||||
#define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16
|
||||
|
||||
// AlexMos Gimbal protocol default baud rates and buffer sizes
|
||||
// we need a 256 byte buffer for some GPS types (eg. UBLOX)
|
||||
#define AP_SERIALMANAGER_ALEXMOS_BAUD 115200
|
||||
#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
|
||||
|
||||
|
||||
class AP_SerialManager {
|
||||
|
||||
public:
|
||||
@ -75,7 +79,8 @@ public:
|
||||
SerialProtocol_FRSky_SPort = 4,
|
||||
SerialProtocol_GPS = 5,
|
||||
SerialProtocol_GPS2 = 6, // do not use - use GPS and provide instance of 1
|
||||
SerialProtocol_AlexMos = 7
|
||||
SerialProtocol_AlexMos = 7,
|
||||
SerialProtocol_SToRM32 = 8,
|
||||
};
|
||||
|
||||
// Constructor
|
||||
|
Loading…
Reference in New Issue
Block a user