SerialManager: add SToRM32 serial enum and baudrates

This commit is contained in:
Sergey Kirillov 2015-05-26 15:57:05 +09:00 committed by Randy Mackay
parent 544eb8ea3f
commit 69959a4214
2 changed files with 15 additions and 3 deletions

View File

@ -156,10 +156,17 @@ void AP_SerialManager::init()
case SerialProtocol_AlexMos:
// Note baudrate is hardcoded to 115200
state[i].baud = AP_SERIALMANAGER_ALEXMOS_BAUD / 1000; // update baud param in case user looks at it
state[i].uart->begin(AP_SERIALMANAGER_ALEXMOS_BAUD,
state[i].uart->begin(AP_SERIALMANAGER_ALEXMOS_BAUD,
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;
}
}
}

View File

@ -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