Skip to content

Commit f84b57c

Browse files
committed
OpenRB-150 지원
1 parent ef7ae1f commit f84b57c

12 files changed

+27
-23
lines changed

c++/include/dynamixel_sdk/packet_handler.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_
2323
#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_
2424

25-
#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
25+
#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
2626
#include <Arduino.h>
2727

2828
#define ERROR_PRINT SerialBT2.print

c++/include/dynamixel_sdk/port_handler.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
#else
3333
#define WINDECLSPEC __declspec(dllimport)
3434
#endif
35-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
35+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
3636
#define WINDECLSPEC
3737
#endif
3838

c++/include/dynamixel_sdk/port_handler_arduino.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_
2323
#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_
2424

25-
#if defined(ARDUINO) || defined(__OPENCR__) || defined (__OPENCM904__)
25+
#if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
2626
#include <Arduino.h>
2727
#endif
2828

c++/src/dynamixel_sdk/group_bulk_read.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
#elif defined(_WIN32) || defined(_WIN64)
2727
#define WINDLLEXPORT
2828
#include "group_bulk_read.h"
29-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
29+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
3030
#include "../../include/dynamixel_sdk/group_bulk_read.h"
3131
#endif
3232

c++/src/dynamixel_sdk/group_bulk_write.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#elif defined(_WIN32) || defined(_WIN64)
2626
#define WINDLLEXPORT
2727
#include "group_bulk_write.h"
28-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
28+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
2929
#include "../../include/dynamixel_sdk/group_bulk_write.h"
3030
#endif
3131

c++/src/dynamixel_sdk/group_sync_read.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#elif defined(_WIN32) || defined(_WIN64)
2626
#define WINDLLEXPORT
2727
#include "group_sync_read.h"
28-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
28+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
2929
#include "../../include/dynamixel_sdk/group_sync_read.h"
3030
#endif
3131

c++/src/dynamixel_sdk/group_sync_write.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#elif defined(_WIN32) || defined(_WIN64)
2626
#define WINDLLEXPORT
2727
#include "group_sync_write.h"
28-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
28+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
2929
#include "../../include/dynamixel_sdk/group_sync_write.h"
3030
#endif
3131

c++/src/dynamixel_sdk/packet_handler.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
#include "packet_handler.h"
3030
#include "protocol1_packet_handler.h"
3131
#include "protocol2_packet_handler.h"
32-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
32+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
3333
#include "../../include/dynamixel_sdk/packet_handler.h"
3434
#include "../../include/dynamixel_sdk/protocol1_packet_handler.h"
3535
#include "../../include/dynamixel_sdk/protocol2_packet_handler.h"

c++/src/dynamixel_sdk/port_handler.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
#define WINDLLEXPORT
2727
#include "port_handler.h"
2828
#include "port_handler_windows.h"
29-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
29+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
3030
#include "../../include/dynamixel_sdk/port_handler.h"
3131
#include "../../include/dynamixel_sdk/port_handler_arduino.h"
3232
#endif
@@ -41,7 +41,7 @@ PortHandler *PortHandler::getPortHandler(const char *port_name)
4141
return (PortHandler *)(new PortHandlerMac(port_name));
4242
#elif defined(_WIN32) || defined(_WIN64)
4343
return (PortHandler *)(new PortHandlerWindows(port_name));
44-
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
44+
#elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
4545
return (PortHandler *)(new PortHandlerArduino(port_name));
4646
#endif
4747
}

c++/src/dynamixel_sdk/port_handler_arduino.cpp

Lines changed: 15 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
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

@@ -27,6 +27,10 @@
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

3236
using 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

7579
bool 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()
9296
void 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

229233
bool 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

269273
void 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

276280
void 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

Comments
 (0)