Skip to content

Commit ee03828

Browse files
authored
Merge pull request #54 from ROBOTIS-GIT/develop
Develop
2 parents 981c322 + 8defd3e commit ee03828

File tree

6 files changed

+71
-6
lines changed

6 files changed

+71
-6
lines changed

install.sh

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ fi
1010
# this will be eval'd in the functions below because arrays can't be exported
1111
# For creating a new main platform, please refer to https://arduino.github.io/arduino-cli/latest/platform-specification/#hardware-folders-structure
1212
# and https://arduino.github.io/arduino-cli/latest/platform-specification/#boardstxt
13-
export MAIN_PLATFORMS='declare -A main_platforms=([uno]="arduino:avr:uno" [mega2560]="arduino:avr:mega:cpu=atmega2560" [leonardo]="arduino:avr:leonardo" [due]="arduino:sam:arduino_due_x" [zero]="arduino:samd:arduino_zero_native" [mzero]="arduino:samd:mzero_bl" [mzeropro]="arduino:samd:mzero_pro_bl" [mkrzero]="arduino:samd:mkrzero" [mkr1000]="arduino:samd:mkr1000" [mkrwifi1010]="arduino:samd:mkrwifi1010" [opencr]="OpenCR:OpenCR:OpenCR" [portenta]="arduino-beta:mbed:envie_m7")'
13+
export MAIN_PLATFORMS='declare -A main_platforms=([uno]="arduino:avr:uno" [mega2560]="arduino:avr:mega:cpu=atmega2560" [leonardo]="arduino:avr:leonardo" [due]="arduino:sam:arduino_due_x" [zero]="arduino:samd:arduino_zero_native" [mzero]="arduino:samd:mzero_bl" [mzeropro]="arduino:samd:mzero_pro_bl" [mkrzero]="arduino:samd:mkrzero" [mkr1000]="arduino:samd:mkr1000" [mkrwifi1010]="arduino:samd:mkrwifi1010" [opencr]="OpenCR:OpenCR:OpenCR" [portenta]="arduino:mbed:envie_m7")'
1414

1515
# make display available for arduino CLI
1616
/sbin/start-stop-daemon --start --quiet --pidfile /tmp/custom_xvfb_1.pid --make-pidfile --background --exec /usr/bin/Xvfb -- :1 -ac -screen 0 1280x1024x16
@@ -55,7 +55,7 @@ DEPENDENCY_OUTPUT=$(arduino --install-boards arduino:samd 2>&1)
5555
if [ $? -ne 0 ]; then echo -e "\xe2\x9c\x96"; else echo -e "\xe2\x9c\x93"; fi
5656

5757
echo -n "INSTALL Portenta H7: "
58-
DEPENDENCY_OUTPUT=$(arduino --install-boards arduino-beta:mbed 2>&1)
58+
DEPENDENCY_OUTPUT=$(arduino --install-boards arduino:mbed 2>&1)
5959
if [ $? -ne 0 ]; then echo -e "\xe2\x9c\x96"; else echo -e "\xe2\x9c\x93"; fi
6060

6161
echo -n "INSTALL OpenCR: "

src/Dynamixel2Arduino.cpp

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,8 @@ const uint16_t model_number_table[] PROGMEM = {
3131
MX28_2, MX64_2, MX106_2,
3232

3333
XL320,
34+
XL330_M288,
35+
XL330_M077,
3436
XL430_W250,
3537
XXL430_W250,
3638
XC430_W150, XC430_W240,
@@ -297,6 +299,36 @@ bool Dynamixel2Arduino::setBaudrate(uint8_t id, uint32_t baudrate)
297299
}
298300
break;
299301

302+
case XL330_M288:
303+
case XL330_M077:
304+
switch(baudrate)
305+
{
306+
case 9600:
307+
baud_idx = 0;
308+
break;
309+
case 57600:
310+
baud_idx = 1;
311+
break;
312+
case 115200:
313+
baud_idx = 2;
314+
break;
315+
case 1000000:
316+
baud_idx = 3;
317+
break;
318+
case 2000000:
319+
baud_idx = 4;
320+
break;
321+
case 3000000:
322+
baud_idx = 5;
323+
break;
324+
case 4000000:
325+
baud_idx = 6;
326+
break;
327+
default:
328+
return false;
329+
}
330+
break;
331+
300332
case MX28_2:
301333
case MX64_2:
302334
case MX106_2:
@@ -618,6 +650,8 @@ bool Dynamixel2Arduino::setOperatingMode(uint8_t id, uint8_t mode)
618650

619651
case MX64_2:
620652
case MX106_2:
653+
case XL330_M288:
654+
case XL330_M077:
621655
case XM430_W210:
622656
case XM430_W350:
623657
case XH430_V210:
@@ -1053,6 +1087,7 @@ const ModelDependencyFuncItemAndRangeInfo_t dependency_ctable_2_0_common[] PROGM
10531087
#if (ENABLE_ACTUATOR_MX28_PROTOCOL2 \
10541088
|| ENABLE_ACTUATOR_MX64_PROTOCOL2 \
10551089
|| ENABLE_ACTUATOR_MX106_PROTOCOL2 \
1090+
|| ENABLE_ACTUATOR_XL330 \
10561091
|| ENABLE_ACTUATOR_XC430 \
10571092
|| ENABLE_ACTUATOR_XL430 \
10581093
|| ENABLE_ACTUATOR_XM430 || ENABLE_ACTUATOR_XH430 \
@@ -1085,6 +1120,17 @@ const ModelDependencyFuncItemAndRangeInfo_t dependency_mx106_2[] PROGMEM = {
10851120
{LAST_DUMMY_FUNC, ControlTableItem::LAST_DUMMY_ITEM, UNIT_RAW, 0, 0, 0}
10861121
};
10871122

