1616
1717/* Author: Ryu Woon Jung (Leon) */
1818
19- #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
19+ #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
2020
2121#include < Arduino.h>
2222
2727#define DYNAMIXEL_SERIAL Serial3
2828#endif
2929
30+ #if defined (ARDUINO_OpenRB)
31+ #define DYNAMIXEL_SERIAL Serial1
32+ #endif
33+
3034#define LATENCY_TIMER 4 // msec (USB latency timer)
3135
3236using namespace dynamixel ;
@@ -40,7 +44,7 @@ PortHandlerArduino::PortHandlerArduino(const char *port_name)
4044 is_using_ = false ;
4145 setPortName (port_name);
4246
43- #if defined(__OPENCR__)
47+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
4448 pinMode (BDPIN_DXL_PWR_EN, OUTPUT);
4549
4650 setPowerOff ();
@@ -74,7 +78,7 @@ PortHandlerArduino::PortHandlerArduino(const char *port_name)
7478
7579bool PortHandlerArduino::openPort ()
7680{
77- #if defined(__OPENCR__)
81+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
7882 pinMode (BDPIN_DXL_PWR_EN, OUTPUT);
7983
8084 setPowerOn ();
@@ -92,7 +96,7 @@ void PortHandlerArduino::closePort()
9296void PortHandlerArduino::clearPort ()
9397{
9498 int temp __attribute__ ((unused));
95- #if defined(__OPENCR__)
99+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
96100 while (DYNAMIXEL_SERIAL.available ())
97101 {
98102 temp = DYNAMIXEL_SERIAL.read ();
@@ -136,7 +140,7 @@ int PortHandlerArduino::getBytesAvailable()
136140{
137141 int bytes_available;
138142
139- #if defined(__OPENCR__)
143+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
140144 bytes_available = DYNAMIXEL_SERIAL.available ();
141145#elif defined(__OPENCM904__)
142146 bytes_available = p_dxl_serial->available ();
@@ -149,7 +153,7 @@ int PortHandlerArduino::readPort(uint8_t *packet, int length)
149153{
150154 int rx_length;
151155
152- #if defined(__OPENCR__)
156+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
153157 rx_length = DYNAMIXEL_SERIAL.available ();
154158#elif defined(__OPENCM904__)
155159 rx_length = p_dxl_serial->available ();
@@ -160,7 +164,7 @@ int PortHandlerArduino::readPort(uint8_t *packet, int length)
160164
161165 for (int i = 0 ; i < rx_length; i++)
162166 {
163- #if defined(__OPENCR__)
167+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
164168 packet[i] = DYNAMIXEL_SERIAL.read ();
165169#elif defined(__OPENCM904__)
166170 packet[i] = p_dxl_serial->read ();
@@ -176,7 +180,7 @@ int PortHandlerArduino::writePort(uint8_t *packet, int length)
176180
177181 setTxEnable ();
178182
179- #if defined(__OPENCR__)
183+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
180184 length_written = DYNAMIXEL_SERIAL.write (packet, length);
181185#elif defined(__OPENCM904__)
182186 length_written = p_dxl_serial->write (packet, length);
@@ -228,7 +232,7 @@ double PortHandlerArduino::getTimeSinceStart()
228232
229233bool PortHandlerArduino::setupPort (int baudrate)
230234{
231- #if defined(__OPENCR__)
235+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
232236 DYNAMIXEL_SERIAL.begin (baudrate);
233237#elif defined(__OPENCM904__)
234238 p_dxl_serial->setDxlMode (true );
@@ -268,14 +272,14 @@ int PortHandlerArduino::checkBaudrateAvailable(int baudrate)
268272
269273void PortHandlerArduino::setPowerOn ()
270274{
271- #if defined(__OPENCR__)
275+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
272276 digitalWrite (BDPIN_DXL_PWR_EN, HIGH);
273277#endif
274278}
275279
276280void PortHandlerArduino::setPowerOff ()
277281{
278- #if defined(__OPENCR__)
282+ #if defined(__OPENCR__) || defined(ARDUINO_OpenRB)
279283 digitalWrite (BDPIN_DXL_PWR_EN, LOW);
280284#endif
281285}
0 commit comments