mirror of https://github.com/ArduPilot/ardupilot
AP_RobotisServo: move serial port init of RobotisServo protocol into RobotisServo library
This commit is contained in:
parent
94380eb9be
commit
9e16112e7f
|
@ -138,11 +138,18 @@ void AP_RobotisServo::init(void)
|
|||
{
|
||||
AP_SerialManager &serial_manager = AP::serialmanager();
|
||||
port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Robotis,0);
|
||||
if (port) {
|
||||
baudrate = serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Robotis, 0);
|
||||
us_per_byte = 10 * 1e6 / baudrate;
|
||||
us_gap = 4 * 1e6 / baudrate;
|
||||
if (port == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
const uint32_t baudrate = serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Robotis, 0);
|
||||
|
||||
port->begin(baudrate, 128, 128);
|
||||
port->set_unbuffered_writes(true);
|
||||
port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
|
||||
us_per_byte = 10 * 1e6 / baudrate;
|
||||
us_gap = 4 * 1e6 / baudrate;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -42,7 +42,6 @@ public:
|
|||
|
||||
private:
|
||||
AP_HAL::UARTDriver *port;
|
||||
uint32_t baudrate;
|
||||
uint32_t us_per_byte;
|
||||
uint32_t us_gap;
|
||||
|
||||
|
|
Loading…
Reference in New Issue