1123+
const ModelDependencyFuncItemAndRangeInfo_t dependency_xl330_M288_M077[] PROGMEM = {
1124+
#if (ENABLE_ACTUATOR_XL330)
1125+
{SET_CURRENT, GOAL_CURRENT, UNIT_MILLI_AMPERE, -1150, 1150, 1},
1126+
{GET_CURRENT, PRESENT_CURRENT, UNIT_MILLI_AMPERE, -1150, 1150, 1},
1127+
1128+
{SET_VELOCITY, GOAL_VELOCITY, UNIT_RPM, -2047, 2047, 0.229},
1129+
{GET_VELOCITY, PRESENT_VELOCITY, UNIT_RPM, -2047, 2047, 0.229},
1130+
#endif
1131+
{LAST_DUMMY_FUNC, ControlTableItem::LAST_DUMMY_ITEM, UNIT_RAW, 0, 0, 0}
1132+
};
1133+
10881134
const ModelDependencyFuncItemAndRangeInfo_t dependency_xm430_w210_w350[] PROGMEM = {
10891135
#if (ENABLE_ACTUATOR_XM430)
10901136
{SET_CURRENT, GOAL_CURRENT, UNIT_MILLI_AMPERE, -1193, 1193, 2.69},
@@ -1374,6 +1420,12 @@ static ItemAndRangeInfo_t getModelDependencyFuncInfo(uint16_t model_num, uint8_t
13741420
p_dep_ctable = dependency_mx106_2;
13751421
break;
13761422

1423+
case XL330_M288:
1424+
case XL330_M077:
1425+
p_common_ctable = dependency_ctable_2_0_common;
1426+
p_dep_ctable = dependency_xl330_M288_M077;
1427+
break;
1428+
13771429
case XM430_W210:
13781430
case XM430_W350:
13791431
p_common_ctable = dependency_ctable_2_0_common;

src/actuator.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -168,6 +168,7 @@ const ModelControlTableInfo_t control_table_2_0[] PROGMEM = {
168168
#if (ENABLE_ACTUATOR_MX28_PROTOCOL2 \
169169
|| ENABLE_ACTUATOR_MX64_PROTOCOL2 \
170170
|| ENABLE_ACTUATOR_MX106_PROTOCOL2 \
171+
|| ENABLE_ACTUATOR_XL330 \
171172
|| ENABLE_ACTUATOR_XL430 \
172173
|| ENABLE_ACTUATOR_XC430 \
173174
|| ENABLE_ACTUATOR_XM430 || ENABLE_ACTUATOR_XH430 \
@@ -253,8 +254,9 @@ const ModelControlTableInfo_t xc430_xl430_control_table[] PROGMEM = {
253254
{ControlTableItem::LAST_DUMMY_ITEM, 0, 0}
254255
};
255256

256-
const ModelControlTableInfo_t xmh430_control_table[] PROGMEM = {
257-
#if (ENABLE_ACTUATOR_XM430 \
257+
const ModelControlTableInfo_t xmh430_xl330_control_table[] PROGMEM = {
258+
#if (ENABLE_ACTUATOR_XL330 \
259+
|| ENABLE_ACTUATOR_XM430 \
258260
|| ENABLE_ACTUATOR_XH430)
259261
{ControlTableItem::CURRENT_LIMIT, 38, 2},
260262
{ControlTableItem::GOAL_CURRENT, 102, 2},
@@ -475,18 +477,21 @@ ControlTableItemInfo_t DYNAMIXEL::getControlTableItemInfo(uint16_t model_num, ui
475477
case XC430_W240:
476478
case XL430_W250:
477479
case XXL430_W250:
480+
case XXC430_W250:
478481
p_common_ctable = control_table_2_0;
479482
p_dep_ctable = xc430_xl430_control_table;
480483
break;
481484

485+
case XL330_M288:
486+
case XL330_M077:
482487
case XM430_W210:
483488
case XM430_W350:
484489
case XH430_V210:
485490
case XH430_V350:
486491
case XH430_W210:
487492
case XH430_W350:
488493
p_common_ctable = control_table_2_0;
489-
p_dep_ctable = xmh430_control_table;
494+
p_dep_ctable = xmh430_xl330_control_table;
490495
break;
491496

492497
case XM540_W150:

src/actuator.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,13 @@
7272
#define XL320 (uint16_t)350
7373
#endif
7474

75+
#ifndef XL330_M077
76+
#define XL330_M077 (uint16_t)1190
77+
#endif
78+
#ifndef XL330_M288
79+
#define XL330_M288 (uint16_t)1200
80+
#endif
81+
7582
#ifndef XC430_W150
7683
#define XC430_W150 (uint16_t)1070
7784
#endif

src/utility/config.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define ENABLE_ACTUATOR_MX106_PROTOCOL2 1
1717

1818
#define ENABLE_ACTUATOR_XL320 1
19+
#define ENABLE_ACTUATOR_XL330 1
1920
#define ENABLE_ACTUATOR_XL430 1 //Includes 2XL430
2021
#define ENABLE_ACTUATOR_XC430 1 //Includes 2XC430
2122
#define ENABLE_ACTUATOR_XM430 1

src/utility/slave.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ Slave::Slave(const uint16_t model_num, float protocol_ver)
5555
bool
5656
Slave::setPacketBuffer(uint8_t* p_buf, uint16_t buf_capacity)
5757
{
58-
if(p_packet_buf_ == nullptr){
58+
if(p_buf == nullptr){
5959
last_lib_err_ = DXL_LIB_ERROR_NULLPTR;
6060
return false;
6161
}

0 commit comments

Comments
 (0)