From 74215ce11b7389d6ae51550f9a62a51b22cf3f04 Mon Sep 17 00:00:00 2001 From: smkaeser Date: Thu, 14 Jan 2021 14:25:33 +0100 Subject: [PATCH] update from robotis git (#1) * Non-standard baudrates are supported on the latest Mac OS * - added clear instruction & example * fixed bug removeStuffing * - added clear instruction * added clear_multi_turn example * remove python build * - reduced TXPACKET_MAX_LEN & RXPACKET_MAX_LEN (4K -> 1K) because the size of most Dynamixel receive buffers is 1K. - checked whether memory allocation was successful. - marked the crc table as static const - changed addStuffing() function (reduced stack memory usage) - removed busy waiting for rxPacket() - fixed the broadcastping bug in dxl_monitor * - modified "ros" directory C++ code. * added clearmultiturn packet handler * added ros clearMultiTurn API * modified ros clear multi turn * sync opencjr * sync opencm * add macro * updated the CHANGELOG and version to release binary packages * Update bulk_read_write.py fixed typo. * - updated c lib & dll file. * fixed typo. * - fixed "protocol_combined" example bug * - changed C# / win32 / protocol_combined output path. * Updated the CHANGELOG and version to release binary packages Signed-off-by: Pyo * Updated the CHANGELOG and version to release binary packages Signed-off-by: Pyo * Update README.md * - fixed buffer overflow bug (rxpacket size) * Fixed buffer overflow bug (rxpacket size) Signed-off-by: Pyo * Added change log information Signed-off-by: Pyo * Fixed typo in the package.xml and header files Signed-off-by: Pyo * Added imports to __init__.py in ros package. * - packet timeout in broadcastPing() overflow bug fixed. - bug in python removeStuffing() fixed. * - fixed "conflicting types for 'reboot'" error in mac OS. * Fix two potential memory leaks. (#361) - Signed-off-by: Chris Lalancette * - fixed memory leak issue (group sync/bulk series) * - fixed an issue loading the wrong library (in x86) * 3x faster getError member function of GroupSync&BulkRead Class #388 * Update setup.py changed the version of Dynamixel SDK * support noetic * update version info * resolve package name conflict * revise ROS1 version * DynamixelSDK_ros_examples * update comment * Update CMakeLists.txt * - modified setCustomBaudrate() function. (#430) * update changelog * update issue template * update issue template * Update read_write.py - position length bug fixed. Co-authored-by: kizitorashiro Co-authored-by: Pyo Co-authored-by: zerom Co-authored-by: kijonggil Co-authored-by: Darby Lim Co-authored-by: guichristmann Co-authored-by: Will Son Co-authored-by: Ryan Jaehyun Shim <38637417+rjshim@users.noreply.github.com> --- .github/ISSUE_TEMPLATE.md | 70 +--- .travis.yml | 6 +- README.md | 13 +- ReleaseNote.md | 45 ++- .../win32/.vs/clear_multi_turn/v14/.suo | Bin 0 -> 47104 bytes .../win32/clear_multi_turn.sln | 34 ++ .../win32/clear_multi_turn/App.config | 6 + .../win32/clear_multi_turn/ClearMultiTurn.cs | 250 ++++++++++++++ .../Properties/AssemblyInfo.cs | 36 ++ .../clear_multi_turn/clear_multi_turn.csproj | 102 ++++++ .../win32/clear_multi_turn/dynamixel.cs | 262 +++++++++++++++ .../win64/.vs/clear_multi_turn/v14/.suo | Bin 0 -> 46080 bytes .../win64/clear_multi_turn.sln | 28 ++ .../win64/clear_multi_turn/App.config | 6 + .../win64/clear_multi_turn/ClearMultiTurn.cs | 250 ++++++++++++++ .../Properties/AssemblyInfo.cs | 36 ++ .../clear_multi_turn/clear_multi_turn.csproj | 82 +++++ .../win64/clear_multi_turn/dynamixel.cs | 262 +++++++++++++++ .../read_write/win32/.vs/read_write/v14/.suo | Bin 41472 -> 46592 bytes .../win32/protocol_combined/dynamixel.cs | 2 +- .../protocol_combined.csproj | 4 +- .../win64/protocol_combined/dynamixel.cs | 16 +- .../clear_multi_turn/clear_multi_turn.cpp | 314 ++++++++++++++++++ .../clear_multi_turn/linux32/Makefile | 80 +++++ .../clear_multi_turn/linux64/Makefile | 80 +++++ .../clear_multi_turn/linux_sbc/Makefile | 79 +++++ .../protocol2.0/clear_multi_turn/mac/Makefile | 78 +++++ .../win32/.vs/clear_multi_turn/v14/.suo | Bin 0 -> 22016 bytes .../win32/clear_multi_turn.sln | 28 ++ .../clear_multi_turn/clear_multi_turn.vcxproj | 154 +++++++++ .../clear_multi_turn.vcxproj.filters | 22 ++ .../clear_multi_turn.vcxproj.user | 7 + .../win64/.vs/clear_multi_turn/v14/.suo | Bin 0 -> 24064 bytes .../win64/clear_multi_turn.sln | 28 ++ .../clear_multi_turn/clear_multi_turn.vcxproj | 156 +++++++++ .../clear_multi_turn.vcxproj.filters | 22 ++ .../clear_multi_turn.vcxproj.user | 7 + c++/include/dynamixel_sdk/packet_handler.h | 23 +- .../dynamixel_sdk/protocol1_packet_handler.h | 13 +- .../dynamixel_sdk/protocol2_packet_handler.h | 17 +- c++/src/dynamixel_sdk/group_bulk_read.cpp | 11 +- c++/src/dynamixel_sdk/group_sync_read.cpp | 11 +- .../dynamixel_sdk/port_handler_arduino.cpp | 22 +- c++/src/dynamixel_sdk/port_handler_linux.cpp | 34 ++ .../protocol1_packet_handler.cpp | 32 ++ .../protocol2_packet_handler.cpp | 163 ++++++--- c/build/win32/output/dxl_x86_c.dll | Bin 45568 -> 46592 bytes c/build/win32/output/dxl_x86_c.lib | Bin 41430 -> 40738 bytes c/build/win64/output/dxl_x64_c.dll | Bin 52736 -> 53248 bytes c/build/win64/output/dxl_x64_c.lib | Bin 40458 -> 39780 bytes c/example/dxl_monitor/dxl_monitor.c | 2 +- .../clear_multi_turn/clear_multi_turn.c | 311 +++++++++++++++++ .../clear_multi_turn/linux32/Makefile | 80 +++++ .../clear_multi_turn/linux64/Makefile | 80 +++++ .../clear_multi_turn/linux_sbc/Makefile | 79 +++++ .../protocol2.0/clear_multi_turn/mac/Makefile | 78 +++++ .../win32/.vs/clear_multi_turn/v14/.suo | Bin 0 -> 27136 bytes .../win32/clear_multi_turn.sln | 28 ++ .../clear_multi_turn/clear_multi_turn.vcxproj | 154 +++++++++ .../clear_multi_turn.vcxproj.filters | 22 ++ .../clear_multi_turn.vcxproj.user | 7 + .../win64/.vs/clear_multi_turn/v14/.suo | Bin 0 -> 24576 bytes .../win64/clear_multi_turn.sln | 28 ++ .../clear_multi_turn/clear_multi_turn.vcxproj | 156 +++++++++ .../clear_multi_turn.vcxproj.filters | 22 ++ .../clear_multi_turn.vcxproj.user | 7 + c/include/dynamixel_sdk/packet_handler.h | 12 + .../dynamixel_sdk/protocol1_packet_handler.h | 1 + .../dynamixel_sdk/protocol2_packet_handler.h | 1 + c/src/dynamixel_sdk/group_bulk_read.c | 10 + c/src/dynamixel_sdk/group_bulk_write.c | 10 + c/src/dynamixel_sdk/group_sync_read.c | 10 + c/src/dynamixel_sdk/group_sync_write.c | 10 + c/src/dynamixel_sdk/packet_handler.c | 16 + c/src/dynamixel_sdk/port_handler_linux.c | 34 ++ .../dynamixel_sdk/protocol1_packet_handler.c | 5 + .../dynamixel_sdk/protocol2_packet_handler.c | 273 ++++++++++++--- .../x64/Dynamixel.java | 7 + .../x86/Dynamixel.java | 7 + .../clear_multi_turn/ClearMultiTurn.java | 261 +++++++++++++++ labview/protocol2.0/clear_multi_turn.vi | Bin 0 -> 54652 bytes .../packet_handler/clearMultiTurn.m | 36 ++ matlab/protocol2.0/clear_multi_turn.m | 305 +++++++++++++++++ .../__init__.py => python/CATKIN_IGNORE | 0 python/setup.py | 2 +- python/src/dynamixel_sdk/port_handler.py | 14 +- .../dynamixel_sdk/protocol2_packet_handler.py | 32 +- python/src/dynamixel_sdk/robotis_def.py | 1 + python/tests/protocol1_0/read_write.py | 4 +- python/tests/protocol2_0/bulk_read_write.py | 2 +- python/tests/protocol2_0/clear_multi_turn.py | 215 ++++++++++++ ros/{ => dynamixel_sdk}/CHANGELOG.rst | 48 ++- ros/{ => dynamixel_sdk}/CMakeLists.txt | 3 + .../include/dynamixel_sdk/dynamixel_sdk.h | 0 .../include/dynamixel_sdk/group_bulk_read.h | 0 .../include/dynamixel_sdk/group_bulk_write.h | 0 .../include/dynamixel_sdk/group_sync_read.h | 0 .../include/dynamixel_sdk/group_sync_write.h | 0 .../include/dynamixel_sdk/packet_handler.h | 23 +- .../include/dynamixel_sdk/port_handler.h | 0 .../dynamixel_sdk/port_handler_arduino.h | 0 .../dynamixel_sdk/port_handler_linux.h | 0 .../include/dynamixel_sdk/port_handler_mac.h | 0 .../dynamixel_sdk/port_handler_windows.h | 0 .../dynamixel_sdk/protocol1_packet_handler.h | 13 +- .../dynamixel_sdk/protocol2_packet_handler.h | 17 +- ros/{ => dynamixel_sdk}/package.xml | 9 +- ros/{ => dynamixel_sdk}/setup.py | 0 ros/{ => dynamixel_sdk}/src/DynamixelSDK.h | 0 .../src/dynamixel_sdk/__init__.py | 27 ++ .../src/dynamixel_sdk/group_bulk_read.cpp | 11 +- .../src/dynamixel_sdk/group_bulk_read.py | 0 .../src/dynamixel_sdk/group_bulk_write.cpp | 0 .../src/dynamixel_sdk/group_bulk_write.py | 0 .../src/dynamixel_sdk/group_sync_read.cpp | 11 +- .../src/dynamixel_sdk/group_sync_read.py | 0 .../src/dynamixel_sdk/group_sync_write.cpp | 0 .../src/dynamixel_sdk/group_sync_write.py | 0 .../src/dynamixel_sdk/packet_handler.cpp | 0 .../src/dynamixel_sdk/packet_handler.py | 0 .../src/dynamixel_sdk/port_handler.cpp | 0 .../src/dynamixel_sdk/port_handler.py | 0 .../dynamixel_sdk/port_handler_arduino.cpp | 22 +- .../src/dynamixel_sdk/port_handler_linux.cpp | 34 ++ .../src/dynamixel_sdk/port_handler_mac.cpp | 0 .../dynamixel_sdk/port_handler_windows.cpp | 0 .../protocol1_packet_handler.cpp | 32 ++ .../dynamixel_sdk/protocol1_packet_handler.py | 0 .../protocol2_packet_handler.cpp | 163 ++++++--- .../dynamixel_sdk/protocol2_packet_handler.py | 32 +- .../src/dynamixel_sdk/robotis_def.py | 3 +- ros/dynamixel_sdk_examples/CHANGELOG.rst | 9 + ros/dynamixel_sdk_examples/CMakeLists.txt | 73 ++++ .../msg/SetPosition.msg | 2 + ros/dynamixel_sdk_examples/package.xml | 24 ++ .../src/read_write_node.cpp | 126 +++++++ .../srv/GetPosition.srv | 3 + 137 files changed, 5578 insertions(+), 320 deletions(-) create mode 100644 c#/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo create mode 100644 c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn.sln create mode 100644 c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/App.config create mode 100644 c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/ClearMultiTurn.cs create mode 100644 c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/Properties/AssemblyInfo.cs create mode 100644 c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.csproj create mode 100644 c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/dynamixel.cs create mode 100644 c#/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo create mode 100644 c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln create mode 100644 c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/App.config create mode 100644 c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/ClearMultiTurn.cs create mode 100644 c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/Properties/AssemblyInfo.cs create mode 100644 c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.csproj create mode 100644 c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/dynamixel.cs create mode 100644 c++/example/protocol2.0/clear_multi_turn/clear_multi_turn.cpp create mode 100644 c++/example/protocol2.0/clear_multi_turn/linux32/Makefile create mode 100644 c++/example/protocol2.0/clear_multi_turn/linux64/Makefile create mode 100644 c++/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile create mode 100644 c++/example/protocol2.0/clear_multi_turn/mac/Makefile create mode 100644 c++/example/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo create mode 100644 c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn.sln create mode 100644 c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj create mode 100644 c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters create mode 100644 c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user create mode 100644 c++/example/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo create mode 100644 c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln create mode 100644 c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj create mode 100644 c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters create mode 100644 c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user mode change 100644 => 100755 c/example/dxl_monitor/dxl_monitor.c create mode 100644 c/example/protocol2.0/clear_multi_turn/clear_multi_turn.c create mode 100644 c/example/protocol2.0/clear_multi_turn/linux32/Makefile create mode 100644 c/example/protocol2.0/clear_multi_turn/linux64/Makefile create mode 100644 c/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile create mode 100644 c/example/protocol2.0/clear_multi_turn/mac/Makefile create mode 100644 c/example/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo create mode 100644 c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn.sln create mode 100644 c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj create mode 100644 c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters create mode 100644 c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user create mode 100644 c/example/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo create mode 100644 c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln create mode 100644 c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj create mode 100644 c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters create mode 100644 c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user create mode 100644 java/protocol2.0/clear_multi_turn/ClearMultiTurn.java create mode 100644 labview/protocol2.0/clear_multi_turn.vi create mode 100644 matlab/m_basic_function/packet_handler/clearMultiTurn.m create mode 100644 matlab/protocol2.0/clear_multi_turn.m rename ros/src/dynamixel_sdk/__init__.py => python/CATKIN_IGNORE (100%) create mode 100644 python/tests/protocol2_0/clear_multi_turn.py rename ros/{ => dynamixel_sdk}/CHANGELOG.rst (81%) rename ros/{ => dynamixel_sdk}/CMakeLists.txt (97%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/dynamixel_sdk.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/group_bulk_read.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/group_bulk_write.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/group_sync_read.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/group_sync_write.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/packet_handler.h (96%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/port_handler.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/port_handler_arduino.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/port_handler_linux.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/port_handler_mac.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/port_handler_windows.h (100%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/protocol1_packet_handler.h (98%) rename ros/{ => dynamixel_sdk}/include/dynamixel_sdk/protocol2_packet_handler.h (97%) rename ros/{ => dynamixel_sdk}/package.xml (57%) rename ros/{ => dynamixel_sdk}/setup.py (100%) rename ros/{ => dynamixel_sdk}/src/DynamixelSDK.h (100%) create mode 100644 ros/dynamixel_sdk/src/dynamixel_sdk/__init__.py rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_bulk_read.cpp (98%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_bulk_read.py (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_bulk_write.cpp (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_bulk_write.py (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_sync_read.cpp (97%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_sync_read.py (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_sync_write.cpp (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/group_sync_write.py (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/packet_handler.cpp (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/packet_handler.py (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/port_handler.cpp (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/port_handler.py (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/port_handler_arduino.cpp (92%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/port_handler_linux.cpp (89%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/port_handler_mac.cpp (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/port_handler_windows.cpp (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/protocol1_packet_handler.cpp (97%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/protocol1_packet_handler.py (100%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/protocol2_packet_handler.cpp (90%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/protocol2_packet_handler.py (97%) rename ros/{ => dynamixel_sdk}/src/dynamixel_sdk/robotis_def.py (97%) create mode 100644 ros/dynamixel_sdk_examples/CHANGELOG.rst create mode 100644 ros/dynamixel_sdk_examples/CMakeLists.txt create mode 100644 ros/dynamixel_sdk_examples/msg/SetPosition.msg create mode 100644 ros/dynamixel_sdk_examples/package.xml create mode 100644 ros/dynamixel_sdk_examples/src/read_write_node.cpp create mode 100644 ros/dynamixel_sdk_examples/srv/GetPosition.srv diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index 34d43d6a..154e2b61 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -1,64 +1,24 @@ -ISSUE TEMPLATE ver. 1.1.1 +ISSUE TEMPLATE ver. 1.2.0 +Please fill this template for more accurate and prompt support. +1. Which DYNAMIXEL SDK version do you use? + - ex) `3.4.1` +2. Which programming language/tool do you use? + - ex) `C`, `C++`, `C#`, `Python`, `Java`, `MATLAB`, `LABVIEW`, `ROS`, `Arduino`, etc +3. Which operating system do you use? + - ex) `Ubuntu 16.04`, `Windows 10`, `OS X 10.14` +3. Which USB serial converter do you use? + - ex) `USB2Dynamixel`, `U2D2`, `OpenCM904`, `OpenCR`, etc +4. Which DYNAMIXEL do you use? + - ex) `MX-28(2.0)`, `AX-12W`, `XM430-W250`, etc. +5. Have you searched the issue from the closed issue threads? -BE CAREFUL!! FOLLOW THE RULES AS FOLLOWS, OR YOUR ISSUE WILL BE `WON'T FIX` ANYWAY +6. Please describe the issue in detail - - - - - - - - -STEP 1. Check what you are suffering from : - -- I'm using `DynamixelSDK ver. 3.5.4` - - - [3.4.1], [3.5.2], etc. - -- I'm using `C++` Language - - - [C] / [C++] / [C#] / [Python] / [Java] / [MATLAB] / [LABVIEW] / [ROS] / [Arduino] - -- I'm using `USB2Dynamixel2` serial converter - - - [USB2Dynamixel] / [USB2Dynamixel2] or [OpenCM904] / [OpenCR] / [CM700s] / [CM500s] or other ROBOTIS product only - -- I'm using `XM430-W210-R` - - - [MX-28], [AX-12W], [H54-200W], etc. - -- and I'm having an `issue` like what - - - 'My motor doesn't work', etc. - - -STEP 2. Write `Title` as `[3.5.4][C++][USB2Dynamixel2][XM430-W210-R] Issue : My motor doesn't work` - -- Now, if you think : - - - Hey, I'm using RoboPlus2.0, and having an issue, but how can I write that kind of `Title`? - - - Hey, I'm using USB2AX serial converter, and having an issue, but how can I write that kind of `Title`? - - - or more that is not listed on above. - -- , You should write your `issue` on http://en.robotis.com/BlueAD/board.php?bbs_id=old_qna - - -STEP 3. Delete all written here, and describe what your problem is - -- Any PICTURES or VIDEOS? - - ![]( Link the PICTURES or VIDEOS here, if necessary ) - -- Any SOURCE SAMPLES? - - []( Link the SOURCE SAMPLES here, if necessary ) +7. How can we reproduce the issue? diff --git a/.travis.yml b/.travis.yml index 69f8dc9c..4fadd455 100644 --- a/.travis.yml +++ b/.travis.yml @@ -15,16 +15,16 @@ notifications: on_success: change on_failure: always recipients: - - pyo@robotis.com + - willson@robotis.com env: matrix: - ROS_DISTRO=indigo ROS_REPO=ros UPSTREAM_WORKSPACE=debian OS_NAME=ubuntu OS_CODE_NAME=trusty - ROS_DISTRO=kinetic ROS_REPO=ros UPSTREAM_WORKSPACE=debian OS_NAME=ubuntu OS_CODE_NAME=xenial - ROS_DISTRO=melodic ROS_REPO=ros UPSTREAM_WORKSPACE=debian OS_NAME=ubuntu OS_CODE_NAME=bionic - ROS_DISTRO=melodic ROS_REPO=ros UPSTREAM_WORKSPACE=debian OS_NAME=debian OS_CODE_NAME=stretch + - ROS_DISTRO=noetic ROS_REPO=ros UPSTREAM_WORKSPACE=debian OS_NAME=ubuntu OS_CODE_NAME=focal matrix: allow_failures: - - env: ROS_DISTRO=melodic ROS_REPO=ros UPSTREAM_WORKSPACE=debian OS_NAME=ubuntu OS_CODE_NAME=bionic - env: ROS_DISTRO=melodic ROS_REPO=ros UPSTREAM_WORKSPACE=debian OS_NAME=debian OS_CODE_NAME=stretch branches: only: @@ -33,8 +33,8 @@ branches: - indigo-devel - kinetic-devel - melodic-devel + - noetic-devel install: - git clone https://github.com/ros-industrial/industrial_ci.git .ci_config script: - source .ci_config/travis.sh - diff --git a/README.md b/README.md index b7f98234..7dac9751 100644 --- a/README.md +++ b/README.md @@ -12,10 +12,15 @@ DynamixelSDK supports various programming languages. - **Python**: Python module and examples (* Dynamic library (*.dll, *.so, and *.dylib files) / .dll: dynamic-link library on Windows / .so: shared object on Linux / .dylib: dynamic library on MacOS) -## ROS Packages for Dynamixel SDK -|Version|Indigo + Ubuntu Trusty|Kinetic + Ubuntu Xenial|Melodic + Ubuntu Bionic| -|:---:|:---:|:---:|:---:| -|[![GitHub version](https://badge.fury.io/gh/ROBOTIS-GIT%2FDynamixelSDK.svg)](https://badge.fury.io/gh/ROBOTIS-GIT%2FDynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=indigo-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=kinetic-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=melodic-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)| +## ROS 1 Packages for Dynamixel SDK +|develop|master|Indigo + Ubuntu Trusty|Kinetic + Ubuntu Xenial|Melodic + Ubuntu Bionic|Noetic + Ubuntu Focal| +|:---:|:---:|:---:|:---:|:---:|:---:| +|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=develop)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=master)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=indigo-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=kinetic-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=melodic-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=noetic-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)| + +## ROS 2 Packages for Dynamixel SDK +|ros2-devel|ros2|Dashing + Ubuntu Bionic|Eloquent + Ubuntu Bionic|Foxy + Ubuntu Foxy| +|:---:|:---:|:---:|:---:|:---:| +|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=ros2-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=ros2)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=dashing-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=eloquent-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK.svg?branch=foxy-devel)](https://travis-ci.org/ROBOTIS-GIT/DynamixelSDK)| For more information on ROS Packages for Dynamixel SDK, please refer to the ROS wiki pages below. - http://wiki.ros.org/dynamixel_sdk diff --git a/ReleaseNote.md b/ReleaseNote.md index c1bb7dfb..93db749a 100644 --- a/ReleaseNote.md +++ b/ReleaseNote.md @@ -1,17 +1,48 @@ # Dynamixel SDK Release Notes +3.7.41(2020-08-12) +------------------- +* DYNAMIXEL SDK ROS example initial commit. +* Bug fix for 4.5Mbps support (#430) +* Contributors: Zerom, Will Son + +3.7.31 (2020-07-13) +------------------- +* ROS 1 Noetic Ninjemys support +* 3x faster getError member function of GroupSyncRead Class +* Contributors: developer0hye, Zerom, Will Son + +3.7.21 (2019-09-06) +------------------- +* Fixed buffer overflow bug (rxpacket size) +* Fixed typo in the package.xml and header files + +3.7.11 (2019-08-19) +------------------- +* Updated C lib and DLL file +* Changed C# / win32 / protocol_combined output path +* Fixed "protocol_combined" example bug +* Fixed typo in bulk_read_write.py + +3.7.0 (2019-01-03) +------------------ +* Added clear instruction [#269](https://github.com/ROBOTIS-GIT/DynamixelSDK/issues/269) +* Removed busy waiting for rxPacket() +* Fixed addStuffing() function (reduced stack memory usage) +* Fixed memory issues [#268](https://github.com/ROBOTIS-GIT/DynamixelSDK/issues/268) +* Fixed the broadcast ping bug in dxl_monitor + 3.6.2 (2018-07-17) ------------------ -* added python modules for ROS to ros folder -* moved cpp library files for ROS to ros folder -* created an ROS package separately `#187 `_ -* modified the e-Manual address to emanual.robotis.com +* Added python modules for ROS to ros folder +* Moved cpp library files for ROS to ros folder +* Created an ROS package separately `#187 `_ +* Modified the e-Manual address to emanual.robotis.com 3.6.1 (2018-06-14) ------------------ -* removed printTxRxResult(), printRxPacketError() `#193 `_ -* removed cache files -* merge pull request `#195 `_ +* Removed printTxRxResult(), printRxPacketError() `#193 `_ +* Removed cache files 3.6.0 (2018-03-16) ------------------ diff --git a/c#/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo b/c#/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo new file mode 100644 index 0000000000000000000000000000000000000000..6955f04aacaf2396ca52140a0304f8b849e3a399 GIT binary patch literal 47104 zcmeHQZ*UvObw65GEXj@&MXu^Nj)Yo@k_CdK#E7(LgQAog4g~^73L*$F z04Rx;l&Ddf%5fbhs#~RLQpc^*rk11H@k~4E)E|;*zoeeA>Z4(~Fr=HYt+qC0E zO=I=<+r1?YhXd|FQXoNLG4KBF?Vq=A-@f2ADS3t&0Q#WO$e#?1+%Bkk3ukxNQTqW*+&Q_kIZ zk~M#5bIttOM->iiqLe&(5>LLiQa)yz{X%_=GyAd%tMTsrfHeRcdrZ~T3T;GKA2aM}Gao!EM%edc!^JYN6xHqTk_WJ%Rzuk%WUB)+IoY^itfL_2Z z0PEX_^Tz>u0R4agzypB2fI+~6fQJAPzz|>iKil&|0JcGyXhn}larZOh ziBta62Py^T??Hsy0B-XiL);Fd{gwQw1LJvtakj!ZG%>b_bMPSlb%;iCcANic#HHNC zP@Mk|@|+elpyc7KHYxPbBs9~s{G{mUn`irXA>E8NA#%y$>{jnpg}4*>Z^q4C0Jru3 zBI4d-Brt^9<&bZ`LHiNykkG;NXb)<}IU`=V(_H%h6G)8mF2gW#7!o*0X`?tF0|wag zM^GO2L8ovR+MhbH((jz&^ZjQ4>@y7HakMgI(Yi6%0eX>d3imk+WrR^S+GlieEMR3T z^8X;xQF^sV)Zt+6{|)|M-u}Y2al!w^_(L7gE&VSg{yzYUniM^5X0{(haGw&rPja2T z7@_i@OHyEg@+6T3=fHpXrNMr|ad*RhLhdUmn`0g=Z|ns*^v)#ikIJlUkN1H7e+6%D z2e`%mDa7>v7?^(qIV6FF6!InC-;cYrmOy=v;;oLmad0Jj3CWB6KZ10aH-kvj;qYsC zulSGC_}A)?)?DO|KSG*2j0T7T^W--%aG(+3U>bL9>k%BM1y_m+?4)6t^J{KmCtyJ) zFPlUv$B=SL^CFL&HhuiD^&fiq%ws=KzVP&#?tguW6_Yr-di4^9&%-M_Zo(a5#0ASYnmVT>N`!l_41RSPrdQh3t#=e59gxqJ$lFiUE*~H zM}_~z;Qt)Q7m)u8Y-~iDZt2g=|J}5xGlfVgW*qdwc9-of`}qH8VQnkuW*;a(%D7RC z_7kx9lbej=O*gJM)=%O+N4T7zGTPoJL_Zt>{qb3M30+0-Y>$Y&3CAhq&Y29RM*ihT zIeg;n!qRtmw!aL__Ld=|uc(^Sa^^0)(X_bu`El!i`_F#oiT*#o@%6Slf3)J_T1#-k zsHo*Paywsq`@*@?SAvgIj&Va%ielchssCQIcOI#@p^U8;Kj44r{QvIy*57=|f5X3z zT%;^kO_*=~wV=#4NFi=;>P(p{?s@k=Zg_3)o3Fmyk!XHnEhaXc#-BC^WX@&$xqvip zH^v`_U}ExEpyQSXsa7C5}>{}3h8Ma zKgx$)0BR!>kmoW&{-Z=_E{V!no}qsV{Tm8`Yx-Y@xJv%F<}Y)i{2@I-LMX=+X8kFx zCXJ`&611WIoFk8jc6CWfo_KiCLv`^CKhy8@U zLDW}00Ma6D$D06~0Z{n0y8)yp_G#Ky?gh}k#xV{C0O)m^_ECTj!1)Qz5d{FW)zMx; znYA6z0q6v51#AO+44}$+KdyJ0?$z@iJnIGQ0_+C#0U#z9`TsEPUOeOZL7X1~L;&Pz z`vAj${eT02PXOru^DrO^cm(iCzzEd z?L%*)*If*?*8#=zA*@y90Q-B@{I8n)$&V@p_Wv6Yfi#V3&DN{ZH`U}%{=hjv(zac| z_$$Ug_K~^d-)R5J^j8P%KQH><4GxnKeJ>3jmO^jr6=M#2BWI+Y!hHK*7kYjiT#&Xy zj<_6q`wf23jdz?2s1!KX!b)h|6(OR# z{I8S!PxTYoTBS$Mzc=AA|NGm>)3KVZZwcVhk?yd*ul&3_DW7tsGh%;l`8 zBLCBfyB5GuEbr9b|HEoyH*4C1;DPjpDL41a^27h6i8=yhe7E?YMBI!q0ahu0HD^?5 z93cOt>_eT}ZT@EY%bx#_q1NL<|KkW$&i4jcLMM^@pZbv7{09;D3r79-LdQD{`vS*5 zHTI}^uwkLWFqiUy{wEwusF%6T{{h6Mj$#h%!?Tm}<`*un=lcCErfhpK8uS7WoI~WS zKP@m5!0@mki^z7^4tY2T9k5jtw`ZVts0%>7(uu>@kjO2R<{x}udY7K} z4rMZ_+!oKUp3NmQ>Foh;5Wkjyzh#RjJe|rceQ#1vC02a-hR94VuTOfznN&)T=aEXzyGu{&*<{??ofHpZ*_ng>haWZ~ zM)FyFy~Q(`i)XT_1KkWr>>5sh9ApauE-T>04 z=YX^XdchlMi=jtG!bBG(`HOs+Hv^J(3~XW29fP#*as5>sIjg=-?>p%SNWYKb9OZZF z2>Vyn`LmtLuNWf8H*Smq^f{Aqx3@$t_0CGg znl%8o_~%$X1Yoe{Z*PAzk4o}8b)@}w6K*I^y3Kzb;;u3hu;xDp`)?C%T(oVu&7W<5 zyOF=U{->k_Tl=r*e;cdF--EcHGYVjCZ{-JR9TO{QK@I<}`T2htWH7H2=}v`e6SC63 zeg7+;D((Nb;&nCo??C*&G?KLD-?0Cy`G?xr|5eL!Olrt~z`=DU|8<2UgH|7^Ll_%A z-W3U-0y-AgJI#&P(@`NMy7f+t!>U)w+f{n-O$lq{VQt;%zy7Q5p1Le796*K$oK0Ci zSg~vWVWa&yS5#WlYP|Dm;T>1Imgk(>^1+9sap|wA=v}UY@`@QbTIId4P2`|&aK=#v z&`X%Q6Mgn&PoiJ%3CxmpVBU2w9PU>!&1Xv6Q_yWVpUwG}88OE^gj7PnDCbfZ!nx-u8q_ECI0V)dAY;=@|GpRCAHlckoBWx{EqpVR&9h`ZM z*GQK+$oevUbAC#z;&X;>fTS3+2E$%4AT&ly6-Yg6p<9BuS_tF03go`LNG_DMx7Y;2l+!tmS zp2&4^)Rd)GE>|m!pbgv6mhC84FOC7s)BAAM0Sq+5TGNHncHycER+~1&ZN?jZ;lmTI zZ|nk=S`jyZ`f;rQOG%G`LBWTokXIHtaxDmP7s8QLNB;=Y618>i9aH$0+GS}^E%pnO zn!mCwMumP&8$b#m*TPt~X*m3Z=ak?a>O12Y}%i@J&3k zJ#<|2Du`n{eryGvM{zZVvmd_}&{Paxa!xRYyFw|cwK{tkv*l=uEVl~eTG1c-L>tOS zT51K*dn$ zzEJg_}TZtxLM4*4Sc9KG1mNK4l|7HUvbT*?9Ld%ofer4*>RLM!r(pdYZGvsZXg z7xvH?t`eZZGa$%W@Z^BEJ|^RH{c zj~A9dkvBa!%bV0Z8OKH?oiFdvZDFO2>xbL-_l?d{O?{1M2QaR2C8^VR*560(N-6u* zR}GzOcCc=0HVIiIE;I+utc|*AH+rttW4je(Ep^2mB=XR2q-T$uNu=IOncumU>s99D zyd~(=%5`=!{0oJ+yLIS19K!c<%D_67AGC}_s4{Q|Nxre)CQ2V2{ zM+-?@=$mpc8ES;wQK~pDbyV7msF_MmrR-6(7jXxONukA(e^25^J(hN+#O!zEW89~R zY0wUn7xtRvN9Xj>D{ZObKGB3Y=1|X811kroowwMopkmn7`g$6_x!R)`GivNF*j~y@ z0e0A{*HOPvZzSL^zh)y-63SHpT856ek9^ffitnbt{;00o)I4hzde>*N~9 z;<`(z!LG*j+V17#pwf1?#$RO#ul4%8 zJ{R81?d`GFcxzirXCSEiIyxWO^04%f9)xRhY+N6RrE#3p(|PZ{KJUJqo>l(KTRi0> z795eQ@vIKCjE)65TH9iYKwD4`v_A3(CxBP4z~M$77T7_0IUtB=xykTiUlqq$flhwnqoUS!B z-HbdOzvp*W|0B`Q@V(M`hM|Q%!gNv}+wSJYMK4hj9zXP0 zB!12=dTBUImWID&MtC&R9=jAMi2g+MhFc04Is)n;6=hK(&M2}}Pc3@8u~f8#b2T1q z=afqqqrcJipF;j)C{KYas{5r=B3aI*fFr9mfo3y8>70v{m5Xt#zE`@Dy$Dfc&~{_-qfuHUDzlTDO*N-tU zEwPEOO7vagvE{%Olg)q*;H-;!-Wq!a5}(<9Z&?6BFDlygkY$tRvAjf|Dz1x*C_fM> z$;$koDK0j@o)*(&+)gKoN|UY9b=%#x*QJiMIea@Ih^Us^Ub9W!Tt@XNG<9Lqd$r}g z7acSwwsK>wcXRcD`A1)B`Kx@TVyQFI(%$+0hW_(kPh32=;XgY2wM%~y(Kg@wi_m>f zd~f#)|M2W9>%O`FJ$(9K2hQB}-Ja*R{(bx_KRw2+4G#E!RDt6!YvyQ8&(Ct9<2pV{@swyGC&w#XqF?GUKii`v#ipHs7*sL#oBt zns16;F|%H}ZpMp|n>%6gUvCcKDupg?uK%_LFGpeBty;U|REGPnX&FM0p=LA>c={kZ zo>N(B(JmaXoXT;n+r>>8LJQt5v=NzUv{Kv9Cc5L(AHDa$KfitE;Ll(BJKR+ zl22ifuwNZuwe-q?U^f!{Du)rQ--eNzY2%a_!DGDFJG^#6&c{DLR$S<0(Cs9ht<2Kgkj7`IC+wO{Uv|#$(Qlaz7D6g49Gb#`4BwT0V*!B9uD zuO}F44)%uInman$Le0LmpuZ#FYvph(LR0rvAAZNNxlmWAClG251v`Vy!S-HUb%eW` zJADDa&)?J4+8gRQd7@CH1Fx{Y+((ux{Jhvd(q{2LK-%*U=?7Z+?@TMvrvCyS zYyFQWwGOGW^`q9-3+M5?+!!YR;q$FJsHwEGIM*~RWW36&N=xUjioIW*yrk>dL&oag z=P0DJMDF6MQ}4Ucg1 zt|JOJY7L#W-OUn`yf!?-;f>0;R{v2q{-2~Pw|<#!+w%k6Q~@c*@rzYYIiMJolFMB;?AK@I=ka@cA3|C)D|u)|&hW{_^Uk(3XwbO(2cWwCpCb9P^eaIy~mb3pa|Hqd8zfIat=jy_1coi3X zdgTK+5W@@k@QL`==rlIe$wen74rkKiwqCr6nRIM2c}!2abYBkml~*&ZM1}P~Lzwg8 zKf=g%lNR%O@Og9lA3)OQt#X~YqVuwiKDKl`8VllTHLDV&N}{24%_~L=UhRVZs&!v) zYY(2J!b5F`A-S_YyTO8>q5Hb6``R$qNDL5*LvroIOn7UQ`+&`|t!|se2i=NoMY{L6 zS#?ohTZQ&oLOE}V>HhXu+o-Qu4+LAAvBIOHxw9=X*4(Pc#sZx|T@SQ%dVM}$d!XZl z>@S7m?OGFLDY0Re@$d@H>{oQ4;tZ|`X|eEEuFlG$Co@=ADO=|s6*rfiw7CD5u1w+r zW$97rW*(1An!B-bk2?-eV#SRd_ak_=r{+tPow@tY_rG+(H@Wl4M_>KkJ0HBF?;-Zo ziY#@mG&+=iuh!qZ`1XZ!r>_Jbzk1cWW3#>GSj|7U^}jFPpQ_-m$~6@Y|9dW|Un&;T o>iq93QJa*%eq + + + + + diff --git a/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/ClearMultiTurn.cs b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/ClearMultiTurn.cs new file mode 100644 index 00000000..37e57f3d --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/ClearMultiTurn.cs @@ -0,0 +1,250 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Ki Jong Gil (Gilbert) */ + +// +// ********* Clear Multi-Turn Example ********* +// +// +// Available Dynamixel model on this example : Dynamixel X-series (firmware v42 or above) +// This example is designed for using a Dynamixel XM430-W350-R, and an U2D2. +// To use another Dynamixel model, such as MX series, see their details in E-Manual(emanual.robotis.com) and edit below "#define"d variables yourself. +// Be sure that Dynamixel properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +// + +using System; +using System.Runtime.InteropServices; +using dynamixel_sdk; + +namespace clear_multi_turn +{ + class ClearMultiTurn + { + // Control table address + public const int ADDR_OPERATING_MODE = 11; // Control table address is different in Dynamixel model + public const int ADDR_TORQUE_ENABLE = 64; + public const int ADDR_GOAL_POSITION = 116; + public const int ADDR_PRESENT_POSITION = 132; + + // Protocol version + public const int PROTOCOL_VERSION = 2; // See which protocol version is used in the Dynamixel + + // Default setting + public const int DXL_ID = 1; // Dynamixel ID: 1 + public const int BAUDRATE = 57600; + public const string DEVICENAME = "COM1"; // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + + public const int TORQUE_ENABLE = 1; // Value for enabling the torque + public const int TORQUE_DISABLE = 0; // Value for disabling the torque + public const int MAX_POSITION_VALUE = 1048575; // + public const int DXL_MOVING_STATUS_THRESHOLD = 20; // Dynamixel moving status threshold + public const int EXT_POSITION_CONTROL_MODE = 4; // Value for extended position control mode (operating mode) + + public const byte ESC_ASCII_VALUE = 0x1b; + public const byte SPACE_ASCII_VALUE = 0x20; + + public const int COMM_SUCCESS = 0; // Communication Success result value + public const int COMM_TX_FAIL = -1001; // Communication Tx Failed + + static void Main(string[] args) + { + int port_num = dynamixel.portHandler(DEVICENAME); + + // Initialize PacketHandler Structs + dynamixel.packetHandler(); + + int index = 0; + int dxl_comm_result = COMM_TX_FAIL; // Communication result + + byte dxl_error = 0; // Dynamixel error + Int32 dxl_present_position = 0; // Present position + + // Open port + if (dynamixel.openPort(port_num)) + { + Console.WriteLine("Succeeded to open the port!"); + } + else + { + Console.WriteLine("Failed to open the port!"); + Console.WriteLine("Press any key to terminate..."); + Console.ReadKey(); + return; + } + + // Set port baudrate + if (dynamixel.setBaudRate(port_num, BAUDRATE)) + { + Console.WriteLine("Succeeded to change the baudrate!"); + } + else + { + Console.WriteLine("Failed to change the baudrate!"); + Console.WriteLine("Press any key to terminate..."); + Console.ReadKey(); + return; + } + + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_OPERATING_MODE, EXT_POSITION_CONTROL_MODE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + else + { + Console.WriteLine("Operating mode changed to extended position control mode."); + } + + // Enable Dynamixel Torque + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + else + { + Console.WriteLine("Dynamixel has been successfully connected"); + } + + while (true) + { + Console.WriteLine("Press any key to continue! (or press ESC to quit!)"); + if (Console.ReadKey(true).KeyChar == ESC_ASCII_VALUE) + break; + + Console.WriteLine(" Press SPACE key to clear multi-turn information! (or press ESC to stop!)"); + + // Write goal position + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, MAX_POSITION_VALUE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + do + { + // Read present position + dxl_present_position = (Int32)dynamixel.read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + Console.Write(string.Format(" [ID: {0}] GoalPos: {1} PresPos: {2}", DXL_ID, MAX_POSITION_VALUE, dxl_present_position, Environment.NewLine)); + Console.Write("\r".PadLeft(Console.WindowWidth - Console.CursorLeft - 1)); + if (Console.KeyAvailable) + { + char c = Console.ReadKey().KeyChar; + if (c == SPACE_ASCII_VALUE) + { + Console.WriteLine("\n Stop & Clear Multi-Turn Information!"); + + // Write the present position to the goal position to stop moving + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, (UInt32)dxl_present_position); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + System.Threading.Thread.Sleep(300); + + // Clear Multi-Turn Information + dynamixel.clearMultiTurn(port_num, PROTOCOL_VERSION, DXL_ID); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + // Read present position + dxl_present_position = (Int32)dynamixel.read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + Console.WriteLine(" Present Position has been reset. : {0} \n", dxl_present_position); + + break; + } + else if ( c == ESC_ASCII_VALUE) + { + Console.WriteLine("\n Stopped!! \n"); + + // Write the present position to the goal position to stop moving + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, (UInt32)dxl_present_position); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + break; + } + } + } while ((Math.Abs(MAX_POSITION_VALUE - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD)); + } + + // Disable Dynamixel Torque + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + // Close port + dynamixel.closePort(port_num); + + return; + } + } +} \ No newline at end of file diff --git a/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/Properties/AssemblyInfo.cs b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/Properties/AssemblyInfo.cs new file mode 100644 index 00000000..6bea8bcc --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/Properties/AssemblyInfo.cs @@ -0,0 +1,36 @@ +using System.Reflection; +using System.Runtime.CompilerServices; +using System.Runtime.InteropServices; + +// General Information about an assembly is controlled through the following +// set of attributes. Change these attribute values to modify the information +// associated with an assembly. +[assembly: AssemblyTitle("clear_multi_turn")] +[assembly: AssemblyDescription("")] +[assembly: AssemblyConfiguration("")] +[assembly: AssemblyCompany("")] +[assembly: AssemblyProduct("clear_multi_turn")] +[assembly: AssemblyCopyright("Copyright © 2018")] +[assembly: AssemblyTrademark("")] +[assembly: AssemblyCulture("")] + +// Setting ComVisible to false makes the types in this assembly not visible +// to COM components. If you need to access a type in this assembly from +// COM, set the ComVisible attribute to true on that type. +[assembly: ComVisible(false)] + +// The following GUID is for the ID of the typelib if this project is exposed to COM +[assembly: Guid("321bae3a-a494-47fa-a8cb-903202eb5fae")] + +// Version information for an assembly consists of the following four values: +// +// Major Version +// Minor Version +// Build Number +// Revision +// +// You can specify all the values or you can default the Build and Revision Numbers +// by using the '*' as shown below: +// [assembly: AssemblyVersion("1.0.*")] +[assembly: AssemblyVersion("1.0.0.0")] +[assembly: AssemblyFileVersion("1.0.0.0")] diff --git a/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.csproj b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.csproj new file mode 100644 index 00000000..f6ff2408 --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.csproj @@ -0,0 +1,102 @@ + + + + + Debug + AnyCPU + {321BAE3A-A494-47FA-A8CB-903202EB5FAE} + Exe + Properties + clear_multi_turn + clear_multi_turn + v4.5 + 512 + true + + + + AnyCPU + true + full + false + bin\Debug\ + DEBUG;TRACE + prompt + 4 + + + AnyCPU + pdbonly + true + bin\Release\ + TRACE + prompt + 4 + + + true + bin\x64\Debug\ + DEBUG;TRACE + full + x64 + prompt + MinimumRecommendedRules.ruleset + true + + + bin\x64\Release\ + TRACE + true + pdbonly + x64 + prompt + MinimumRecommendedRules.ruleset + true + + + true + bin\x86\Debug\ + DEBUG;TRACE + full + x86 + prompt + MinimumRecommendedRules.ruleset + true + + + bin\x86\Release\ + TRACE + true + pdbonly + x86 + prompt + MinimumRecommendedRules.ruleset + true + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/dynamixel.cs b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/dynamixel.cs new file mode 100644 index 00000000..cc0d12e2 --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win32/clear_multi_turn/dynamixel.cs @@ -0,0 +1,262 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Ryu Woon Jung (Leon) */ + +using System; +using System.Runtime.InteropServices; + +namespace dynamixel_sdk +{ + class dynamixel + { + const string dll_path = "../../../../../../../../c/build/win64/output/dxl_x64_c.dll"; + + #region PortHandler + [DllImport(dll_path)] + public static extern int portHandler (string port_name); + + [DllImport(dll_path)] + public static extern bool openPort (int port_num); + [DllImport(dll_path)] + public static extern void closePort (int port_num); + [DllImport(dll_path)] + public static extern void clearPort (int port_num); + + [DllImport(dll_path)] + public static extern void setPortName (int port_num, string port_name); + [DllImport(dll_path)] + public static extern string getPortName (int port_num); + + [DllImport(dll_path)] + public static extern bool setBaudRate (int port_num, int baudrate); + [DllImport(dll_path)] + public static extern int getBaudRate (int port_num); + + [DllImport(dll_path)] + public static extern int readPort (int port_num, byte[] packet, int length); + [DllImport(dll_path)] + public static extern int writePort (int port_num, byte[] packet, int length); + + [DllImport(dll_path)] + public static extern void setPacketTimeout (int port_num, UInt16 packet_length); + [DllImport(dll_path)] + public static extern void setPacketTimeoutMSec(int port_num, double msec); + [DllImport(dll_path)] + public static extern bool isPacketTimeout (int port_num); + #endregion + + #region PacketHandler + [DllImport(dll_path)] + public static extern void packetHandler (); + + [DllImport(dll_path)] + public static extern IntPtr getTxRxResult (int protocol_version, int result); + [DllImport(dll_path)] + public static extern IntPtr getRxPacketError (int protocol_version, byte error); + + [DllImport(dll_path)] + public static extern int getLastTxRxResult (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern byte getLastRxPacketError(int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void setDataWrite (int port_num, int protocol_version, UInt16 data_length, UInt16 data_pos, UInt32 data); + [DllImport(dll_path)] + public static extern UInt32 getDataRead (int port_num, int protocol_version, UInt16 data_length, UInt16 data_pos); + + [DllImport(dll_path)] + public static extern void txPacket (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void rxPacket (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void txRxPacket (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void ping (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern UInt16 pingGetModelNum (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern void broadcastPing (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern bool getBroadcastPingResult(int port_num, int protocol_version, int id); + + [DllImport(dll_path)] + public static extern void clearMultiTurn (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern void reboot (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern void factoryReset (int port_num, int protocol_version, byte id, byte option); + + [DllImport(dll_path)] + public static extern void readTx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + [DllImport(dll_path)] + public static extern void readRx (int port_num, int protocol_version, UInt16 length); + [DllImport(dll_path)] + public static extern void readTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + + [DllImport(dll_path)] + public static extern void read1ByteTx (int port_num, int protocol_version, byte id, UInt16 address); + [DllImport(dll_path)] + public static extern byte read1ByteRx (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern byte read1ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address); + + [DllImport(dll_path)] + public static extern void read2ByteTx (int port_num, int protocol_version, byte id, UInt16 address); + [DllImport(dll_path)] + public static extern UInt16 read2ByteRx (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern UInt16 read2ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address); + + [DllImport(dll_path)] + public static extern void read4ByteTx (int port_num, int protocol_version, byte id, UInt16 address); + [DllImport(dll_path)] + public static extern UInt32 read4ByteRx (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern UInt32 read4ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address); + + [DllImport(dll_path)] + public static extern void writeTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + [DllImport(dll_path)] + public static extern void writeTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + + [DllImport(dll_path)] + public static extern void write1ByteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, byte data); + [DllImport(dll_path)] + public static extern void write1ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address, byte data); + + [DllImport(dll_path)] + public static extern void write2ByteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt16 data); + [DllImport(dll_path)] + public static extern void write2ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 data); + + [DllImport(dll_path)] + public static extern void write4ByteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt32 data); + [DllImport(dll_path)] + public static extern void write4ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt32 data); + + [DllImport(dll_path)] + public static extern void regWriteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + [DllImport(dll_path)] + public static extern void regWriteTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + + [DllImport(dll_path)] + public static extern void syncReadTx (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length, UInt16 param_length); + // syncReadRx -> GroupSyncRead + // syncReadTxRx -> GroupSyncRead + + [DllImport(dll_path)] + public static extern void syncWriteTxOnly (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length, UInt16 param_length); + + [DllImport(dll_path)] + public static extern void bulkReadTx (int port_num, int protocol_version, UInt16 param_length); + // bulkReadRx -> GroupBulkRead + // bulkReadTxRx -> GroupBulkRead + + [DllImport(dll_path)] + public static extern void bulkWriteTxOnly (int port_num, int protocol_version, UInt16 param_length); + #endregion + + #region GroupBulkRead + [DllImport(dll_path)] + public static extern int groupBulkRead (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern bool groupBulkReadAddParam (int group_num, byte id, UInt16 start_address, UInt16 data_length); + [DllImport(dll_path)] + public static extern void groupBulkReadRemoveParam(int group_num, byte id); + [DllImport(dll_path)] + public static extern void groupBulkReadClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupBulkReadTxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupBulkReadRxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupBulkReadTxRxPacket (int group_num); + + [DllImport(dll_path)] + public static extern bool groupBulkReadIsAvailable(int group_num, byte id, UInt16 address, UInt16 data_length); + [DllImport(dll_path)] + public static extern UInt32 groupBulkReadGetData (int group_num, byte id, UInt16 address, UInt16 data_length); + #endregion + + #region GroupBulkWrite + [DllImport(dll_path)] + public static extern int groupBulkWrite (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern bool groupBulkWriteAddParam (int group_num, byte id, UInt16 start_address, UInt16 data_length, UInt32 data, UInt16 input_length); + [DllImport(dll_path)] + public static extern void groupBulkWriteRemoveParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern bool groupBulkWriteChangeParam (int group_num, byte id, UInt16 start_address, UInt16 data_length, UInt32 data, UInt16 input_length, UInt16 data_pos); + [DllImport(dll_path)] + public static extern void groupBulkWriteClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupBulkWriteTxPacket (int group_num); + #endregion + + #region GroupSyncRead + [DllImport(dll_path)] + public static extern int groupSyncRead (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length); + + [DllImport(dll_path)] + public static extern bool groupSyncReadAddParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern void groupSyncReadRemoveParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern void groupSyncReadClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupSyncReadTxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupSyncReadRxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupSyncReadTxRxPacket (int group_num); + + [DllImport(dll_path)] + public static extern bool groupSyncReadIsAvailable (int group_num, byte id, UInt16 address, UInt16 data_length); + [DllImport(dll_path)] + public static extern UInt32 groupSyncReadGetData (int group_num, byte id, UInt16 address, UInt16 data_length); + #endregion + + #region GroupSyncWrite + [DllImport(dll_path)] + public static extern int groupSyncWrite (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length); + + [DllImport(dll_path)] + public static extern bool groupSyncWriteAddParam (int group_num, byte id, UInt32 data, UInt16 data_length); + [DllImport(dll_path)] + public static extern void groupSyncWriteRemoveParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern bool groupSyncWriteChangeParam (int group_num, byte id, UInt32 data, UInt16 data_length, UInt16 data_pos); + [DllImport(dll_path)] + public static extern void groupSyncWriteClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupSyncWriteTxPacket (int group_num); + #endregion + } +} diff --git a/c#/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo b/c#/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo new file mode 100644 index 0000000000000000000000000000000000000000..3aff87b0de1107e5b84984446b54c872ce9d0636 GIT binary patch literal 46080 zcmeHQdyre#S--MlVkd4BH^%glIGflBZn9FfdaZU{yVhgZcI>q`+4b5GxofR-cP+10 z+DKZjH@1U$1e}z#sR^_|ODTjIrhu8`5129&CN0AZ1DQz(VW!jJk0!v-p`o1)3=lH0 z`Tg#>N4mOtUCHuFvhUG+_i=Qd-#Oo4)t;mp=ZsVsg8cwaS&N8tE{m6AvHA$oie*+2}SS%m%=R0rY2GZv%V;umx~CU=x7< zG44n4e24x%iMuhqy?EaWxEIg|xF5iH+i>3w_>BHezw7P7hP)zpjsiviY#)|+AMX1B zj{pt;4g$sihX98Gy9h-_!s@FTgJca zlada|vC1*exqqXf|8o4ZPm|u<3NVj<#wD1?zs!U8n_>K~2X17Y?=n0~zizt!Jj(YA zfM)<~yQgvgWx%fhF6w^I;{G|nuL7O}d>$a%THb#RelGxi9q=1~F9E&`_)WlX0e&0s z6@Uyc@7;upo3Si*``?VMUaE5j{O26F+ycgCD{dqBPp0NTWZtc$!FeUd#Ufli{+B$t zM+B>R1^-*5wN~^0C8YKd78q_4JoX|uIr98@Jm)o@Kcghz69t@B1{AmQun1h``Vi{R zxsv>_)%;2OWKv_uV?kSWte`Ahi>0vw;Farw6rM7`(PHsAFC*%AUkmkTRK5BQ@jqb7 z&-}{u2b=OffYtiXAngC@2{meeuO6<}jrl)-KbbdOt#C&FS-b>w1jzNDiWVwAK875n;JrqASmT5_v9ZeNe84bLbshhl-vc;ux>)7TVv~|8f~u zBEOi+o;sHpjxFWYTt1e~7h=h5VrfCm6!Nh|yfB~2OfTnS$(2leA$3Mg=aciX#I_h> z6|#wJ+T(J^5@|J_n_gH-7gE!OrCcVqoXP}zmEKx7Ef_-~>vQMMh60g6pDz@2x<`B= zr*AY8a0Y{ckkcLTd4gWI-xnD4o!=B;4r9zy_q?ZKQF{Z>e{KG0hW^;} zzy0)I(qJoNug&zoNc*kQUz`4y=1KB6GoTT38W)&@e5=Hd9Mz~#5;Ti+uDa{T{71Y? zS3Oj@FJ*?4x|ccsFeo2s;ykEkR?DAs*I1JBw7~y3w!!P;0G6Tr-|BCa*Kv(bXU<>b zMEWlz!6B4m5m+G~mePGiOmPh$|DVPqW!hHrC%;G;3Eij?g3Qqk3O}Mmz-u}cFWv^= z@5FTg6D`Tri|o0A178$GN+7WmFW7EhhP6zZHu?}%e&>C+_BOG*-c zS-cIP%r1ot!(lKC(JBl>R5A<`(F3hA3^k_xRnN9Ru6hRJff=_`_4@oya3(?LP#`($ z^sDh%?~qSby@4T@+wC6o2G40NYq)$=aja34?-YGDzxp1Y9RP~g^pz0SM0z{VVGNL) z=tD0^X>)oW&pW_d1eJjDNrW4Ne*&ShT9Q`Viaf^@dKo#79NIUAwv}=i-YM5x2jDa1 zdmJN_`*UqWzKVsV&X00H%J(TVBp*vTAbDV8T0f<~Q~u4d`3V5W2>YH<{(m3d?+0)U zZwGK5c@V%cwFB@;z(WA8!1@7BfD7;`fE&Q|3D<~RC-?wFQ6yTKZm&SbokO8pe7XeQIxK1H`E&!GQrvb}=Gk_JqlYp}T_RI5trvN_( zxB#$5e2@}kz2HDf!=nNF<7>tSA`aDNN)Uo-hP(nmiC{Ifri zrdjQO&E!x1gfb}7wrWoDU!;?*wd8j<@K3r;8g4cJFCr{y zJKdz#`{vQRh3sttRF9lj0i%Kvutq(A@*n0)p3Z9iq&@4IIouR-kaD*f${wo-h?2(-HYdhAT`ASziWa%Gc`|s1{oFp)wL7mgM zj%s<*hZ6Bd?po<@7`;9LxtPJ{|FK!-$-YkXXQ9!Y0`Bi z?;^gd1^h=5^-dAJqWzC*bxwc^nmHXkg6RhNbJOh~K^mL&bgIi88%rhyb&@L;Azc(p zntuTYaid67lNFL(SyS?`bpPT1PtT>7pF8;Hx4aX$``_1I-ehtjRDvyU!kkKU7S&py0UA45L8nrmhJ{SFe6^uJn~&H72&!+W!F+Y$a+^8XwbZg-&& zYn1v4NV!v4|F$oX@+#)rJ`?x#NW z(6N91?~5nif8`&Vtg6wWa`pHCjDH7ZQ5?@! z^EdK8)#v|NjpmU5tEYQq`MLfgKSy@XYW|NQ>{I##au__`DackhlS!udwT} zuhPANad2v#qU^x{`aTv>uKOT!#p3w<1CW#AzqhfloW}bo1iv1Q-F;^APTxoc|9Ze>wkiy=T<_w;=y3?hCS7|2@dxmj3|>aAy3M zz13S*^rp-b{ls^j6YvLHo=!2qQ>G*~k^~qlcFEss-0%Hk;1(_f5fCA(hSS z^16KZ4PbrU-xt9YzLZmUX%RVaBodm8pHY_zxp=z2Z+vMcok|=~S0=ObYG&7r+dJ!@ z9h@B)Nc!DzZ+soo->MaBYGUL}LCvs8u0!F-#JJgpataHYN5T`4^N7;TtMg^7(lXHY zTeFUAw3Zi=y+ut9eM-6K$9En3ee6}0%>qZcA^ zI`okU$0_B6!eW)Svge?wA@0W`5l$!-jw|v-Xi})dppJJ%vyq-eDk1bL%HV|*d?#e_ zgPP5geDc6r!vi08as5kSfhg~SrWt~`s?3p@P*EPW=*uC6B?R*3`Z}hUHD;_4I_E|x+Jt$5ry-=0 zM2Ti0mk{>CE=_it!M`3&hf6E9S%jbk8y)-a-tfWwl+jSvFV=gt?1LGS(t$=;i-A(p zPLMWwl#y`P_+I!>dMjim!e&EQFHNJh2hr+-sKF?%URd$C@f5`D=R^+*qh4V=g+bE; z2WV{ zK7*%O+&%aWprmocOltQ5LoH}MRGXp*+Y~ANifMW=TB)Sb3nczy#Xi)`%;`dF(B^|} zIHQft5c&&u|EKUyy*qnQ3EP}ug~n%5Yhg+R86sAZ4lQT6kG~Z6dh{obh5#_fzTpSZ zR?-K|(|*#2|2zP;L=;bKogjLfA7zaqPFVXlingR3KKoO27%Jk zGP^AOcF#{whvNxs;hh^zsp;g}FRqzb$rscGS0tNGtBGpzpMWj@QQrU4@BY>A+43K) z^V{+tRg?JG@*nOLQL+9k$sal;|G6Gg1zWz81y4h1hArO_`z(83zGJWNh0MS6Qo6<~ zzY~~kdt(J`ukY>keLX3&y}qxvd%sh&N~I3M1$x6Bm(<`{lV~Cdj)SqiT{!KWTIXst?$vg$ z#RpZkyE&v83z9o3-6tX=uqFi(ZPzmxD8LFh@7k+o)Lbgzil!3ui04*LcpiUTR}@VY za?l?2_bucT*<3m`Q!;4wx!nAfteI2av0;&bX) zJcBC_oOK=9?>d5GXr=zDzpr+{QbDR&R@W+vcVK4L8}tX_NpHZXdi}?b)0lL_T3l}7 z#iSs!5p?`G(Q>P9#lAk0U096g)ZF@g@%+h&)RQU>uv@=H?<vuz<91s4m(Hx?x{Ws6Jb{ophyvEFIi{~%05m5zD{=jj zs##s1na|H-{w8B&dR>!Wz4I1J_z-9KX_?`|waf)Tt9XzW$<5)x+$Q3i5uGhV0(R3p z+faP3qO)ZYa?&*VDa&)Q_)qzEMok!EEiTCFQxM@dBRg?`ii*>l=>uL)y&;2 zo#-o-<>A@$EX(IR-aeF7k@|~MOBLnWj+ZC}3v-^vO8i{vcxh;5nZe#2>Tkt4_1(~e zXra!%3f+LA)95|yMLCp+7O5=N3mtDamWq;Ap1efaEcu#Fj5qEdNF)DQl!vDR3#usJ zyQf5=oZWzB99WQpmFA%%~%EBV)N00f^Scg$1b-<@Bv5VhhLcX-0ysS4Q&|L2aWFti*a zps^wB-U(q&90G7}&mea42)`ie9M<-pe^?}{rN#X~;!NZ7*hLt^KWDZ5K($f??|z$N z-T*5X1^lQ>g)83!$sJsj8zG8A>1(vd)IyLCL}FTH{??Juj?!Dw)G$1bF$ScOta2Nm zwU3ijZj#F*?mSXh-H($Hrw#FQM6dilZvHg>xYbVl>OaX)@{aVBvhUKEPl=gOw%`6i z=;7zSweO|xe&hAK{@~~x&5hq`BOND^H##=0cz}!0LCJ5w2t6OUoF&ZUa*XiQaxTGn zin$Nh`aQaGj5slRxMPlc;XD{s#xX)Y=rU*%&-|15itkMsbLHt4b#VU$;A6GqjP17%s(1cbb0@4cK3`((jt~9Q*0&G8`{rxG zr1Sfm9%0v%JGbS%x%2C?QYu#8fU;>eZJQ7BW&|H+kVh=^lYVpWryqsYoFU!ZvR(J{YPzw`CG?k z+dFE?&9j}P16FMU8QyAGtKpjYj<77RZ9gdON^SeWQa?9aIoS4tX8T{;ez5YJ;sPg> zE8F&iwXkE`5B6zi_8KkxrG2NgKg(kdw(SS&VaT>0OhV(Ig~ovAKN~Ss-J-D<><1-B zX6-KR2V1rOBmdfa_Jgzu6!w4B`0r-y|7bgCv>)`W`N8yMnWzQ(Kk($u*$M@?Wm{r%T#vUn?E z4t93u&YcYfB7;6(DCl&L_(D$KXe8ha1_L3dJK*yKy>7oRFz7o^_SB*5SD)UR{F^8C zbjB3{5r_0!AwSac;5Ur3!%(-YAHt+r2Rb8Lfg zw_MzV^HN^s1+H_ZqD6FeV#sWYq}6zCjDu}b3^rl2Z`R#$w?{M1o`0p?wY+nKq4+wX zm9s#u_ZY6x?5mz_8%FbYiv4o)tMB2N5}LBD8fI?NivF5u@=KCd+Nz}2D@ocrZNE(t OXWMU!t-YPtvHkxqdxX9K literal 0 HcmV?d00001 diff --git a/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln new file mode 100644 index 00000000..c9ff38d4 --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 14 +VisualStudioVersion = 14.0.25420.1 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "clear_multi_turn", "clear_multi_turn\clear_multi_turn.csproj", "{321BAE3A-A494-47FA-A8CB-903202EB5FAE}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|Any CPU = Debug|Any CPU + Debug|x64 = Debug|x64 + Release|Any CPU = Release|Any CPU + Release|x64 = Release|x64 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Debug|Any CPU.ActiveCfg = Release|Any CPU + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Debug|Any CPU.Build.0 = Release|Any CPU + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Debug|x64.ActiveCfg = Debug|x64 + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Debug|x64.Build.0 = Debug|x64 + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Release|Any CPU.ActiveCfg = Release|Any CPU + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Release|Any CPU.Build.0 = Release|Any CPU + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Release|x64.ActiveCfg = Release|x64 + {321BAE3A-A494-47FA-A8CB-903202EB5FAE}.Release|x64.Build.0 = Release|x64 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/App.config b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/App.config new file mode 100644 index 00000000..d1428ad7 --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/App.config @@ -0,0 +1,6 @@ + + + + + + diff --git a/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/ClearMultiTurn.cs b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/ClearMultiTurn.cs new file mode 100644 index 00000000..4e699592 --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/ClearMultiTurn.cs @@ -0,0 +1,250 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Ki Jong Gil (Gilbert) */ + +// +// ********* Clear Multi-Turn Example ********* +// +// +// Available Dynamixel model on this example : Dynamixel X-series (firmware v42 or above) +// This example is designed for using a Dynamixel XM430-W350-R, and an U2D2. +// To use another Dynamixel model, such as MX series, see their details in E-Manual(emanual.robotis.com) and edit below "#define"d variables yourself. +// Be sure that Dynamixel properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +// + +using System; +using System.Runtime.InteropServices; +using dynamixel_sdk; + +namespace clear_multi_turn +{ + class ClearMultiTurn + { + // Control table address + public const int ADDR_OPERATING_MODE = 11; // Control table address is different in Dynamixel model + public const int ADDR_TORQUE_ENABLE = 64; + public const int ADDR_GOAL_POSITION = 116; + public const int ADDR_PRESENT_POSITION = 132; + + // Protocol version + public const int PROTOCOL_VERSION = 2; // See which protocol version is used in the Dynamixel + + // Default setting + public const int DXL_ID = 1; // Dynamixel ID: 1 + public const int BAUDRATE = 57600; + public const string DEVICENAME = "COM1"; // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + + public const int TORQUE_ENABLE = 1; // Value for enabling the torque + public const int TORQUE_DISABLE = 0; // Value for disabling the torque + public const int MAX_POSITION_VALUE = 1048575; // + public const int DXL_MOVING_STATUS_THRESHOLD = 20; // Dynamixel moving status threshold + public const int EXT_POSITION_CONTROL_MODE = 4; // Value for extended position control mode (operating mode) + + public const byte ESC_ASCII_VALUE = 0x1b; + public const byte SPACE_ASCII_VALUE = 0x20; + + public const int COMM_SUCCESS = 0; // Communication Success result value + public const int COMM_TX_FAIL = -1001; // Communication Tx Failed + + static void Main(string[] args) + { + int port_num = dynamixel.portHandler(DEVICENAME); + + // Initialize PacketHandler Structs + dynamixel.packetHandler(); + + int index = 0; + int dxl_comm_result = COMM_TX_FAIL; // Communication result + + byte dxl_error = 0; // Dynamixel error + Int32 dxl_present_position = 0; // Present position + + // Open port + if (dynamixel.openPort(port_num)) + { + Console.WriteLine("Succeeded to open the port!"); + } + else + { + Console.WriteLine("Failed to open the port!"); + Console.WriteLine("Press any key to terminate..."); + Console.ReadKey(); + return; + } + + // Set port baudrate + if (dynamixel.setBaudRate(port_num, BAUDRATE)) + { + Console.WriteLine("Succeeded to change the baudrate!"); + } + else + { + Console.WriteLine("Failed to change the baudrate!"); + Console.WriteLine("Press any key to terminate..."); + Console.ReadKey(); + return; + } + + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_OPERATING_MODE, EXT_POSITION_CONTROL_MODE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + else + { + Console.WriteLine("Operating mode changed to extended position control mode."); + } + + // Enable Dynamixel Torque + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + else + { + Console.WriteLine("Dynamixel has been successfully connected"); + } + + while (true) + { + Console.WriteLine("Press any key to continue! (or press ESC to quit!)"); + if (Console.ReadKey(true).KeyChar == ESC_ASCII_VALUE) + break; + + Console.WriteLine(" Press SPACE key to clear multi-turn information! (or press ESC to stop!)"); + + // Write goal position + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, MAX_POSITION_VALUE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + do + { + // Read present position + dxl_present_position = (Int32)dynamixel.read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + Console.Write(string.Format(" [ID: {0}] GoalPos: {1} PresPos: {2}", DXL_ID, MAX_POSITION_VALUE, dxl_present_position, Environment.NewLine)); + Console.Write("\r".PadLeft(Console.WindowWidth - Console.CursorLeft - 1)); + if (Console.KeyAvailable) + { + char c = Console.ReadKey().KeyChar; + if (c == SPACE_ASCII_VALUE) + { + Console.WriteLine("\n Stop & Clear Multi-Turn Information!"); + + // Write the present position to the goal position to stop moving + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, (UInt32)dxl_present_position); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + System.Threading.Thread.Sleep(300); + + // Clear Multi-Turn Information + dynamixel.clearMultiTurn(port_num, PROTOCOL_VERSION, DXL_ID); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + // Read present position + dxl_present_position = (Int32)dynamixel.read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + Console.WriteLine(" Present Position has been reset. : {0} \n", dxl_present_position); + + break; + } + else if ( c == ESC_ASCII_VALUE) + { + Console.WriteLine("\n Stopped!! \n"); + + // Write the present position to the goal position to stop moving + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, (UInt32)dxl_present_position); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + break; + } + } + } while ((Math.Abs(MAX_POSITION_VALUE - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD)); + } + + // Disable Dynamixel Torque + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result))); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + Console.WriteLine(Marshal.PtrToStringAnsi(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error))); + } + + // Close port + dynamixel.closePort(port_num); + + return; + } + } +} \ No newline at end of file diff --git a/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/Properties/AssemblyInfo.cs b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/Properties/AssemblyInfo.cs new file mode 100644 index 00000000..6bea8bcc --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/Properties/AssemblyInfo.cs @@ -0,0 +1,36 @@ +using System.Reflection; +using System.Runtime.CompilerServices; +using System.Runtime.InteropServices; + +// General Information about an assembly is controlled through the following +// set of attributes. Change these attribute values to modify the information +// associated with an assembly. +[assembly: AssemblyTitle("clear_multi_turn")] +[assembly: AssemblyDescription("")] +[assembly: AssemblyConfiguration("")] +[assembly: AssemblyCompany("")] +[assembly: AssemblyProduct("clear_multi_turn")] +[assembly: AssemblyCopyright("Copyright © 2018")] +[assembly: AssemblyTrademark("")] +[assembly: AssemblyCulture("")] + +// Setting ComVisible to false makes the types in this assembly not visible +// to COM components. If you need to access a type in this assembly from +// COM, set the ComVisible attribute to true on that type. +[assembly: ComVisible(false)] + +// The following GUID is for the ID of the typelib if this project is exposed to COM +[assembly: Guid("321bae3a-a494-47fa-a8cb-903202eb5fae")] + +// Version information for an assembly consists of the following four values: +// +// Major Version +// Minor Version +// Build Number +// Revision +// +// You can specify all the values or you can default the Build and Revision Numbers +// by using the '*' as shown below: +// [assembly: AssemblyVersion("1.0.*")] +[assembly: AssemblyVersion("1.0.0.0")] +[assembly: AssemblyFileVersion("1.0.0.0")] diff --git a/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.csproj b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.csproj new file mode 100644 index 00000000..4c008832 --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.csproj @@ -0,0 +1,82 @@ + + + + + Debug + AnyCPU + {321BAE3A-A494-47FA-A8CB-903202EB5FAE} + Exe + Properties + clear_multi_turn + clear_multi_turn + v4.5 + 512 + true + + + + AnyCPU + true + full + false + bin\Debug\ + DEBUG;TRACE + prompt + 4 + + + AnyCPU + pdbonly + true + bin\Release\ + TRACE + prompt + 4 + + + true + bin\x64\Debug\ + DEBUG;TRACE + full + x64 + prompt + MinimumRecommendedRules.ruleset + true + + + bin\x64\Release\ + TRACE + true + pdbonly + x64 + prompt + MinimumRecommendedRules.ruleset + true + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/dynamixel.cs b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/dynamixel.cs new file mode 100644 index 00000000..cc0d12e2 --- /dev/null +++ b/c#/protocol2.0/clear_multi_turn/win64/clear_multi_turn/dynamixel.cs @@ -0,0 +1,262 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Ryu Woon Jung (Leon) */ + +using System; +using System.Runtime.InteropServices; + +namespace dynamixel_sdk +{ + class dynamixel + { + const string dll_path = "../../../../../../../../c/build/win64/output/dxl_x64_c.dll"; + + #region PortHandler + [DllImport(dll_path)] + public static extern int portHandler (string port_name); + + [DllImport(dll_path)] + public static extern bool openPort (int port_num); + [DllImport(dll_path)] + public static extern void closePort (int port_num); + [DllImport(dll_path)] + public static extern void clearPort (int port_num); + + [DllImport(dll_path)] + public static extern void setPortName (int port_num, string port_name); + [DllImport(dll_path)] + public static extern string getPortName (int port_num); + + [DllImport(dll_path)] + public static extern bool setBaudRate (int port_num, int baudrate); + [DllImport(dll_path)] + public static extern int getBaudRate (int port_num); + + [DllImport(dll_path)] + public static extern int readPort (int port_num, byte[] packet, int length); + [DllImport(dll_path)] + public static extern int writePort (int port_num, byte[] packet, int length); + + [DllImport(dll_path)] + public static extern void setPacketTimeout (int port_num, UInt16 packet_length); + [DllImport(dll_path)] + public static extern void setPacketTimeoutMSec(int port_num, double msec); + [DllImport(dll_path)] + public static extern bool isPacketTimeout (int port_num); + #endregion + + #region PacketHandler + [DllImport(dll_path)] + public static extern void packetHandler (); + + [DllImport(dll_path)] + public static extern IntPtr getTxRxResult (int protocol_version, int result); + [DllImport(dll_path)] + public static extern IntPtr getRxPacketError (int protocol_version, byte error); + + [DllImport(dll_path)] + public static extern int getLastTxRxResult (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern byte getLastRxPacketError(int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void setDataWrite (int port_num, int protocol_version, UInt16 data_length, UInt16 data_pos, UInt32 data); + [DllImport(dll_path)] + public static extern UInt32 getDataRead (int port_num, int protocol_version, UInt16 data_length, UInt16 data_pos); + + [DllImport(dll_path)] + public static extern void txPacket (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void rxPacket (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void txRxPacket (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern void ping (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern UInt16 pingGetModelNum (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern void broadcastPing (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern bool getBroadcastPingResult(int port_num, int protocol_version, int id); + + [DllImport(dll_path)] + public static extern void clearMultiTurn (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern void reboot (int port_num, int protocol_version, byte id); + + [DllImport(dll_path)] + public static extern void factoryReset (int port_num, int protocol_version, byte id, byte option); + + [DllImport(dll_path)] + public static extern void readTx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + [DllImport(dll_path)] + public static extern void readRx (int port_num, int protocol_version, UInt16 length); + [DllImport(dll_path)] + public static extern void readTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + + [DllImport(dll_path)] + public static extern void read1ByteTx (int port_num, int protocol_version, byte id, UInt16 address); + [DllImport(dll_path)] + public static extern byte read1ByteRx (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern byte read1ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address); + + [DllImport(dll_path)] + public static extern void read2ByteTx (int port_num, int protocol_version, byte id, UInt16 address); + [DllImport(dll_path)] + public static extern UInt16 read2ByteRx (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern UInt16 read2ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address); + + [DllImport(dll_path)] + public static extern void read4ByteTx (int port_num, int protocol_version, byte id, UInt16 address); + [DllImport(dll_path)] + public static extern UInt32 read4ByteRx (int port_num, int protocol_version); + [DllImport(dll_path)] + public static extern UInt32 read4ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address); + + [DllImport(dll_path)] + public static extern void writeTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + [DllImport(dll_path)] + public static extern void writeTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + + [DllImport(dll_path)] + public static extern void write1ByteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, byte data); + [DllImport(dll_path)] + public static extern void write1ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address, byte data); + + [DllImport(dll_path)] + public static extern void write2ByteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt16 data); + [DllImport(dll_path)] + public static extern void write2ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 data); + + [DllImport(dll_path)] + public static extern void write4ByteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt32 data); + [DllImport(dll_path)] + public static extern void write4ByteTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt32 data); + + [DllImport(dll_path)] + public static extern void regWriteTxOnly (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + [DllImport(dll_path)] + public static extern void regWriteTxRx (int port_num, int protocol_version, byte id, UInt16 address, UInt16 length); + + [DllImport(dll_path)] + public static extern void syncReadTx (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length, UInt16 param_length); + // syncReadRx -> GroupSyncRead + // syncReadTxRx -> GroupSyncRead + + [DllImport(dll_path)] + public static extern void syncWriteTxOnly (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length, UInt16 param_length); + + [DllImport(dll_path)] + public static extern void bulkReadTx (int port_num, int protocol_version, UInt16 param_length); + // bulkReadRx -> GroupBulkRead + // bulkReadTxRx -> GroupBulkRead + + [DllImport(dll_path)] + public static extern void bulkWriteTxOnly (int port_num, int protocol_version, UInt16 param_length); + #endregion + + #region GroupBulkRead + [DllImport(dll_path)] + public static extern int groupBulkRead (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern bool groupBulkReadAddParam (int group_num, byte id, UInt16 start_address, UInt16 data_length); + [DllImport(dll_path)] + public static extern void groupBulkReadRemoveParam(int group_num, byte id); + [DllImport(dll_path)] + public static extern void groupBulkReadClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupBulkReadTxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupBulkReadRxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupBulkReadTxRxPacket (int group_num); + + [DllImport(dll_path)] + public static extern bool groupBulkReadIsAvailable(int group_num, byte id, UInt16 address, UInt16 data_length); + [DllImport(dll_path)] + public static extern UInt32 groupBulkReadGetData (int group_num, byte id, UInt16 address, UInt16 data_length); + #endregion + + #region GroupBulkWrite + [DllImport(dll_path)] + public static extern int groupBulkWrite (int port_num, int protocol_version); + + [DllImport(dll_path)] + public static extern bool groupBulkWriteAddParam (int group_num, byte id, UInt16 start_address, UInt16 data_length, UInt32 data, UInt16 input_length); + [DllImport(dll_path)] + public static extern void groupBulkWriteRemoveParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern bool groupBulkWriteChangeParam (int group_num, byte id, UInt16 start_address, UInt16 data_length, UInt32 data, UInt16 input_length, UInt16 data_pos); + [DllImport(dll_path)] + public static extern void groupBulkWriteClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupBulkWriteTxPacket (int group_num); + #endregion + + #region GroupSyncRead + [DllImport(dll_path)] + public static extern int groupSyncRead (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length); + + [DllImport(dll_path)] + public static extern bool groupSyncReadAddParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern void groupSyncReadRemoveParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern void groupSyncReadClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupSyncReadTxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupSyncReadRxPacket (int group_num); + [DllImport(dll_path)] + public static extern void groupSyncReadTxRxPacket (int group_num); + + [DllImport(dll_path)] + public static extern bool groupSyncReadIsAvailable (int group_num, byte id, UInt16 address, UInt16 data_length); + [DllImport(dll_path)] + public static extern UInt32 groupSyncReadGetData (int group_num, byte id, UInt16 address, UInt16 data_length); + #endregion + + #region GroupSyncWrite + [DllImport(dll_path)] + public static extern int groupSyncWrite (int port_num, int protocol_version, UInt16 start_address, UInt16 data_length); + + [DllImport(dll_path)] + public static extern bool groupSyncWriteAddParam (int group_num, byte id, UInt32 data, UInt16 data_length); + [DllImport(dll_path)] + public static extern void groupSyncWriteRemoveParam (int group_num, byte id); + [DllImport(dll_path)] + public static extern bool groupSyncWriteChangeParam (int group_num, byte id, UInt32 data, UInt16 data_length, UInt16 data_pos); + [DllImport(dll_path)] + public static extern void groupSyncWriteClearParam (int group_num); + + [DllImport(dll_path)] + public static extern void groupSyncWriteTxPacket (int group_num); + #endregion + } +} diff --git a/c#/protocol2.0/read_write/win32/.vs/read_write/v14/.suo b/c#/protocol2.0/read_write/win32/.vs/read_write/v14/.suo index 7b2b476023885cd1ee36768bfa23018c9fe8cd56..a52b9b35904520f942a22e4f90895407a4d1c282 100644 GIT binary patch delta 2715 zcmb_dZA_C_6u$Rui>189+LrQRf$}9N(1Bq{pg^@0J3wK=3|X+Nzy>HPU!8!&7Do(5 zS?GJv#JRZHvCM4A5_vPT8Mk1@59ds_CH~xx#r-qJkZmNmOx-yxo!yd2HoVQ#bKm=M z?mf?W&inco1pj?u+Q#FrRIV3z3}guD@l6LVfB1#}4o_u_`Ey`2rcShASBZFn4FdLT zJ_SpHPnC&7X)vNVrme=FE*AgD0#|PIC1a14N7}1V&oS6fLFf_Lh(rXfTZeWdVgn)p zVMMG)JjS^sw6vxYZ4<(R$Ux8?vJg3lIK(DIE@N=P9LsB=U!5NC6!ElhN4dd;v*e|I z#Xf;c8iSJjgFQD}Wy0ac@Y-QXXh1@K5G>l?KYhx_Cgfw3pZ|OKzUc7DJvBA@dW4po z6EieMje;g}XxxmJ0;S-HUk!rR5Gf*p)=<-8pGcv;3N4XBeQH}U2ke=wK)`HJ)#4UI zIJAOi^N~nYa8r2gn4~ER^HZWJkl)vMc)(+q^e#22gN_f$K?h#F5B%Gdu&i$oDU$T4 zX&5pzi4+>;C$dMh;RCIthKHyrRsxi1ELU1Cb4hf;O;Z8bol1FFY~W%VE+mCSJgEBd z;T}9Jt`F(c5H-cCz-#pJN?0;Bilh!wN@Sm8R>E*Xy_RGW%0y&BtiS;sg4&$8@b5?N zYg8BFn#jh&llYLyX&YnPSs(s-Sr6-A``HlMBkVAH2{DNMF4hehmP{?9l#;$zeB^OG zjA%FWVl2T_uxFI0rf_l*#@!Am64bEZw!y$T7ihAx<=&(jE~PDq)|Ks%Yfxazd%p!o z{w~m2%G43nQHoR~wU1$>?HJz(OKm=$0N#D4C9@0sX60tO2ysvPr(z^Ml18aWBYB~O zV;z|dFlja?qv}F41uK^B@&cj=zEtMJkXaWN%^&6_Xvi&tiPSME&mvn)KXGa6(Em$M zTvU4GCs|yO%4+ zm`i6NnB#(~0yUhFiuf%UPcq~;6924?)nL(dFfTiVSvia&gE$s0r-N8ThuLfFDEPLG z(@Q1PI0J4kl{_NM9WlYC?i6{P;}5+SVyD-^aLujU+U3}13iBg`MS zll{Q%$s)imsc1kvqKa z`S?q)A|r#y$N-CYUgJ&WYn`P6EOh?{?k+o+dRk!djRCmWWl_8wzOpJr0sP!`O8&g3 zPYBit(0;%qSM}bDg-cTvaz%-g^XSm4lEq+asWfbqZExP^!D#{Z9GaDH54UlUI`iPT zHA%M5%qt*x@LhN?s)O78YWQ)q9!|J-z_hz03R%H-)Sw^O1Itbe%+;D;(qAU+tWjKC z1DVC+4mi4u#7RDHJzt+FJ$39+6iDcW2BwKNa5rSi{)xv5 z{m}vXw$W!Y6b_ya-%l2WKEbef%BF7pE?iE~H)VnDQ%T@&&V%cdNnDg~G=IY7-U~(! v_Ks5UoNIyk93xCyW5D(HUAcBN#SvDqxmx!g)!M*;OBn=b#zG| delta 2479 zcmb_dZA?>V6u$56Ef% z?>X;t&p8b~;Da~$X&2L8tx4h8CdlEg%7B6&{PH^s!{D8oYiXZfx`ey$QIIZ7V6S_6HwAN8tpi@#`NqsdunWMjI)*C zyeOt`LWySyx^39jYK@>2}(Mjs302+HO}dpbUmVj z)&-Q&#n?lkC@IcP6cGhPNvO*xB(LimR1o+7feI0~llSLQkz^O9a2Xs)wwhU-%ppER z%p*QRTtHkzEFdl+!ibL%i-=DUpCUd(d@jF{)XyZHSN7_UF_CUvfFQS&Q{o^hKO<;J z|F_e6xS=YQ+=4u;Yhxlq7ccfLdNoScMw6X^PYi&a7r^5ZU{&;r^hHw;O6)MC?G%Ya z`Yei3-HnO>k5gN^9omI=PC?OH~6rNU6&NG9i~(}2O57UB>F40?7Omgld-yK{PI+G9=Z;|_Cg zbHm(02pCR;t$Z|o9``7B0G-JeAoo<6ijgD{OfsI}EVNO>Q{JOgFvsbNJxVaz^AVJv zg|T<2>ggT22+>X51N$?4W6E=pol@g@%zMyYhuDFrM<{+22}biFffSf9pO-C;`%JP8 zv0U)&4X_+o*}Il(!CiU;4q!VoAd**vt&M7zEWdVD%E9>{gWGd{*Aa=G%7#ATkWB*<)x%4c-xtWq-Zo*02A4oM0j{24fo{m>990nlNQUgR3H|v35#R^i^RQHmGA+^z&LP^ zRq;P^Fgi97+nlSW;PlWps)w!P)^IBib>pQeN4Sj|!y`%{INlSDu5`R$>7-v}EaS#7 zk*ICau^eMu%fXYT1Gfe}oJ!t3*~>>8E^VO!SKh0QW+fE&6hiM*N`9ZSzud9+2Wll) zG>*6Woy8Ru&c0&1(@|Ej-Ts=xS?)NlhTW592!;w_e$v1a<>kwl8M_C|GlyaSO#YJn z279(4#di>SZ4YzG_r5G*P!!4p&sV2l|6C^cOAPSftQel=K{|H?Q?MPTOA_R-XKEQp Z2MTFj_MC~Rl;p(z5G$z{_VDnW=1)IeJtrue full false - bin\Debug\ + bin\x86\Debug\ DEBUG;TRACE prompt 4 @@ -26,7 +26,7 @@ AnyCPU pdbonly true - bin\Release\ + bin\x86\Release\ TRACE prompt 4 diff --git a/c#/protocol_combined/win64/protocol_combined/dynamixel.cs b/c#/protocol_combined/win64/protocol_combined/dynamixel.cs index 2919d6c9..3c3cb890 100644 --- a/c#/protocol_combined/win64/protocol_combined/dynamixel.cs +++ b/c#/protocol_combined/win64/protocol_combined/dynamixel.cs @@ -23,7 +23,7 @@ namespace dynamixel_sdk { class dynamixel { - const string dll_path = "../../../../../../../../c/build/win64/output/dxl_x64_c.dll"; + const string dll_path = "../../../../../../../c/build/win64/output/dxl_x64_c.dll"; #region PortHandler [DllImport(dll_path)] @@ -46,18 +46,13 @@ class dynamixel [DllImport(dll_path)] public static extern int getBaudRate (int port_num); - #ifdef __linux__ [DllImport(dll_path)] - public static extern int getBytesAvailable (int port_num); - #endif - - [DllImport(dll_path)] - public static extern int readPort (int port_num, uint8_t *packet, int length); + public static extern int readPort (int port_num, byte[] packet, int length); [DllImport(dll_path)] - public static extern int writePort (int port_num, uint8_t *packet, int length); + public static extern int writePort (int port_num, byte[] packet, int length); [DllImport(dll_path)] - public static extern void setPacketTimeout (int port_num, uint16_t packet_length); + public static extern void setPacketTimeout (int port_num, UInt16 packet_length); [DllImport(dll_path)] public static extern void setPacketTimeoutMSec(int port_num, double msec); [DllImport(dll_path)] @@ -68,12 +63,11 @@ class dynamixel [DllImport(dll_path)] public static extern void packetHandler (); - [DllImport(dll_path)] public static extern IntPtr getTxRxResult (int protocol_version, int result); [DllImport(dll_path)] public static extern IntPtr getRxPacketError (int protocol_version, byte error); - + [DllImport(dll_path)] public static extern int getLastTxRxResult (int port_num, int protocol_version); [DllImport(dll_path)] diff --git a/c++/example/protocol2.0/clear_multi_turn/clear_multi_turn.cpp b/c++/example/protocol2.0/clear_multi_turn/clear_multi_turn.cpp new file mode 100644 index 00000000..e40ff594 --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/clear_multi_turn.cpp @@ -0,0 +1,314 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +// +// ********* Clear Multi-Turn Example ********* +// +// +// Available Dynamixel model on this example : MX with Protocol 2.0 (firmware v42 or above), Dynamixel X-series (firmware v42 or above) +// This example is tested with a Dynamixel XM430-W350-R, and an U2D2 +// Be sure that Dynamixel properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +// + +#if defined(__linux__) || defined(__APPLE__) +#include +#include +#include +#define STDIN_FILENO 0 +#elif defined(_WIN32) || defined(_WIN64) +#include +#endif + +#include +#include + +#include "dynamixel_sdk.h" // Uses Dynamixel SDK library + +// Control table address +#define ADDR_OPERATING_MODE 11 // Control table address is different in Dynamixel model +#define ADDR_TORQUE_ENABLE 64 +#define ADDR_GOAL_POSITION 116 +#define ADDR_PRESENT_POSITION 132 + +// Protocol version +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel + +// Default setting +#define DXL_ID 1 // Dynamixel ID: 1 +#define BAUDRATE 57600 +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define MAX_POSITION_VALUE 1048575 +#define DXL_MOVING_STATUS_THRESHOLD 20 // Dynamixel moving status threshold +#define EXT_POSITION_CONTROL_MODE 4 // Value for extended position control mode (operating mode) + +#define ESC_ASCII_VALUE 0x1b +#define SPACE_ASCII_VALUE 0x20 + +int getch() +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + ch = getchar(); + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + return ch; +#elif defined(_WIN32) || defined(_WIN64) + return _getch(); +#endif +} + +int kbhit(void) +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + int oldf; + + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + oldf = fcntl(STDIN_FILENO, F_GETFL, 0); + fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK); + + ch = getchar(); + + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + fcntl(STDIN_FILENO, F_SETFL, oldf); + + if (ch != EOF) + { + ungetc(ch, stdin); + return 1; + } + + return 0; +#elif defined(_WIN32) || defined(_WIN64) + return _kbhit(); +#endif +} + +void msecSleep(int waitTime) +{ +#if defined(__linux__) || defined(__APPLE__) + usleep(waitTime * 1000); +#elif defined(_WIN32) || defined(_WIN64) + _sleep(waitTime); +#endif +} + +int main() +{ + // Initialize PortHandler instance + // Set the port path + // Get methods and members of PortHandlerLinux or PortHandlerWindows + dynamixel::PortHandler *portHandler = dynamixel::PortHandler::getPortHandler(DEVICENAME); + + // Initialize PacketHandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler + dynamixel::PacketHandler *packetHandler = dynamixel::PacketHandler::getPacketHandler(PROTOCOL_VERSION); + + int dxl_comm_result = COMM_TX_FAIL; // Communication result + + uint8_t dxl_error = 0; // Dynamixel error + int32_t dxl_present_position = 0; // Present position + + // Open port + if (portHandler->openPort()) + { + printf("Succeeded to open the port!\n"); + } + else + { + printf("Failed to open the port!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Set port baudrate + if (portHandler->setBaudRate(BAUDRATE)) + { + printf("Succeeded to change the baudrate!\n"); + } + else + { + printf("Failed to change the baudrate!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Set operating mode to extended position control mode + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL_ID, ADDR_OPERATING_MODE, EXT_POSITION_CONTROL_MODE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + else + { + printf("Operating mode changed to extended position control mode. \n"); + } + + + // Enable Dynamixel Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + else + { + printf("Dynamixel has been successfully connected \n"); + } + + while(1) + { + printf("\nPress any key to continue! (or press ESC to quit!)\n"); + if (getch() == ESC_ASCII_VALUE) + break; + + printf(" Press SPACE key to clear multi-turn information! (or press ESC to stop!)\n"); + + // Write goal position + dxl_comm_result = packetHandler->write4ByteTxRx(portHandler, DXL_ID, ADDR_GOAL_POSITION, MAX_POSITION_VALUE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + do + { + // Read present position + dxl_comm_result = packetHandler->read4ByteTxRx(portHandler, DXL_ID, ADDR_PRESENT_POSITION, (uint32_t*)&dxl_present_position, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + printf(" [ID:%03d] GoalPos:%03d PresPos:%03d\r", DXL_ID, MAX_POSITION_VALUE, dxl_present_position); + + if (kbhit()) + { + char c = getch(); + if (c == SPACE_ASCII_VALUE) + { + printf("\n Stop & Clear Multi-Turn Information! \n"); + + // Write the present position to the goal position to stop moving + dxl_comm_result = packetHandler->write4ByteTxRx(portHandler, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + msecSleep(300); + + // Clear Multi-Turn Information + dxl_comm_result = packetHandler->clearMultiTurn(portHandler, DXL_ID, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + // Read present position + dxl_comm_result = packetHandler->read4ByteTxRx(portHandler, DXL_ID, ADDR_PRESENT_POSITION, (uint32_t*)&dxl_present_position, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + printf(" Present Position has been reset. : %03d \n", dxl_present_position); + + break; + } + else if (c == ESC_ASCII_VALUE) + { + printf("\n Stopped!! \n"); + + // Write the present position to the goal position to stop moving + dxl_comm_result = packetHandler->write4ByteTxRx(portHandler, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + break; + } + } + + }while((abs(MAX_POSITION_VALUE - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD)); + + printf("\n"); + } + + // Disable Dynamixel Torque + dxl_comm_result = packetHandler->write1ByteTxRx(portHandler, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); + if (dxl_comm_result != COMM_SUCCESS) + { + printf("%s\n", packetHandler->getTxRxResult(dxl_comm_result)); + } + else if (dxl_error != 0) + { + printf("%s\n", packetHandler->getRxPacketError(dxl_error)); + } + + // Close port + portHandler->closePort(); + + return 0; +} diff --git a/c++/example/protocol2.0/clear_multi_turn/linux32/Makefile b/c++/example/protocol2.0/clear_multi_turn/linux32/Makefile new file mode 100644 index 00000000..0d0e7906 --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/linux32/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m32 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x86_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/clear_multi_turn/linux64/Makefile b/c++/example/protocol2.0/clear_multi_turn/linux64/Makefile new file mode 100644 index 00000000..1059c159 --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/linux64/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m64 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x64_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile b/c++/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile new file mode 100644 index 00000000..5f5758e1 --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile @@ -0,0 +1,79 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_sbc_cpp +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/clear_multi_turn/mac/Makefile b/c++/example/protocol2.0/clear_multi_turn/mac/Makefile new file mode 100644 index 00000000..f2d8206d --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/mac/Makefile @@ -0,0 +1,78 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_mac_cpp + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c++/example/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo b/c++/example/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo new file mode 100644 index 0000000000000000000000000000000000000000..a3f42d9935bef459cb360257472bdf9d121945b4 GIT binary patch literal 22016 zcmeHPTWlOx8Jz&A#o9XLkI=+0i-^)l~BbC5j@dC8@_L5k9T&nyB^=# zINf9YGiT22KbQai&;S4Dtp9TLp0{3p?f$o=hHzZkEq!=>pY$nHy3G`qJ|pRQO#ATq z_3O-H9MMkLK{Iex%HgjhbxBbvi+4d<;!;`;2c_Fq*Zi(EYQ6QQeB|Z#->^N1a?jsq z6dne~oHQ?;0QMQgqEcmzR_e14O1oC^bK2{3n|~=t2Knki;3wX^q@f1|Nd?3)7YabF zmTUDo0{pv?c@MxU{w|dL37G}qj8p~|O-f_@gjo~j2vQ10v6fHZx9vf07r-k1^Cxn8v)j5f^2c_Qh%*}ZHs&_^2Pj`d7gQc4}4qY|JzW0z5MSm^@F$=dXd)H7bB&bAJ$Wn{>fFfby921ds+8KY;h=00#k|2XKoQWk^e;5%DeF zLjE5{-Vp%z0m^^o3;EA@H`00lb^z&t>+b}(0B(Q>;05>rEZ>KBpc+4l_fvqU0mlHx z0bd3@1CRkBKo}4KL;*2CKVSfG0&o&=3NQ#50-Oe%0Sp610A~Slz$jo0Fb)vo6YmR1 zOH|Xpg7*~Q+3GjTd|Y8d*E&+rdloS^1saF~9fTT?1LLDclEqgFb5cM~2Js?#T?_sV z=wGZ&T4ESSd!xXfgAO!}X9Y7!?3aK$iP&1<5$HdpNw&v1T&q0uCjg{%hB&Y!F;Z%w z#F^5uJCM#EQ8!B?mc?ug;;kS*jCUC+CB6P};3uz$_0tpAc=(Vn@MqB$=i6v)jfzdO z@7%!rbH7NC;SorC9sd91@_z`_oRb#7*$Q}I0d#N8?lGu`GJThgw0{5ze2esU?{mnc zY-bn+-Xic0g3pS;9hc_Np8{e@o%`ygjZw$^r2Rv@BAD}9#V3)$y^UcU{5%Z&vyjL# zaFX9IfgfoPmarqJunLRFb3p=dziA9k@ZY^i6uMGlezR}#oJcqDP~uVYYLK&OJSk;` zWvc4EqST?xQT1nSR*qu)+^^R&elz|7;7jRJFN?X?(0UA*w5lAe;Sv39d{h2%?P=Gs z4~_ZFzRmbU7fZ&=0u5Xw?-U}%){VxHL>4ZD0^ zrwGn{^SN+rK>kwyr9RD2zsjSagR;&C!XHx5IaBOHMji7L^tW#Mub=--^S^G(b39h( zzr+7EKKZ!$KMX3T1TI1nrXgJxb^WH9q%l)nEl&Rz*Ik5KPV1PN{>H#r^tw^AqMljL z56yYb+%n|Pw&Lgdv++vE zy;b@%>;LWi&!l~^Pd1R<>gPuEuZyVt*VPs_9}%+0>i9R0vA%_!jDHK(f8Fx8v;Ot; zv)QlB(BI@$diNwrZW)fzWmXsNlep#414o}-qXk)%x}Zxq@n_gf?Ij5J&R;_3I12CB z7_<;tLPf-fb-kpdp9xY2PUyB6EyWVFg}nZ~1l@r?sWjx2it=%kIfb00)Q!Ic(kgmB z&-GM%=g~ILI&&yN?cS~1bP1%Yy8bZ*?Wcg&Xk|4|b)aS*f5uri$Nvl4PV4(S|JpbE z=PO4`-~Yz+%)g%)p5iFX6vQ}nLThvX&Oc60Tq$Xl!G9h+u*_jl*_^nUf-o@;u-Ivz6m5QFD|{feQFcEr8F7D3F5{#zZ#70@zu#cAE2 zxB|-eqrL)?RPi8>iC~T*-KUb`x$WTJWgI_flK(FgpY4rKfyxbHi7;(;^i5LRs4^m z>>BOBu< z4Okuj{V4ltwSh+bw0U^$w3gpb;D`OM<0Wnek>2k81!M~Ub0dEGf9V4yU6TIRIs>Es zf#yc(hrh|tmhnrnK^Q*S-}uaW+CD*uzGtkVBh^Zz}-y&nGCYX0ZAMIcYF z70mqKxc)Wyvjm-hC-Pd`<|u!7_QE?M>_gka)lBpL+lYS%vNr>)yoYMmMOy6v8}WZ~ zy+*5jX~f@r|1tNZeuQ4gf1bas=lqXnC9UMYfr%%f#!XaNw>O9I#rvT~s<{Waf1&UH z;{KI6uT`A7inxEkdlS{IpjGkq>8#9!7meIWi+<#ExnC_gMsqo>*wZzx7K-Uy_L#@v z#h=ULcJ*|H%UY>iP>*HRa;czbJzc})X)T>Rr7n%;7S!yqX{Tq#H`6!ca;1Du#iQKD z_7CaJj>n^wlA2|c4m}~RmP+aDY>`DCdU_(AP30Cv+VO>{sgROfKz=N(YN_4d+!bFc zmeh_jF~7$y`B8PuB+IbvXHF zVKjYxiZAK&yMi9C>I?)g_FOP#Xc%2nX4N4ji)Tj7mK zVDG^yt(+;O(pg1YErW{EKEZ2y7->;D9Z<*06SOm;KzS4Ken*^yY!U;NM2*I(h4THNV* z_rRlX{QU6Y{$Kt5?JJK@XQ~IAGr4L!C}!UDyBDtdXI8D z|C?3+AMc3Mr)gFH-)jFKXNNvWtN6|K#}@eiY{H(iihn!&fApzY#ox~Vw*mW4$4lG{ z=*F7CJpYaM*G{zmjFB79H3yFZTW$Z*pV6`ZI`*G6%erI#t>JpOae_MbUt6)Z8C$Pe z-H!dYotA06{nyd|Y0WotFeKoE;8~nmOfWb!)AuXNo@or3E%1EN1a;W?eT+6XnGlZRt3h z-CT=HNA`apcYl4O_IF$g%p7?A!`BZDzVf})tKT_vEx11WoqcPxP1j?;@+@Wu7Oe)m zHr>L;HCw`T8(hX6sja&;l>(pF+t%ypzwzrV_HeKMyXCFy+f(|ll((`)2Y#!}o07cm z$h(#+`fryz{9mteG~W+8{NK!fNAB;7(D1K(a*WbMxC*7u|4gIcNHIk4{k zr~R^%@Bd2JOKZP+4&%IP79-+r#$BOtw=ho5c=K7@f95?--Y2n1f3ii6I`MZ|cE;pr zEEcrO-cZEu4R`|fK%XmQ4+UM`Xw2<$`F+kSD+N_aO)VDEB{fltIxZzE`9f}fC44l& zQ}AM9SW`+fxk4rpQHu+uTs{$5$|{+3Mb+YwQ;B4EcS5ZwnY^YZP_L9r<}|m%X=>3F zbtLoom6gj8XVfM8!hU~>$F4r`OX_1=%7mH$5X z%q=yvJyPg5VyVK;kl*j~#O%Ic)NS|nxuSMC6mr=ka=;r6`Q%tE>c6s*s%TS{fPX5P zSdCd&C`CyW3#cO2YpR%9m|D~?XJA=#h0=hMO=)VuxUW%kB(1JZ==UE*_mj9Il24?w zNv)hx>qn6o7No}O8>$$HW6tsj{w7A?iur<(V8m~iJz=Na>ko(R0aqko_qZc2IpB=> z!>*8N0rL6U66Eu%i;!%|E&V4(2gX7-GELKQO=;YvT=*I=jPV{_55S;Rv6kHbd7 z@;OFk0=>aGJ!SHA{H*hYTqt^z{t>2}&5n$@P&!!Q5nINlEwi_fL*a_J$VcV~REx z3@iPy(%_Q2_hj(oP$pBFoIbHoN-5=G_o<2L(DLANaXuVgmVKkMDP?{sRvK9t8}s;; zvM-<%XVm4Ov*H_GIukm*EX(J+quJS|#l_6&AvqoB9-1#N3|D5Cm(NB{rbD^(xk|nt zH? + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {A0FAEFF9-A4BD-4838-871B-B914EF211650} + Win32Proj + clear_multi_turn + 8.1 + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + $(VC_LibraryPath_x86);$(WindowsSDK_LibraryPath_x86);$(NETFXKitsDir)Lib\um\x86;..\..\..\..\..\build\win32\output + + + false + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsCpp + + + Console + true + true + true + dxl_x86_cpp.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + + + + + diff --git a/c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters b/c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters new file mode 100644 index 00000000..21141bfb --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + diff --git a/c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user b/c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user new file mode 100644 index 00000000..45bf49fb --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win32\output; + WindowsLocalDebugger + + \ No newline at end of file diff --git a/c++/example/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo b/c++/example/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo new file mode 100644 index 0000000000000000000000000000000000000000..08a021c2af6bc0b5c8d0606bd639ffcf5ca470d6 GIT binary patch literal 24064 zcmeHPTWnlM89tk|G?%uaB!tqIcH5*EYVT(6-c3m8UTr6Ky!QH*WP^LWdu*@0x9%lg zJBfsYnV*IUQ{8#9TR%+vC0?E{0 zI>CQ6$ zG{yO}{k>us>Gp99?q5_!1hv;W1r@N3Qg50&#h0{@HUa0mQO5Z4CI{|7)8kQHPD*+CAF3&gU! z;JeG=gYXZ5z63f9Is*DK=rNEN9jyUX|d9+Q2 z1tNntEg&=6M~ftlw>V^yLrMzaJZiPZ0)W6~UCKpa51#+M`=KpL&^M(&|<``eNKeJGIg z23>VOvv)Nd#Qq-uCJ-7>TNdUO@TdJ-ZGR|`LIEQo2N~oM682CIV~$eLv{0>b#ly0K z@mDE-j=edROAdakxJOjt9`L6;*`8MQ?*#I4Zl@bY>+;~+hZeHk5zKnTUa{lF>4(HQW`JY1G zzm*GY#-Fx*Be#OY5K9+=BI0teKq_8SZ%q|(z55uqMr}KNXuhA64pnp zwV3N4F(NTztNrgm-jg(%;TrKD0e7y9jqE_!Un)K&25ptUe*LR$|4pIQ(~t@=k7&JG z-76lQXg~3=*dx6nLyd?>5qG9+e-8ll%mR7Q{;gi)M^yw{qX1nL?QgbQ?1|`->INT1 z%9G{P@B{-aLGNO)!m5#8`GYEN^0s$g`uC|lkN$N>-(z31zyEAia?MxH7sL#7w6G>2 z>1q72uYDi|QlEp}l|e65T07b|`sX9)f6AZ732cErtzMX0kFS;!tNC-zBkpWw_lvTD zKh(W4?sv4xpLG@XXElG?f5br4OX^=U3@q>u_gY%zPkYtJMF6g#j(=hun`+@k%kq!I z=AB2FqhG>EE9} zSorSKlT+_K;)4uViT~93hvT_b{oBNU%k$JHjsKe2U+ZoEt#0&bUsLadTZ{7AEkp38 z-|n|-k$*M(8`)pii2Y~a`NSt^|Ec!JwQB!W+aF`K_ zcx~6S7UHbr0Q}Ro{5mz~?`0>)+LM{!=~wE#uDxU^1S_CM$HO`i1yc=pOy*^jhzF{j28R4}DL8EAJud z_oC{}1knGs`QL#`4VNoc&A;~kgT5w}Epn`YKhMhQ;eU-2Pr|gDh+Y+8_v4NC1GQLv z4RHQ$;C=@0RU9gPG_1trZA&1ytMDHIav={&RC_ocB!I-Z#qaYyDRCVX;i4(XwUl8kSC zW=mutUrrP`TAIs#DiOJ>m zILsFQwa}WbF4-A#x~v|%L$SC$r#nw+0t%yQ^0d+~r}0cF>4JHr*F2I}a-#m7#`+nT zE7FEw?bgXDyW8oK<93%ru{%$nW`Av0kN^1CluxyMD3x2vD!k2~NoD1nlH1lJ=Vu~` zMFj_^+xC_HyJ4$!)$`vqIRCe8|7_0x%k#gOwy8(@a65WcYZrAjah00CMcPwq^Z8C~ zhg{T?{Jss+c4IXZ!7~-^EE{#VDvY>!Qo^~43pWd+ICtSKGwvtnK~q>?jVcbxWAB}} zF^uYcm?Fj^@81|zJDm4GqAE&Csg_Dw>cV?3cCCZ(&!9ZMbJshG^eMb!R=tX9#`YFa zAK@&xQ)wyx)e4C;;j7;*eI%y0*Lq%l^G6qV|6puapLF|g?@In}`@Vr^E?;>6;_EN) zN+s_1{A169Z~S=QzV284{`UEYCsSoWV?f$Vpq1>RcSGvKxWP7pQzM=%tnW#}mGiF` zJ#0s!B*UI9R>l5K_nHU)GAMEZmvz(&~r zVyWPyp%1q+iLA!ftM%=s{kNW$>D6cdeILrU68mrCExt-JdM<6EQ*Fsmd z;zWMoqpT%_X5kCmA@vt+XMqa#@BGNy@%5GBuZZNH+VlFyuixAE!gt~?K6~#aPkZ=H zs`%A}A9$C)Tsw^YZEDpJcJp~_i@)(uq;rrS_pc5u;hG)l-MM}snj~;dq7KHZ#(!)JEzoI{LmWL?U4E_#kFm1b&qK0 z4R-bR-xMUseG8uc`_LnCwI>AzJ-o)PGuP1$GjwQU>#@8Cdaiut)QUX#i_)_={gI^A z;IFmRWPLldk=9I>gp2xLJ+(T1@mbmN9yjlk8l>MD0tYSlJL|QCyunb&WAZwD0h7aR zcbnW@R-eh|u{wewo7L)aTF#%#DRO*bK9?vc(dD4|Ostg6WoFO$4@P+ml8=Uya$zcy zOGN`pey)(oMgt3JIh80W$w=T>G}h4(RZ4Oyn^dCsu8@gkk~XtNSE4Rxj%Bmw&YcZd zf>y87?=t!9PLIhEbXZLupUYyh+g(nN&E~gxZMO4V!wk~5K6pM@`tK8uT~|%JN%Fla zy2@|yxm-?r$mH|{Z6-&THE8nsd{$Gy>vjZvPH!j_be%sJFC`~RZr4OCx)f@mqhvXn z&*2l%UlaNG+{Cc?RJI}- z7OKYcJ4H0aJkxRu{w!Kx4LLmlPrzmJ+Wi)j!{zsz+}42GWVZ#ZUbiLW@>_kn4#;Mg zyC9og>V#O`(bC;J+%w|4a?sRl*F-XrE|#KM^v%SK);U^K>n#ghS3~7?-OPl^V|=}4 zrFAR#sjZf>GtsYlh%~bnIF}gp4Ghg&j&)CGyl}@OBQwE~X@q=y^$z;IC+JVP4|rx6 z@Qxpk3|V@;xx6Fh8f3&!dT_*w-2T$+{2BL&!4XCtjRj{;#^$}=K)xTZT>)<_e&&g8 ze&9P085#1824=$6lipGwC}ZO6tYeT#jI`B}ez(d!(Zj?1$Pp~B$Y$cWt~7oBc7Kcy^s zEG1`nVZe8M(d#|g5ll}n%+IHe_j?oWj{e!=T(~s7xHuFzn($>3Cra6F9M#Wdx>6ZS z@j%3uvNq=7QgnJ<7PLoCF$2ILeJVB_}b&YT{`^t&lTanjoqEspX*#JXmAt%ZQ{R`q1{dV zSA7C&#;$?*4dN#LYi<8VtXq=wJkFRk{P%{iY1bG3)w5_f00v%s|gPkh*$-6n}an9IwIC>4B6Mvrf~&ZE v0y{794kFKfTETzZe_jp#6ZK!|nOm#%uZ665|BGmMHTA#I?|-fK{@(uq3~3$1 literal 0 HcmV?d00001 diff --git a/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln new file mode 100644 index 00000000..4e8b2195 --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio Express 14 for Windows Desktop +VisualStudioVersion = 14.0.25123.0 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "clear_multi_turn", "clear_multi_turn\clear_multi_turn.vcxproj", "{A0FAEFF9-A4BD-4838-871B-B914EF211650}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Debug|x64.ActiveCfg = Debug|x64 + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Debug|x64.Build.0 = Debug|x64 + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Debug|x86.ActiveCfg = Debug|Win32 + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Debug|x86.Build.0 = Debug|Win32 + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Release|x64.ActiveCfg = Release|x64 + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Release|x64.Build.0 = Release|x64 + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Release|x86.ActiveCfg = Release|Win32 + {A0FAEFF9-A4BD-4838-871B-B914EF211650}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj new file mode 100644 index 00000000..43585907 --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj @@ -0,0 +1,156 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {A0FAEFF9-A4BD-4838-871B-B914EF211650} + Win32Proj + clear_multi_turn + 8.1 + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + + + false + $(SolutionDir)$(Configuration)\ + $(Configuration)\ + $(VC_LibraryPath_x64);$(WindowsSDK_LibraryPath_x64);$(NETFXKitsDir)Lib\um\x64;..\..\..\..\..\build\win64\output + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsCpp + + + Console + true + true + true + dxl_x64_cpp.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + + + + + diff --git a/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters new file mode 100644 index 00000000..21141bfb --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + diff --git a/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user new file mode 100644 index 00000000..0f71dd30 --- /dev/null +++ b/c++/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win64\output; + WindowsLocalDebugger + + \ No newline at end of file diff --git a/c++/include/dynamixel_sdk/packet_handler.h b/c++/include/dynamixel_sdk/packet_handler.h index 37ff2400..8b20e26f 100644 --- a/c++/include/dynamixel_sdk/packet_handler.h +++ b/c++/include/dynamixel_sdk/packet_handler.h @@ -24,6 +24,11 @@ #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) #include + +#define ERROR_PRINT SerialBT2.print +#else +#define ERROR_PRINT printf + #endif #include @@ -52,6 +57,7 @@ #define INST_BULK_READ 146 // 0x92 // --- Only for 2.0 --- // #define INST_REBOOT 8 +#define INST_CLEAR 16 // 0x10 #define INST_STATUS 85 // 0x55 #define INST_SYNC_READ 130 // 0x82 #define INST_BULK_WRITE 147 // 0x93 @@ -222,6 +228,19 @@ class WINDECLSPEC PacketHandler //////////////////////////////////////////////////////////////////////////////// virtual int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0; + //////////////////////////////////////////////////////////////////////////////// + /// @brief The function that reset multi-turn revolution information of Dynamixel + /// @description The function makes an instruction packet with INST_CLEAR, + /// @description transmits the packet with PacketHandler::txRxPacket(). + /// @description Applied Products : MX with Protocol 2.0 (Firmware v42 or above), + /// @description Dynamixel X-series (Firmware v42 or above). + /// @param port PortHandler instance + /// @param id Dynamixel ID + /// @param error Dynamixel hardware error + /// @return communication results which come from PacketHandler::txRxPacket() + //////////////////////////////////////////////////////////////////////////////// + virtual int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0; + //////////////////////////////////////////////////////////////////////////////// /// @brief The function that makes Dynamixel reset as it was produced in the factory /// @description The function makes an instruction packet with INST_FACTORY_RESET, @@ -491,7 +510,7 @@ class WINDECLSPEC PacketHandler /// @brief The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits the packet with PacketHandler::txPacket(). - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write @@ -506,7 +525,7 @@ class WINDECLSPEC PacketHandler /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits and receives the packet with PacketHandler::txRxPacket(), /// @description gets the error from the packet. - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write diff --git a/c++/include/dynamixel_sdk/protocol1_packet_handler.h b/c++/include/dynamixel_sdk/protocol1_packet_handler.h index ebfa05c0..3dcbadd1 100644 --- a/c++/include/dynamixel_sdk/protocol1_packet_handler.h +++ b/c++/include/dynamixel_sdk/protocol1_packet_handler.h @@ -178,6 +178,15 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler //////////////////////////////////////////////////////////////////////////////// int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// + /// @brief (Available only in Protocol 2.0) The function that reset multi-turn revolution information of Dynamixel + /// @param port PortHandler instance + /// @param id Dynamixel ID + /// @param error Dynamixel hardware error + /// @return COMM_NOT_AVAILABLE + //////////////////////////////////////////////////////////////////////////////// + int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// /// @brief The function that makes Dynamixel reset as it was produced in the factory /// @description The function makes an instruction packet with INST_FACTORY_RESET, @@ -447,7 +456,7 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler /// @brief The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits the packet with Protocol1PacketHandler::txPacket(). - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write @@ -462,7 +471,7 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits and receives the packet with Protocol1PacketHandler::txRxPacket(), /// @description gets the error from the packet. - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write diff --git a/c++/include/dynamixel_sdk/protocol2_packet_handler.h b/c++/include/dynamixel_sdk/protocol2_packet_handler.h index 3c953f39..b8bd8856 100644 --- a/c++/include/dynamixel_sdk/protocol2_packet_handler.h +++ b/c++/include/dynamixel_sdk/protocol2_packet_handler.h @@ -186,6 +186,19 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler //////////////////////////////////////////////////////////////////////////////// int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// + /// @brief The function that reset multi-turn revolution information of Dynamixel + /// @description The function makes an instruction packet with INST_CLEAR, + /// @description transmits the packet with Protocol2PacketHandler::txRxPacket(). + /// @description Applied Products : MX with Protocol 2.0 (Firmware v42 or above), + /// @description Dynamixel X-series (Firmware v42 or above). + /// @param port PortHandler instance + /// @param id Dynamixel ID + /// @param error Dynamixel hardware error + /// @return communication results which come from Protocol2PacketHandler::txRxPacket() + //////////////////////////////////////////////////////////////////////////////// + int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// /// @brief The function that makes Dynamixel reset as it was produced in the factory /// @description The function makes an instruction packet with INST_FACTORY_RESET, @@ -455,7 +468,7 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler /// @brief The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits the packet with Protocol2PacketHandler::txPacket(). - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write @@ -470,7 +483,7 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits and receives the packet with Protocol2PacketHandler::txRxPacket(), /// @description gets the error from the packet. - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write diff --git a/c++/src/dynamixel_sdk/group_bulk_read.cpp b/c++/src/dynamixel_sdk/group_bulk_read.cpp index bcea7551..edd1ad69 100644 --- a/c++/src/dynamixel_sdk/group_bulk_read.cpp +++ b/c++/src/dynamixel_sdk/group_bulk_read.cpp @@ -232,14 +232,5 @@ bool GroupBulkRead::getError(uint8_t id, uint8_t* error) // TODO : check protocol version, last_result_, data_list // if (last_result_ == false || error_list_.find(id) == error_list_.end()) - error[0] = error_list_[id][0]; - - if (error[0] != 0) - { - return true; - } - else - { - return false; - } + return error[0] = error_list_[id][0]; } \ No newline at end of file diff --git a/c++/src/dynamixel_sdk/group_sync_read.cpp b/c++/src/dynamixel_sdk/group_sync_read.cpp index f392943b..79e5f3b8 100644 --- a/c++/src/dynamixel_sdk/group_sync_read.cpp +++ b/c++/src/dynamixel_sdk/group_sync_read.cpp @@ -201,14 +201,5 @@ bool GroupSyncRead::getError(uint8_t id, uint8_t* error) // TODO : check protocol version, last_result_, data_list // if (ph_->getProtocolVersion() == 1.0 || last_result_ == false || error_list_.find(id) == error_list_.end()) - error[0] = error_list_[id][0]; - - if (error[0] != 0) - { - return true; - } - else - { - return false; - } + return error[0] = error_list_[id][0]; } \ No newline at end of file diff --git a/c++/src/dynamixel_sdk/port_handler_arduino.cpp b/c++/src/dynamixel_sdk/port_handler_arduino.cpp index 19ad599f..07add9ad 100644 --- a/c++/src/dynamixel_sdk/port_handler_arduino.cpp +++ b/c++/src/dynamixel_sdk/port_handler_arduino.cpp @@ -27,7 +27,7 @@ #define DYNAMIXEL_SERIAL Serial3 #endif -#define LATENCY_TIMER 16 // msec (USB latency timer) +#define LATENCY_TIMER 4 // msec (USB latency timer) using namespace dynamixel; @@ -91,10 +91,17 @@ void PortHandlerArduino::closePort() void PortHandlerArduino::clearPort() { + int temp __attribute__((unused)); #if defined(__OPENCR__) - DYNAMIXEL_SERIAL.flush(); + while (DYNAMIXEL_SERIAL.available()) + { + temp = DYNAMIXEL_SERIAL.read(); + } #elif defined(__OPENCM904__) - p_dxl_serial->flush(); + while (p_dxl_serial->available()) + { + temp = p_dxl_serial->read(); + } #endif } @@ -205,7 +212,7 @@ bool PortHandlerArduino::isPacketTimeout() double PortHandlerArduino::getCurrentTime() { - return (double)millis(); + return (double)millis(); } double PortHandlerArduino::getTimeSinceStart() @@ -285,8 +292,15 @@ void PortHandlerArduino::setTxEnable() void PortHandlerArduino::setTxDisable() { #if defined(__OPENCR__) +#ifdef SERIAL_WRITES_NON_BLOCKING + DYNAMIXEL_SERIAL.flush(); // make sure it completes before we disable... +#endif drv_dxl_tx_enable(FALSE); + #elif defined(__OPENCM904__) +#ifdef SERIAL_WRITES_NON_BLOCKING + p_dxl_serial->flush(); +#endif drv_dxl_tx_enable(socket_fd_, FALSE); #endif } diff --git a/c++/src/dynamixel_sdk/port_handler_linux.cpp b/c++/src/dynamixel_sdk/port_handler_linux.cpp index adf3ef82..9f563508 100644 --- a/c++/src/dynamixel_sdk/port_handler_linux.cpp +++ b/c++/src/dynamixel_sdk/port_handler_linux.cpp @@ -56,6 +56,27 @@ // or if you have another good idea that can be an alternatives, // please give us advice via github issue https://github.com/ROBOTIS-GIT/DynamixelSDK/issues +struct termios2 { + tcflag_t c_iflag; /* input mode flags */ + tcflag_t c_oflag; /* output mode flags */ + tcflag_t c_cflag; /* control mode flags */ + tcflag_t c_lflag; /* local mode flags */ + cc_t c_line; /* line discipline */ + cc_t c_cc[19]; /* control characters */ + speed_t c_ispeed; /* input speed */ + speed_t c_ospeed; /* output speed */ +}; + +#ifndef TCGETS2 +#define TCGETS2 _IOR('T', 0x2A, struct termios2) +#endif +#ifndef TCSETS2 +#define TCSETS2 _IOW('T', 0x2B, struct termios2) +#endif +#ifndef BOTHER +#define BOTHER 0010000 +#endif + using namespace dynamixel; PortHandlerLinux::PortHandlerLinux(const char *port_name) @@ -217,6 +238,19 @@ bool PortHandlerLinux::setupPort(int cflag_baud) bool PortHandlerLinux::setCustomBaudrate(int speed) { + struct termios2 options; + + if (ioctl(socket_fd_, TCGETS2, &options) != 01) + { + options.c_cflag &= ~CBAUD; + options.c_cflag |= BOTHER; + options.c_ispeed = speed; + options.c_ospeed = speed; + + if (ioctl(socket_fd_, TCSETS2, &options) != -1) + return true; + } + // try to set a custom divisor struct serial_struct ss; if(ioctl(socket_fd_, TIOCGSERIAL, &ss) != 0) diff --git a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp index f8efe111..668adfa3 100644 --- a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp @@ -365,6 +365,11 @@ int Protocol1PacketHandler::reboot(PortHandler *port, uint8_t id, uint8_t *error return COMM_NOT_AVAILABLE; } +int Protocol1PacketHandler::clearMultiTurn(PortHandler *port, uint8_t id, uint8_t *error) +{ + return COMM_NOT_AVAILABLE; +} + int Protocol1PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error) { uint8_t txpacket[6] = {0}; @@ -407,6 +412,9 @@ int Protocol1PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t lengt uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length+6); //uint8_t *rxpacket = new uint8_t[length+6]; + if (rxpacket == NULL) + return result; + do { result = rxPacket(port, rxpacket); } while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id); @@ -436,8 +444,14 @@ int Protocol1PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add uint8_t txpacket[8] = {0}; uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);//(length+6); + if (rxpacket == NULL) + return result; + if (id >= BROADCAST_ID) + { + free(rxpacket); return COMM_NOT_AVAILABLE; + } txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = 4; @@ -534,6 +548,9 @@ int Protocol1PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t uint8_t *txpacket = (uint8_t *)malloc(length+7); //uint8_t *txpacket = new uint8_t[length+7]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_WRITE; @@ -559,6 +576,9 @@ int Protocol1PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t ad //uint8_t *txpacket = new uint8_t[length+7]; uint8_t rxpacket[6] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_WRITE; @@ -615,6 +635,9 @@ int Protocol1PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16 uint8_t *txpacket = (uint8_t *)malloc(length+6); //uint8_t *txpacket = new uint8_t[length+6]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_REG_WRITE; @@ -640,6 +663,9 @@ int Protocol1PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t //uint8_t *txpacket = new uint8_t[length+6]; uint8_t rxpacket[6] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_REG_WRITE; @@ -669,6 +695,9 @@ int Protocol1PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_ad // 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM //uint8_t *txpacket = new uint8_t[param_length + 8]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH] = param_length + 4; // 4: INST START_ADDR DATA_LEN ... CHKSUM txpacket[PKT_INSTRUCTION] = INST_SYNC_WRITE; @@ -694,6 +723,9 @@ int Protocol1PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16 // 7: HEADER0 HEADER1 ID LEN INST 0x00 ... CHKSUM //uint8_t *txpacket = new uint8_t[param_length + 7]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH] = param_length + 3; // 3: INST 0x00 ... CHKSUM txpacket[PKT_INSTRUCTION] = INST_BULK_READ; diff --git a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp index c897e620..06dae1d2 100644 --- a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp @@ -17,11 +17,14 @@ /* Author: zerom, Ryu Woon Jung (Leon) */ #if defined(__linux__) +#include #include "protocol2_packet_handler.h" #elif defined(__APPLE__) +#include #include "protocol2_packet_handler.h" #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT +#include #include "protocol2_packet_handler.h" #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) #include "../../include/dynamixel_sdk/protocol2_packet_handler.h" @@ -31,8 +34,8 @@ #include #include -#define TXPACKET_MAX_LEN (4*1024) -#define RXPACKET_MAX_LEN (4*1024) +#define TXPACKET_MAX_LEN (1*1024) +#define RXPACKET_MAX_LEN (1*1024) ///////////////// for Protocol 2.0 Packet ///////////////// #define PKT_HEADER0 0 @@ -140,7 +143,7 @@ const char *Protocol2PacketHandler::getRxPacketError(uint8_t error) unsigned short Protocol2PacketHandler::updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size) { uint16_t i; - uint16_t crc_table[256] = {0x0000, + static const uint16_t crc_table[256] = {0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011, 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D, @@ -190,39 +193,48 @@ unsigned short Protocol2PacketHandler::updateCRC(uint16_t crc_accum, uint8_t *da void Protocol2PacketHandler::addStuffing(uint8_t *packet) { - int i = 0, index = 0; int packet_length_in = DXL_MAKEWORD(packet[PKT_LENGTH_L], packet[PKT_LENGTH_H]); int packet_length_out = packet_length_in; - uint8_t temp[TXPACKET_MAX_LEN] = {0}; + + if (packet_length_in < 8) // INSTRUCTION, ADDR_L, ADDR_H, CRC16_L, CRC16_H + FF FF FD + return; - for (uint16_t s = PKT_HEADER0; s <= PKT_LENGTH_H; s++) - temp[s] = packet[s]; // FF FF FD XX ID LEN_L LEN_H - //memcpy(temp, packet, PKT_LENGTH_H+1); - index = PKT_INSTRUCTION; - for (i = 0; i < packet_length_in - 2; i++) // except CRC + uint8_t *packet_ptr; + uint16_t packet_length_before_crc = packet_length_in - 2; + for (uint16_t i = 3; i < packet_length_before_crc; i++) { - temp[index++] = packet[i+PKT_INSTRUCTION]; - if (packet[i+PKT_INSTRUCTION] == 0xFD && packet[i+PKT_INSTRUCTION-1] == 0xFF && packet[i+PKT_INSTRUCTION-2] == 0xFF) - { // FF FF FD - temp[index++] = 0xFD; + packet_ptr = &packet[i+PKT_INSTRUCTION-2]; + if (packet_ptr[0] == 0xFF && packet_ptr[1] == 0xFF && packet_ptr[2] == 0xFD) packet_length_out++; + } + + if (packet_length_in == packet_length_out) // no stuffing required + return; + + uint16_t out_index = packet_length_out + 6 - 2; // last index before crc + uint16_t in_index = packet_length_in + 6 - 2; // last index before crc + while (out_index != in_index) + { + if (packet[in_index] == 0xFD && packet[in_index-1] == 0xFF && packet[in_index-2] == 0xFF) + { + packet[out_index--] = 0xFD; // byte stuffing + if (out_index != in_index) + { + packet[out_index--] = packet[in_index--]; // FD + packet[out_index--] = packet[in_index--]; // FF + packet[out_index--] = packet[in_index--]; // FF + } + } + else + { + packet[out_index--] = packet[in_index--]; } } - temp[index++] = packet[PKT_INSTRUCTION+packet_length_in-2]; - temp[index++] = packet[PKT_INSTRUCTION+packet_length_in-1]; - - - ////////////////////////// - if (packet_length_in != packet_length_out) - packet = (uint8_t *)realloc(packet, index * sizeof(uint8_t)); - /////////////////////////// - - for (uint16_t s = 0; s < index; s++) - packet[s] = temp[s]; - //memcpy(packet, temp, index); packet[PKT_LENGTH_L] = DXL_LOBYTE(packet_length_out); packet[PKT_LENGTH_H] = DXL_HIBYTE(packet_length_out); + + return; } void Protocol2PacketHandler::removeStuffing(uint8_t *packet) @@ -393,6 +405,11 @@ int Protocol2PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket) break; } } +#if defined(__linux__) || defined(__APPLE__) + usleep(0); +#elif defined(_WIN32) || defined(_WIN64) + Sleep(0); +#endif } port->is_using_ = false; @@ -489,6 +506,8 @@ int Protocol2PacketHandler::broadcastPing(PortHandler *port, std::vectorgetBaudRate()) * 10.0; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = 3; txpacket[PKT_LENGTH_H] = 0; @@ -502,7 +521,8 @@ int Protocol2PacketHandler::broadcastPing(PortHandler *port, std::vectorsetPacketTimeout((uint16_t)(wait_length * 30)); + //port->setPacketTimeout((uint16_t)(wait_length * 30)); + port->setPacketTimeout(((double)wait_length * tx_time_per_byte) + (3.0 * (double)MAX_ID) + 16.0); while(1) { @@ -595,6 +615,24 @@ int Protocol2PacketHandler::reboot(PortHandler *port, uint8_t id, uint8_t *error return txRxPacket(port, txpacket, rxpacket, error); } +int Protocol2PacketHandler::clearMultiTurn(PortHandler *port, uint8_t id, uint8_t *error) +{ + uint8_t txpacket[15] = {0}; + uint8_t rxpacket[11] = {0}; + + txpacket[PKT_ID] = id; + txpacket[PKT_LENGTH_L] = 8; + txpacket[PKT_LENGTH_H] = 0; + txpacket[PKT_INSTRUCTION] = INST_CLEAR; + txpacket[PKT_PARAMETER0] = 0x01; + txpacket[PKT_PARAMETER0+1] = 0x44; + txpacket[PKT_PARAMETER0+2] = 0x58; + txpacket[PKT_PARAMETER0+3] = 0x4C; + txpacket[PKT_PARAMETER0+4] = 0x22; + + return txRxPacket(port, txpacket, rxpacket, error); +} + int Protocol2PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error) { uint8_t txpacket[11] = {0}; @@ -641,8 +679,10 @@ int Protocol2PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t lengt int result = COMM_TX_FAIL; uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length + 11 + (length/3)); // (length/3): consider stuffing - //uint8_t *rxpacket = new uint8_t[length + 11 + (length/3)]; // (length/3): consider stuffing - + + if (rxpacket == NULL) + return result; + do { result = rxPacket(port, rxpacket); } while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id); @@ -672,8 +712,14 @@ int Protocol2PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length + 11 + (length/3)); // (length/3): consider stuffing + if (rxpacket == NULL) + return result; + if (id >= BROADCAST_ID) + { + free(rxpacket); return COMM_NOT_AVAILABLE; + } txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = 7; @@ -770,8 +816,10 @@ int Protocol2PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t { int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length+12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); + + if (txpacket == NULL) + return result; txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); @@ -796,10 +844,12 @@ int Protocol2PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t ad { int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length + 12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); uint8_t rxpacket[11] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5); @@ -853,11 +903,13 @@ int Protocol2PacketHandler::write4ByteTxRx(PortHandler *port, uint8_t id, uint16 int Protocol2PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length + 12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5); @@ -879,12 +931,14 @@ int Protocol2PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16 int Protocol2PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length + 12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); uint8_t rxpacket[11] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5); @@ -905,11 +959,14 @@ int Protocol2PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t int Protocol2PacketHandler::syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 14); + uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3)); // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H @@ -933,12 +990,14 @@ int Protocol2PacketHandler::syncReadTx(PortHandler *port, uint16_t start_address int Protocol2PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 14); - //uint8_t *txpacket = new uint8_t[param_length + 14]; + uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3)); // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H @@ -961,12 +1020,14 @@ int Protocol2PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_ad int Protocol2PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 10); - //uint8_t *txpacket = new uint8_t[param_length + 10]; + uint8_t *txpacket = (uint8_t *)malloc(param_length + 10 + (param_length / 3)); // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H @@ -992,12 +1053,14 @@ int Protocol2PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16 int Protocol2PacketHandler::bulkWriteTxOnly(PortHandler *port, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 10); - //uint8_t *txpacket = new uint8_t[param_length + 10]; + uint8_t *txpacket = (uint8_t *)malloc(param_length + 10 + (param_length / 3)); // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H diff --git a/c/build/win32/output/dxl_x86_c.dll b/c/build/win32/output/dxl_x86_c.dll index c765a65176d1d7adba608dad14d56ab35ffa2a23..95b8673d0dcd426a3b1703900d0a40e4abd16d09 100644 GIT binary patch delta 15718 zcmd6O3s_Xu`uE;50}L=aqoR_cprU9h&3%|*E`S4~iK2jL$i)kYgo--jEp!G33m8dk zb+Mb8dCEFw8Y-xr6NZVFm72$_w5($}-p$Ok(D{CA??KQs`#<0JJ>SRUZ|`+^*Lz#< zy3W>lO5i*%sC7E@mO(w1`EfI*7E&3^oqsFkfe)u9GR!E}pK%@eby92X zNk-5onC-|g3sGX^OU;Xjk{unic^$)8yD-evZKRs*8+g#4Vb-o@n39!!dUlnqVVJm9 z9`s$yFvn2wj6ke4&qrPcP?jQ~-CqR5M3HTR&SZh0 z8~ZkSS`am8Bg)(T#X)5B-2CF%QyGRT!(0Z$z^1xy1@l<8;`MPNJnPc@!to;W{D-ln zb@l$`EGr}i@gst%x#V&2m#7&QI3)0bnqkiQdAg<6Eew21fWp3#-_W*42NP{Op<@Et zzT9z%P>`NUdUW21vgXcb@Z8d6JD!Ch;i#_+d7l-C$J8ZtV`-!0?oojk2JmbX>K1nY zma@(4aShMWJrCg-5!M&2hK0=%b~_ivFs?na+?*`;kJ(M0A;Y;WDG?7Mm%~*N6}61a zwMYE=o+i9ajd(K6i7hadSvot--K&%gi>P*tLEpIch|oN-HI?B$?^+^e?c?2vk`1ga zpkdT=j4Zopg8)ezpA;dvicgA>Y~YhJB#-mS2qathWZaICNHl~!&&Z_K-PuiEyTmhb zpie3}-siF40!}hScuGlp-@d^+xV!{;DVfzb+~IB2%<~WQHm5D8qlER^#r7c2yIost z_z$As&-I^&w$}H5qohLDX^1iMVad_kO~bTg zZe%~n0**Q5HB(Kt^zWv%r@cnIbG+Lw&MabUjK9+E9DK`bYY=(6(hhfbp!G%U_$uoT z(O!n}G=T+qGcG(6hI$TYefHm}k$vLdFHC#^J}X*w>?AI^F30Q&fkD`|6zZ;3{1{Z z_i4I=3kIK4?(oC^P=`~0*1<}3Xz_cX4uS1E#urTXZ1hM^j5&0PxJXo^zR8Wb-**2b z@T&bW>d4B0^3=*yq31Pjv~tFK?V)XB;vs!&oS~E3bA15Q{*>wN2Qek*`}GXE9lFJ& zQ)DO^)VD+M8@J2C$ehS-cii$2kVv$p2`m0IErE1={kvflump_+9~n6=OvU}k;+o8UyN|E2A-yC;Q{jMkYQ0nuz$Hz z*&ZmlEh{(2C+I2pq=9cG-%a}hN^a9iGh1y6R+#!*?;^hJQTm84Q!n_~&Qz=sJg2Mc zsO-%~GpiXH9Aotl{YCl{Sn))cIp1_z?oT%`o7o)LqWaV`LQ5V~Jt7Fz61U3O|NOIb z@ofm<7So13T+Wny)$6sJ8&>gk#m|!SsxXI$&&BYsQ-ro#)`*3euD@W>$dzyrSe+>T zKfbaHvYSYi<`Hzw4o%MhE0%lD)End*&G3Lcn(lg|Zjd%t$X+KG^u5R%`Xu(Zx(oX5 z0`_O(XPl2+Q>n2p-2kmIWpt+#Z&i}mt)cUc@RuTg?|cazXu;+zP)s-Hvlq#yW((3C zEVF1+OJ~}2MO-ePm*O0F&W@jr=XdcdXgYyDy$N$jQT+`Il7=>WkJfc$yRG^J(t+ZQ?kj6-iX$%A|RC`VG%ul_YDp5$RRKD_AG#l{_5j z{NxPw2eK=96w=}m!}7c1tx-;9Ki*C7=V22zGTh;W3$vS~+Z+2kyk4*C zdcXpUH*%S1JT_Lo-aW-pG(^0>^>rTqs^DK+`PXIsHEcrf$sqi za0$2u@XHdZ))X!{WLmuyronLkS|=5x6r#+#gql2;KfzM|Pi;>43HyVS zJ0+x20DJo#&f5{+iIQjn3xsC#NqD-~FAa>t8 za~ifzl3iYmw@hjMb$6n;R=T}o&3x8MqXTZ`w1RPk_r<=M&)gsI-2cpBI)^IzselWE(5p9$dDU zmPqRl@--5JwEnZ!oUd-XL|@rjF6A@l{K2a-M9($i$-vP5lsiM5<^HfT)9*#;#)H&* zmBan-v7sQF#}S9?yg1FBEgtXIY{j6ik({8a5B|hy?9JG^a50sW)oiT{32pIu=@g#n zHqp_)`+I@##$HixwkqX%)e^CHf!O1{35rZHqD#7cBwU{0SFrngaY69D26|8|aP1C| z*6*)MX@RHbcScjDd3cCC?z-3OJ1FfHc-_Ord*fLCCAi7ugiKBRE%yR(>i8nYV}b~n zOc$2K7Cuf$r*tJIFKc=f+d_)dRb*}YlVK4oMsY8yr|Ph@zPT#nR8`{DnuRx)d6$-u zgbX=rA@ec}erI;URoexE5UF*n^RN)=^mBvAj`5a`O@FkGQ0i{-RO}!&j3_c^2>O0Q zUdepiky#W}6ZR2pF!&fh=54FQHO5uV)>R?h(MkMyqo|{Ifuw4*QyY|;SA@+B8>abniIvS!nUYEQj;i7ZJ=rj4-MXptw$;s zY2&QL$_91f33>i;=0vwiMZLiD&qIK7Pv?4lBgQV!N($#W2N;U4!(?`hBm5edV9;#Fn30aYQGR9N$$j})grc% zg|V?8m!5ZLT*qN~@D*rwW+6;*+jdEcBy^A)u93K`P|QfyU7-+4^0LDGyQvOC4sm7m z%@Bb&$ERc>#9+RLL}wcP z_kRVMHAZ1ob_-o{FiQw|)sJ$P`NI1sKc8cs6@K9!DXvP8EZZ-w*upSsZlZk)a}@fB zu0**x%?aF6#LbPqZ5U7i-;~xg%yW<3h=fDA~Bb5O|z3;}CC# zikbmgZWvi4z?8=_o;R`4xYL|t?ope`Yw=ykrl_71{(`lbUVqJN&ze)u$Di862{_ay zz-JQ{08T)!_Ps={6SY~_;SbKbMFYF!+5GSBB;jXO@q90-sSY0;yvw|JQIUuf?v5Aj zjT2x($4kg~3a}w-v(+D6_lY~*pKM9!M`jP~Rq$7WIAg=_C5YFVnhG(H+9s}~O&lzz z;y&_;i)v>%4Cm(sZu5>a(~^)HHNRE*g?u-qtC=ol{K(*MK*!UitaD)=H9hxp-_(Ig z*Ef|Xi3@Prs~PE6ne2yEoLrnL55&nVC1hTAEbggOyE@W5CoaGdbazAN>l|)_)3%wT zxtCBER*p@5{ zYP2nat_7G0$ahn%2|c+TpKE3dTNB5+JG#eG$0+xCz$b;uaNJAAdMd;9Nt+-3t_;VYWY9Rh@8H303i)A5=lhMHBUFt`AN$m} z|M*!t{m*iyM?a9jCA86ab>c>!Ac>aD}}owosDnL#Q}6n zc`nV9cADc(CKMO@%hy5N%jDzY)JJdNFzeaskL^)8eh+IFMJ`>6g4b!m3ckRDRjlw7 z9-h2lhM9=NhkcOeB(Cf#8f_7UCu!|*T5BZvGbi;tgEMqfb@pkm{lA_k@vG9rrXopU zDwS77j?c{NHH+4J-bQn;{gfxLm7;`FNXW!ldj;D0q|fXD>{OCGdvgC#lzpIxY4mnY zM>5shbpl@5O$f8H^O4|E)ZHVk`)sy~WgSE?M?GUCl*V}@!1Fp-p9}S9kx%s$;7LzS zLS|Z-xeFlnq$A}Sg9kDY?)ibN znKNMeY4~a4MEqX*9unX$DNM)O?72vbn>+%L(@TtV$Wn2aXz`gdc!C4IBVg$cJcg9a z&GWCN-dsVB&Mgg^03UG*_a~F)MF&oRSLo85O31vZj@_t_f_Y}QL}cH*#~!l6y|^t? z;Q}GC#oILwSp`iPNvv(!kZH)O8soA*lrV)Qkmv21hms~P?Kuol6Pp?qqP)q|^L_G( zEt>r=`Q6r+T}XP_D|=tUU5-0Zgqy?W#0~f^A+9-bBQ6PH3{u9HZUeIPrEoVWK1 zh=BULBGwVv{K$ZTG(B(~iJjlC!!gL>*Qi3blgyi6DCj@G?!^2L*l-(ay!}hKXEFDD zmV2(^o(*K%!bdF0NTc&qjkhnqD6bt<16PYp8QI>9zR7pxMaU2YxlQb~QP(SP|jl zkA7~?A06P6P7F^N1QS-1`A@`B#&u5^1<9+)&nSenp{0EVvejg4Y1bebCv9Sf(AA`* zwEsh)Ty}!!Q@(t{?xq9Y{>x!%onrlmtfROdp9ujKKrOHi*aW-}90NSSH9*|JFx>z- zkN}JW1h|?F1)_nUc7g}67Wg-C7+8$*X+SbS|DHjcN}v#+fB$Y^vYErk;P#pOd)h}R z-+@n|fNOvUI0$S7Rsr*YNx(>e{vAi#Afzw)ctrZjCzLZX^0Qzd5jnOvDB<_?LI3=m zQfCm;)7hH|VLCZgPAxvW(mMw-L!D91zRXl-0aMJ(a4uw)I2SnQGO0|4GuQbT^Qdz) zV`buwKHp<@`6ZmD%DX z`1#543iG0~lBsb%gSJ|J-z9>7&9%sKQ+sA%d)?D@>8^Fn6Dd1dq2Qg%^U zAv?2ddf61VU)cb52s@}OhBcMx%9N~(?dm8CFYCbumvv zN$7SxEvyihxtxM!w zf}7>Pm0uAY6#S?ByYjCEpOk+l*dy3oKCC=RFiJ3@e1agmJhOb9phRFVca$#{JYGIa zFikMIJVMaF{E_m91+nF3fm)y_?;81XEjl_nB8XwK((-K)R(vrRkvVsUEkFCtT84aH z-qR7pWTnoSHGO!#EoJt!{L%KA*%9~WN|`cQ33F#po;G#zJR5EJKyoH4ekxV%-h>Wb zUCNiq8kaw1_H5g|3ER^RE6$%hH^p9Tn~`pxdmqN_>60c;wZTv0^5^B>&E0W_*Qn3N z$od!IVF6=5As76N5{GB9-RNo_zrp>bH{zg40~NB)kVUl&xtjRNHEX*%Xvp!0Gd{RTg zo(j#TpG!yE@)z17XU?KL=qJ&~@QR*6Ka-Bs&?3m=zNC(p%cmAh$F8F_KWtoj0Y4n|Bg$2*;? zVOHW>aC|u4`Z+gz!%N{l?~a_ekpIe?>wpb#C{Gu;c=6(CQ(yuUwyu@lHZ^iYJf{J6 z);=Dz>@iMGjcVx7+_-%E&q_X$!M*U+j*4n_*};eLz1>!Gk#l6Oa4@ zyVMQH;3K)zDR?9DozW;u#+EskVd$s5ap}mhQ%hP3KJojgChx-V`OM zO9j7(Y2X#ZqY*qWgFXT>)*6v$913D|-R1FUfOIQTk#2UHg7icPr*y;6 zHp_wbU`|mB=gHtyIh-1y2Z0YXeG-;a$jq?D*ORGp&<5$XX%IFSKzk+uMnHfZ0%Y)7 zNjB;;Q3iwJQo*AbZ-ja+(s45(!-336WY!{+hj5pVMZ;NOhO`rDC(fy2Nl;2I!( z2mRmc9sE}mAQl(_?7O=#DM-}iq@H+4=@IJ5~_!9UD_!YPXbbOCt zx&pm`{=g7G4H$t$U<@!3$O8(262Jkh0M-B-ft|oU;7i~n;5duNRe-5um@YsB5DgfC z6krOl6nGw32W$iO0*8PTz!~5M5VVzHdIFI^G!O#}1I7SZKt3=Zs03aD-U4=PWyUc3 zk@y-o58MJeY=ecsP{0hN0#krFKpC(Scp2CTGyop~hk@h3>1}n|S|>~1U%7eU?K2KD z^^PNt;;wvM{xj44>h!Co`#I?H)B5*V15&j>eQOCsqO2HYvUX+6PQ*FN(%Y3qpsW#P z)7q8Ap$uPNGXvX|O+guMq?ic4ESQt@60Sp**RJf-?f>;HP1^s3TN=`F&G~?Ferd(| z`6YEX*1RcvZ~X>;b_03q?PZRijV;CiQ)g2z(?FBLq%~!l7MPwle{J@+Bw64YIkpQ} zfs5o7@@n~N`PcHR^55kliml2|m0v0YR902CYP#wL)e+SN)o-f7>S^jF>ZjDZ)W55{ zX~Hy%HP35a(G+O?bynR}U7_w--9L4kb)V>t>MrV9bUkATVuvcEpd*z4Z$K|KxSLA=l8O0-t z7)632U9nElq&TnWs8lImQ1(?#R84{3oT@5^YK>}xYM1I))ljugovD^+hG7LPT(fy$djERcT$2enNi8&b~()ZR!>Zj>#`X%~m{T}^K@RiOm z&9L0?jA5PO4?`gQR33XZwxclwUP(93GTMw!8;=+-8m}5x%$DT*{j zg<`GZ4aF%1qx4rMD{acf%FmU*BR2Y|#=*2Bs;^a#suv(GzEF!a-84NlQJSHeX_|6P zwdS9i-44xO&8M0pnr}2eXwGOZYkt$*(ulNTtwbx+hG;{zVcH1oIBk}8vUaYPXoGb_ z5JoF?-{}6OKLm@bVCxHri=BpphOZ1443gN1u|=`VW9y8Ej9(fD!b+RzInx1Cpn0I# zX09^7V1Ctn!Q90XZ%MHfSe~_PwK%R(3-hono?IMjbOD=GmA{F98rpJk+c*C!ibGn%^*QHH$0}mH`&EWtnA*rQWiS8d|~+XRCa++zBJ~3P+B@rKnQ8 zs8A{sm6^&(%0lHVVIlivD-Kzz}5UW(YS#8Xh*N4Q9h=LylpV zVS(YeVNLA8*l?rLm}nepoNSzHTxER6xYfARc))nns5Zr$3QZ*#;Z3G*O=nFvOaimi zY&IvEv&_@Y^URCP4zt_5$^4zU+VYmA&a%gH$a2);XrXR#a{m}sJ^&FgTK=+pEn<8( zH;QK~7Al;IX2ns(2}KuWm~xO(tu!f9;i)N{uV}nGl}{>{E1yxWQm$66SH7*>uRNwa zt(2&uRcWf1Rj;f5shW)u@V0t~dLPC>yvCu~rTI>C4WZtDs5V+_(9$I@1bQ5kixgtT cC`+nkf`wVjmnB0?g|ZTiHz@12l*-xv1=Y8NZvX%Q delta 13556 zcmc(F3s{t8`uF?Ja2R1^MjaFt6%>yk&iTNcIID?B%E2RI3L&B*42Fu%0OA58F8P?+ z=6WbAH7g7gtgJCetkleP)yi!tEhi62>MFMA{D03o1Dfsb|J(2SuIroY`n}KZx$ozA zKlgKb=e1qu*)H?yY}U|2QG>J3r%vud{@bmSmm;27otE@07iJ{oaN*NQOSmwF3!6sm zm`vr_=hG%xPh-UD`H=7wXRjFw9Cw)NbkWRYcAv`!U-XW@jJZZBoMy?Qz0~VcNDZOu_S^0|QgG zGE8(=88ob8n6pr9Kb7ONQMnz!?{)P|BCdwCEJ72ZSM0X>a0@AQCJ&Ca5gHwMGOY=n=qj^j=`{PG5)v0uWBsBx&E$pbpLDS_`}N#-!ib&IdP28az`BZs z#X-(jIlZ7dLD-rgD20B`PjV!1*8W~T0P+*vKa@vHDNeU12=}lS-zFQ)+`NYeYTe`J zUf?I(Q~-M2O~s(%OU`(vvD2F zEkOpSO~^1*oXcep^m@EI+0dOJNue|S)45D&q;o$x5IWRdUjt5D~w zQcv+*r9#+BQ0(X25!hwbA7uYZ|4~qvUZs3eFLoDE+Mg-}sFDXS<5;&vN$JoCo<&9W z4PD0jQcLCx8zH>UC8sSE>Bt|4jr3O!pt)!lW|LlHg8F!h-Oq_>vES>+^gy(e|2JT|>L{;=0EhAH-S-bQN7f(RXX zDJ+!m^#jNQbFVQ^W^fftT*YEfu5@JUiIyN+qK@<$9!e$-4;F6WtU{|jq9MzM2lugZ zZR4CXinbDr6bzI2b7HQqdh*fm5yF1m8I4>|XC2{Yg-PLCUC_ zz@i;%IV-r^(Zm^$*{)!^ODsG!`#`1Jj(XvW7&pxwUpF{1daf)Bcf3#lC&>?hsAh;NCedxvZx4P)nw zxt{!F0bfJXT>wae(33kV@_F_Haw2j7>mXMmN3tzMG;RW0LZ**90E78SR}45o$9{4r zeAeEoI5{`dnP5QaSo=?qL1W`a1}8mPmmehEbsf86_n0TL{+oB&)lsnNV&NjW)`_K)# zp3OvG6epdmj(n{c$2+Yh{z}8}%Nyx>-z4OAfTj<)m~p}#m#f&+ROi+$*hun~!Pd^_ zxs+13@FEwhbYP#L+XISd;w0R5;NH*pzq(M2z&Q&+N-o{PobC5rE^d|Va!-VCk(va- zlRMS#HY)3$|9Yo-ET{5tV*6mS5cPp%3(9k{8 zqZ!$)5kNtAP>&*@TOo#m?x!BbKRRgVX(b_0(B0LexY(`u?Oy9qAK}zq$asSEP>q9g z>Qn=L57O;*eg~PQ8t;3W^1zOUy{frM049+|KvK~m)<;$rUZk)NL$1(-nQ0C=Ap|aviUKsm0n;2ZG*uCU=pSmv_de2O%0hC%)sa% zlYot4#)1WbjkFDgHW+NaEe9+FET35jZ5UVyv)a~btsDjVoUIV*2(T0;4QeUaT-!{@ zlwgx=$zWQrcqRr~16Z@|7-Z34CzwwmiwC>F{0(dZ*m>I-Xp_L&nSVf*0_L*)3Rx=H zHQUc%)4?t?*6*O64Z4$g6)X$vZQDMm7l6HQ`w%P_>>zUh+I%o#+YDI&*f!=x$Sh!0 zOf6Um*dJ`=(3XN#l&xc1D{Wxw+3K>^%C%ry**}9-fo&<<2<`fZE~~4aeHX$y2tO)& z55i4gZ(W0I&`)Tt}hq1mjou@Zp3QIw8MD1)LBph(8ES0M@UfH?%@9DPIMd7|dJ|1(^ga zydn}T2rP^r3T-f07C##-1Z-(V9<*U#)>Rd2Ku3XE_{*S<0Gn2k4w)2eHh%_WO0Wt1 z$zWQr@fESq8o(U*5H=OB7^QTY-C7Z&j5 zL3%NSHylCRxbiU&Ue=eJ5IB`Q8HCsSl=nrfJ($-Yu{#1@PXryl;EY3cT2 z;rm#;7_7z}Sel7rQh)2($#g{%H99J8vc+FvJ#-(#csSsxXcCHX^Dn}Cibo6OwDb)7YC$f2Nt4Hj4o&e99UAX_^gDt7@!HDHn^?)JYda9w ztzS96!OI!Dul@6CPJ!cWj(xnB;!I9;CDZP5edvn@*Npe6s^lS78}qQb@(waqI@XvK zpNfV=Gd1xd->S7LT44Pk252hz%-tAtUa#?$(9r9Z<+ z_U0EACq?^D3##UNSB>|Xn~5!Gmh(eghJR->Sd0#Z;62(iGIsJh>#l>?2rI4&rrGBR zY=$7lGLYLEYlVM93MTyXS*`I^lAunQ3nP+VtK`JTyn=2ry147oi2-yzAn$SqvW5fP7~M*1)@XA7=T3Y9E?DY|M4a|EIAcNeMOD;t5B4lH-Hx??^rd#vDCH0us{54aegsU80i1*fFvG0sUyD{4GWFCqy7QKO3#Cd=7Q z@@n!(wu78ZRO*iuIL(LI5lUN0|%U2pqk{!}=(wRq|Wo z`I3GZD7WW4eu@onpJH*)shKRqQK>pnXuJQguxD$ca z31bm+zIV(^%h2@)Hs{7-;k~VBLWM)jKL+PcaRo-84bWK8UWb5x43Z$X1oz-nABjE5 zN9?>f6sr&&NqRqThZvW2%!*GSrq@~ShU(Fa*K#*c+*iG$xvMC>wY#tD?rS@)rZ%*| zeShalTleQwop3phfr4+aV z@fsSpbwQ=03Etrn#UIb$|Kgl-4(^Kuo7oz_RWkmLXU5u%bdrf0@4{*o4+B;UTH|*}5}{R`sZD%X zoz_vE(1GQ1kv(aLP~oT}9jReM%%aAR!`m?-kw80geb2q5Ve0VDWmLyN{L0A>@FXy1Z zIhw0LLT@14%K>-M{5A9Ja z!J9-OdQ1XlJk5*y2bnjc-{6{4w3C8a?p~sQoEy+RB?CJyDKG{1=4{5joyEIZk0g*DNFszl5RiNcYi zKU&lu+Yyn@>fd`#Gy0T=x94~*C!{O;5z=Ok?Ek1wkKQ;tN5fgjpTmZb#OP7z(9-Au z>@-pntz!R19MSZye=|CmjUmDqdSjm(GnAc0%43XF8^dX1B3Ky-j(rANYpk3NC-1~Q z6Cq4-S!6JZ?6JkX`+iEtgLd4jc9J)GO6F$iL;KT{h&`Y-nzg43YLW!5sw7?ydZN09 zK}mO>xk*anVr3|HIhKO|=qA`2a_n;?Zf_y!S@EP-yhPHY_$sx-saxF6;IS5IJSVZMxe(UCVEzD@p4-Of7N7bhHx&zt$*~? zmL{o=Z^XLb^|1CSUppvyFFVyQgr4GTba5iRa)NnvSIM}Xq(0^N6X&<@b_>XcoB{NW z%)XpqVUJ$qx;Fw1U7bCL<}B>jGeO|~gJ&8%Qb^diK32c~&^!LW=-rF<@mg6wp>J@g#Ms-y1N4MZIR{PvGJe;}y3^QX!rK5PXvyIO%YaN!5+>2Cu zfokK)*hRAk{(`-{xn|B4SMeq1I&Y+J&J*TtrS&~eb}z~rw4Cal`;gsLeA(HfD@7Ac zAt9mp$9PLh$WQqr*hNIVc;4_-T6_;L#^DN#2E~Czi-23*%C3i@l)Qer^zFzO;6}fugSkIZcSCIG5mwhFkb@N3-);MC#dQ?7&~Z1J^och+cqn6{Kq& z#axP|Ztm;M0l9VqiJh~-oEdl^f~D1Y6&8Xeg6MxP#l5l4Vhv7l6_eFV#nzk9&6t5d ztKQ=hS%kT%I8He4QgO4>4~0}ZL~Cy&N*i&HihueAPn3&4cJUYBG4Fh2V4WB7$Gr1A zG-#NY+<_85b4UD;?<1P;+E4W?XN`*MLb`iZ-nDo~R6JyhOPwa@(d98XOUM*p%zwSQ54@vPTxINaxOUGHcn$fWg$J{_etj zyh+`%nf;S69JnVaaPCRybOla8R7OcW;TJB5$U;=%h@SJYkjX7TeXhXSkTi4L`8BGV z(cDx5d9!o=VL}Qc*=ywE!lA5<{7_iM-Xlwjg4yZBUNnmH1DLy~=uq>$3j-aY-ZtcN zFI&^nKg>t_-_L)ETqp|jwNP$(iSRAM0?(qduBF8t=6+sI6qa1xoRWq=TRvj@=OTq` zcs}Dr_)ukhmo9rsQTJ8o|oPH)=!oG_%P2Ct)tPNhhd9uZH{P-V>phA zOlr0{fix7Vcjdg4xZ$9_2-`j{5kNRrt z=`CbMi7doZ6aBh_R_v(>W9X@gd{z?0+q#ALtkBbf<5n1WRa;2eiYQv!krhLEDO<>Q zD+2vexY}m)oW5n_%HjQ|bFt}OC*9)dN1IQ$hF8Hx4KXXHvR26fh6w>804?wokPa*W zY(O2b9jFIB1TFwqfx?3fvku4vUIvCpjaQYLx!!V-&IY57z2y@?I zW-x^wK_n8>-)Y1z0-GBcrV1zkQUNW{7wClUswYn=!hOI7PrStwZe5F&^A}zO@mhU= z{~g0LIIQbgeQNH)qL7^8CG#x{mo5nbUyxl;m_2`L$g|m&)RL(sQ?rYT z^DQ9@mlRpD=PmGKh8OvfNoDu{kMd6~Ntri)QMM(auyASNqaqsO%Aeu+<;+`{kGdiw zL&%lt5&X9 zn@<}P7d0D}DJ+_ul0VOqv$SyW?D*`WMV6%n++9@9+ZG}zG| zm(8T9oxhQ#aOtj-vh{tU+JB=-0`a^-?&&|)U{B~K#?E%U=B#&E@A9dkE~lg;FcEqGj(>Q09>?oql_cRK9p3_Vdr zmT+c*5%Jr`By(SfMP|Fd=Gyr-!>p%?+_sd{G!gY~H}J?5R2B`{V>VY(8J*aPnPF`B;wmH;;T(LMHVzv%;`IyA9DMV3Iu+q^OkZ#+cRYu<#tkt-3dcC+S>`m9 z?I?uNx{-o{3aAWL55fQYDUnDVi!bIfpa<_l+gN-$=Rq9`qmUw=6^$?*>5Z8nwbRo zBJ>|T1$-xXhzxxP56OoPJY_QE;B_**Mv)?7L!=D~2e^1K41!TjNk$@YF}M`m2A&1p z1}qbX40=mKc_jVzdj2Q91J4 zFj&!Z(Lq|)c<5o-l<6qbiXNR#L8JhH--bMmg2C&-3&7jK#qeDRc=R&Jz{O~N9e6u< z0eCxj7Hterhw^MwkbVgO9)hxMOBv=fxa=9=Yv4!V4#3}y*I2#r7zB(4R6qid4m=Ai z1ImH*z@LGAKof8bI0O6ubOMrBF$IBGAQ_kinn?qisK zz$icmBmh%^xxgZz1gHcE@G@|~ipLS)GvGXM31|l%0RC^_$N-E6R6r~+1(*fo0>wZD zuo2h=>;v8djsl+oUji3^Hoyt|0{j#3-j9_ZkO0t^k1OncMBLiarBQPGA4lDqc0c(INfBhxk8pdwP^0pQfE?i>y&8da?y-4;iWOBFc(Shm7xF^%21ahVj z=P6n23QP9X5)W_Ku`SKpO82j>->(P2>KJCvW3r@o;02I1Jto`P02hO-^D&tNvJW5= z(lR{1HpuYd7<2lubi9M80RlME4kxnz-)G_}|BuhaB64e@Me*CfNkpBH0~zPengPs$#L?ImJQ6NyT3j66IK>LTORfDK{(cD8;J2 zsvlMB)Gg{uYNuMF3D-z9lQij?C7M#rOPY5zr>&ZE8h@=yJ3(8lt^uSYdT9gjL6bvf#G)PpF2K3!j-uhtX& zR{eJU9{mCRhx%4M-!Rf(FvJ)p8>Sg54X+!H7(O&lqN!W}0nUXtJ2fOq)!*O#4kAnU0&jGJS8lYZ_<{Ge?+X&GXC!=3;ZJ z`IPyu=1b zRO1q(#aL%-F@6i{_?S{nOJJ9srpu;>CNHzvTxC9JevkG(1sgX4ku*x0Ce1{@&q{Ad zZ^J)~vN)MVRx2a27TMoqmt+#TRIZj=2n|T+{?Q~f^HVh3Juid2Gt$kDb zp4Lkz(GAj#(OGmGbz5~0t-7$Nq^PM;&qTc+^=Z_VsG0f}{kQtd`VM`V!DNUxWEyrG zJ~Xr#+6)q7q)};1H|{omh+%0rDox24mUVE^JEmVvOU-{Wzia-`{JEJafHPvMrb-t} zi=?}yN2JZtJJO!AKC*b(9NB!?CRx4gknE03Ebl9yF1N0g*T`M+F^U95vSOCvXGI@n zf8_yXi}D+kCsgRddL5NHTC3^R-|$PH13SVOWQ!!Xmd)2E9E+QCOlw+{2O_j{I;A`1S>`=-c~dz z9134$U*#a>H05mNLacAAvBGUrzO3A%d`o#y`JU3DJf=LMJfpmz{8o8cc~z-XO;Ba1 zN>$rc%_@I&AN4@>-_=*t12m>1?jinwy$%?G$a!Xzdd13)=14eOkKPg`l-(rCu_D bY`wNlyH#7Kuh*Z@pVnX3x9jnuM#=sUxWV;Q diff --git a/c/build/win32/output/dxl_x86_c.lib b/c/build/win32/output/dxl_x86_c.lib index 44ea10aeaee49c65309908305e9f7d5608957040..e26ba9ddc7069d739894cc4197c9b398cdc88188 100644 GIT binary patch literal 40738 zcmeHPdyHOHwO=iYSP?5?#fng{%0tDr%v4&dmbTCq`WR-W4_=*q^JqITof*FQrk(OC zlv3WM(9)Kth=_<-Q4y;m*K3S1gm?}2#+&$uFenzjgNG?6vnk`+kSh z>HX(UvgSK`?X}i#@3q%{p8b7i&a2gXHhpQ*=cdWOnXRpJX3uPCozo)uGjwv!j0OuDZTN+v zzBh<6T8mH6hD#OozDbl(1D~Kx`xW)0Oib7QQBnWjkp^8mtZ38ekOTGaP_*$mqKxL^ z6SVn|qJdY4GFpI7&}NjE>AKf7t-~j%?IcAjz-M{@_Lz2WP_*kDBBq_cQ}pN<5z`~n z6&?635z~H@hv{KpFzx+=q9@)WVtV{3MK{9^(~a$lZbH48Za6{F)?0~~#^67uEwdGk zpk7RkzbM+ViHK=C+K1`3S&BN>6ER(mx-s4UjH1ZhSF+GGbGu`=n zMSK26#I&|s(cO4vy5dS z@fnJ?-v@lq>QfZm4f{-2|4PyQJ7E{pF-6l6e1eARibm$4JwR=@C|ZejV%mc;GwnwC zn0BEYOm{3%^ynWEKcGjzV>-A<(SEcm)5A|I+Sf+J^yCUfPn?K20^I^TOgFx&=;n!t zC(sRB6m5MQ@dMg6L(!IJ5I>*>e9JV7m|)t0vN7G-t?0Ich#yer>xwSNC(};&nrYc3 zidG}mn3f+=bUi+qhF?wZBFjf$r&5bS28dbk&%mYo13Ofw~%s z+Wri`f>y#GOndH9^ZrfgU|x(Lt1l=>YJU_Mfb1-_PM!(38+( zdII=Nx4f+Art{DrK{pR7y5TMO6*RV1(YD9oSI}12V`}VDH2NC+3c7u+qFeFIw1X6_ z0-vcJWoO!1SG4R9{0drwdNZv++c4GPH>T_1Bc{ER6y5bA{0e#ywwdl6R-rj=qMH%XE6~c>5uMH=BvXKh z&ccDdTD`4SuWk0q=VnCo+WR&SZRv|Cikyh%MZLW-wVWN%@yZso>Y93gqc2i@kMCK| za@~5`C<$_+nwx5a8v_?8RW~c9E1V=@MOI8V_mou3`7tfWg;^1W4?DIE_Jlnn;5v3q zo{0afJkgwprrQC8qMH%X%e#Qk%GnVeFEmUMb9O{02n?g;W<>Nv`^h4@eI}xrH=t0< z*%2Mxtfp*1t7dJT*V7vI_?~4I#QxC0AVE%4(+z(KxzNpu>Bilc!HTSyZtf`wn)72? zjtesw3&nmaxw^0|R z9Vjy8OQ^!;GAga4w(>yPvS1sJmTbvShf+%0l?&|6^6WWj$DZao_5{a~oaxzf(xH@N zPs;`6bE>Ky9V@0)vI?4n%CDnM9anitPewJ1R^Wt}&%xnXaPu8^v4oS%ZDdS?VG~}y z!O#|549A6x;Use#8Pj0cgqLqHv;`MK`IgPQUgoqhD*a+i@ux!BQ0r+7)wi|xjqq|w zrj$evk4ei%2O9mIqxC`R^3$fY-9tmLQ14Tpio3C|v7kOw>+PwHG}`(HHv$HR(EAJc zN~_ydK?j#fB{K|bSX3?_>g^j?F^ZK`z{urPrm1nmSsuF2O1^FvborCYY1o|nN#&q6 zytr+L+q0_W36&4mGHVSF1k@!{*1|Hl$V{jg*X!79vX>%Up~21WIF-d+mX!@HdmJn2 zs-pmIQppTwOY0@I!QO#B6w*s7nf?*A{_X7F+&46e1`ilY4!#hA%RBn8=ZJIT8lkjl z=WKXs8>$1{c~n-ohp4RlN#&r*3u>di?KN&Hk+ArAJ_?#AtUeoFQQNHa^MuvUSzJ*o ztn#zo#Z2AN)T7B88tF56_EF^x4fhSIto%vk48vI7T5dw+qY$IRth%Ouuy<(dNaj(G zqa-;T(4ZatgFSs6jhdrToMSZ?j@IjagP8#f1hp7j>3AVym5TVbHbF#L)mUKJ%(%YI z_H}KB(z79E`5{M1nuxQ40Yk|-!DmHdJX>xPidGs$4tUl!w>U?sm4@wrXKe>L><-_8 zlC}|SEr%Q#IzL*7)ow94{s|P<0)xxaXB+sZi16bwr8`f7P1MI?=3JP z6moJ&tDG-7EmFRQY##&DODY>Vlh<8BN;8yP7J+s-1-XC`%4q|xWN6c_myAu9;n>t{ z*QR7SvUYuBY`Tn4&b6r}!*cTEWz6Yk$C6rl=J`UOJEiM7KdtOou5K*57==|&qEj`e zwJIcB|FKOso!iN{7Aa485*A5Y5lF6A8OcrOb~3I-%2S?%MbcITl6E+Q2;Vcqn$8|_ ztJYxlp!n{Z6aZdQ$;dS+qymP);MFPe)iTwV7mMKjp+O|=gOca*)?Iz7r55B0GnAfK zvO?TXD=BZu3b~MzOX_TVC|<*^W5E&$m2cLs$aNl#u9_q>P5Y?wP&KoFMYc>S35@-A zJqr;pX{`inS7k277CIa)uA}9m7DlYJSi>soKFiAbRz+G#dGo=nU_JmRmu$}hTMOBQ z%J)Wp2!)(n(kkckfkn#4`t~s}y`-{{GkFLTQktRU+(A9F7BE6NZNQZbZQ9`q*qNlu zaBOO}Yg4iuSvxQpn=T`ib8TwLu$!U(E-$ylNUi(mp8p_^=PT!VIM+#(#+W zX(i>2{*Vhfxunj`x@r>0H0`6-%Z|`H8lxLF;LL?x#jm0A zw34dz_U0^+Q2C?7z1UJOY+p!S&ZEk6<`@(}rj&#`#X!VMS}VcSqRhqELWko~%{aM& z;8|%gy(nRyWo3m0)XGhlzqvEV-rT_}Y}&P$=tqU5e*7@m{>a@5VO~P3kB5MIcz*plygvq=)Q0C3kb404dUg|?gZJUT+lhDOj}lFPgy^>iU}ryc9wz$3 zUZS_2AbRR?$lQ$g;5P#MCZZE=z`OFTC?DR#&&K=fLnB0g!MpHHJ5ZnPM6+;5X?-W~ zE+=~CcGPV(Y%Yh+^{5x#f44kD^!q!B{)YG4-FQ#`x4Vg+y@KfYt5Ei9@Y#jB4xv1Q zL@(Y;G#~WK$B>5Y=T;F-g*@LoIrV<{u^sk1;19_E2Jh(q3f^wKkAHg&?hQbH`h6%r zXa?$VAM{T_S$0AHSJ2-H*(uOH0;)rQ9_n!m{4;wcY@=+yfq(YFKTGa_ui>A4@Xw-y zs4M*QH2l-H5AXhQcj83&Xvr;TH~42F{ImuBc^m$ju?_Wyf2P7W>qcP@{^`CIZ4Cds z4*$Fk|4f4KFIfh^pL$UrrqF=*Dz4yS*m1rmU=y~|40U!Mt zWqlfDy$fZX_W-cr)59q1YWV7Sl=mf+wHNJqGRpgNl=U#mI)<{ojIy4Gb{s@m-$Gf} zj^U0C%6c-&ybEQ04P~8+c6$wFu5in zMc2~9^hLUZUZmBuf!5GQnnye7JJe3y^kuq>zE4-vCG-IOl$Owg^e?oO9-^O7C-u^$ zw3q&suA<9mAN`z8r1#N#>0R`0nndrR6XCFr783g z`Y@eI)97^iIGsVK(Q>+m*3u?gMhoa(dYLYwd*}yr1@+VCX*)en7t*ctEt*ZY&^M`t zZlZ5cE8R@b(FJrPJxeob8$Cm_=mz>a&7d**8eL8`nhQsMo4!D|(;=Eex6upqCE7*b zrL$>>9;HvwAU#4qrbTo=9i|TIp~bX^UZs_^g4R(Nt)f1XLuk5L<~r_a$=dYaCsE%ep@ z_x}H>_m9I0;2quJ(F+G}&+9FDB6GP|y_n^PVA@TZ;9|a1lcW3k*5~A^_8qU#Tchrs z@Z#Jx=dgtZhi}cu#h|ewxz>neOB;LwD%6=_4<1#`dIr3cddu(x-G!_%>hf%fT&67# zFF@^k3%dj{EDwr>!($Bt8qc-x@ocvs#b^4^HD?PBnqj#RhUeN1)^U!FAkQ@xWcpU~ zrI}|k&+zT#Ij%7d0QK(2wt-=VZ6H>T4zS?6xFW-aEqE@O&>;|_QZze8+;Z0 zeAHm{_}PvLoUlWIcOc;^AR5eV4591rb2IsSI%^_ldBwHIQt~c~K83Paj+n)Y62#H7`_^-qy#ap{iGGEf>KJylq7Vw!0i--$Yhp%$5LNJ9?gwHSv7!m7h!LHdjz; z&(H2fDerxhcN{4X_;U<%L6H~3j(c6U;~>L!OPTW``ob5nL%+H=NSkzSOAFXi;N;G% zNli5zme=v!V?IZkmxkGxX<=MJ7fMaw_7ajB=pZck>dsMdURWrh9?ACBfDEWvp>Xt~ z%}8(=HRt4&wnBN8%^W9hRkE_4WJIKRd~2rRHLFQmXv1(c{MAy!uAdw&BV_f0qu{N) zyVGwE+%2BZw?_R8Yue4oBVKZ&R-CBMr1iiVl*ZvpJ5GiyjU9qbFuV4haY(YI4L$M& zrE&POG)_j;lII&cvPP}=zHvv~tkjVqH{;8IbXXF`zJgQTQOkKn6yvHDLFMd0hCRZl zxo;)JS%miv2E`EBu;w08jvCPi4hr#%@$p7#THNGh~19Nu~Um+=er+|ZQSEjAnQtgI#Q!dPHfz)ZI$J0 zwq;Jd___JkvA-6rvY;vi~JlU*axzSZyT)nx~+uC45>oL%?JP!KSaK2X+ z2@A~I481>9S4Hy8s*?pvHpLqaCjnR|B?WmpbTYGrgGg)fY`I~Cbwb^H{hQiBJLR#a> zjal6e0OpBxG!wS58Ob+bPQr#Rcy@y&Z(6{Ro2iV6y-+3~IK^M+Z~=vi$gp!Pkj;ea z3V7S65j`Gr8|KekaGSx!Hlv(bm3j; z%hR)Uvc1{U$?K&0cUB6~!849&Tqj`+*=>f-vyi%9TlTEf?;O})Ksdj5U;r0-{ zX`L}s{rJwb^^=xOIF5Gw$A4e_0o-3W0aqjNH{tx=zV6YD({Y1D{Vl`?uA7Lz`80XK z`Te~(0hvC_WSoMBe*^uOW*mpl`84BaT5h&xn2S2=RXY~>+l~Ja3Yy%&nL=?yvcB~3Nq4hhSS0_VBq3~)@sc; z%s-3&=|8qkxK5G(O~i!}{4~Zpd#RrIVT?(l(oICntkzjh#7xX0<|incDsntxdh>c@ zPfo;KV6r%3zF`vjlOu-hjzc6g)4CrAbm5PUl=j<&uHRHo`%eI*{Fdlxt=dId5OYs+ z|D2xIV)z`m|85fc^C=k%y5)|@yNhy8JkB~G8HB3i5Y!8fm^P6yh%0<@VP zoB(fPluDt!J3yON5v@hvgPrEpZ7S+^e1>L^=c*zl;)Cx2ItPKi3(LoR0_y~cwv(8LHw}1`B6z+t1$;B{Xa@fX-uohWzC%mnC3@S5 zjF+9*=D(mI?8_K!rgn+edw+=LJM*YU%Sj=g@66J8Ev@m9@}r2B4_Lfx7(1@P8LW=>d zjcVTB$u9p6unOXcN1Km(Sbj5#YBmu)EeWjCJuJWJ%3`$^tZb*FUT0{m;5DY_%+i zQPi}VxJjUWHbC>6uq;~2ljmn>;_`_w{|-jc#BA}o0L|W1sEV3cH_ix9oy!hYaTBY6 znE|f3IU+$ts)^`H^~hNPrh6|%AeA2NQn(icxbC%)YPhL2a!ZJ7-s?)x(&JtVwKYJs zS9YqRCgON@1l7!DvN7L5uT6|dpBK2Aq-D zJM`@mFNn+6F)`D9DL^X-;_|485#q}M>am&W<_EarKhs?lU>=*9Zb5)s+-=InZ)(n2 z7~&p-nQl>lTF_OGY8+o2K|K~T-6aBdyl1+_AzHy8Q8tcJNRp(_I!K7j&PpEu4BQyo^!(3)upo{0b(uVp|@;J38k%Ed?h?r(zYcf>F&K za&IaZm2G03l=9|E7bjk=(lL`-r?fHNu(%2@s#Cu0S_;naaxJR{_4frYOMjH3^)@vz3zhwD77%04XE7iL#=JuKXyujs|pEyDEy zT2()$&}so%Wltu0bhkmvzGzY1kEveP<6%|xVhXF*!x~Q?_6e-=Ntnu{WMh~m9 z4--9llZRD35>tJwKR~PM#}wMN0a|5GCVKRB1}*ynQ*}S4df9-7Rn?0rtj!+Qc=~Wq zV2y8&9`dlp(}%+zR%IV1di3=kR`p0s^|5+@R@ILww2=Up>T)lQd;hB_eLSLdt$& zK*X5bbTu*hr26TtIZAcECHm=YIZkD-rRIno3dj6dxvY*+h)_$`K zX6#QRR`wQQ#>2GqYCH8^seLi*qlBC4{SO;l^AkkUz2)mzur}uJ+wJ$T;?)xcXeNpZ zR+Q6#ct9h{-%k<l?`(WkAr)MpE8R+o9`>|Es_wr8*4HFfbq^+1vClA8{$p^$W$$2RnHcH6 z&PZGR-n5bR^6Y8 z2z@!ktL)9x+V6)JFY=1A^x7}APCqP=j?PXswV(Tu#nV6NDi$l{*Gj1~?jL(teuxO@ sCi-{^>n9$TA0DN#606Nu9IT+5m5z?oKL4izsj~kPdyrQJlJC9$0ojh02mk;8 literal 41430 zcmeHPe~e#6wLdM0SW#=Oh=^FQ@}pvv@&$;vS%*>s)m)mXL zA8(Vh-#cf{IiE9U&fJ+hcfQ}#E^6y(mrJ_ZXiI^T-rsx5*m+5Z!&$NA)q9@KF zVtVYbqWwFFm>!*>Xzw41m>$`q=-@sgrYF&ErrTkMX*1%=bla7RHoZc`w6Q_aEyF}i z!+%n=4zXie|BRx$P9b92^1Pxu|3JjlvPRLiB}7cuqOX`1ys7AB_{!9`RM8&z%CzG_ zMGrkk#I&Sa(N0`5T?ZVd>&Gh^c!`MV2E?3cXo8|v)HC(Iqo`*p5!0>?Mfbf+#B^Yz zqB{-~F6g-d40>2@%se#FuG!f}*?NAJd&DD%v`ah^gfb zMcZCQ9)ac`P_+0s#1*s57)7{;Q4va(pf*yZa(POJI zUP1eT&9v`zMSIsFzM!X|$8_)lP4jMe5XgPdf8v3iE)^`y1cUoJo zn7?RYQ%mcdOPgmmU9qTTVN+|zaChtQ`7>JEskL>%HS^}hB6ORTQ4%e4uUT+a>zqqk zE`d(h+P>D-RsFp~eY1wTZ))mn>$tpga8BD`85u}gkFi3V<&W4%8-l$37y&9oo)S#+WOnp2LAaK3B9JywY}>)Q;MP{ zp?OJ1M@r4H6FPx!QLirU?;7k(G(X@6mWx`yoiL*VKvpFZ@Z?BsBd2AQb(Igq|A$Ld&reIzeg} z7acpH6D5Yx@+%U0qW`3e{+LNls6C~M5-!P7FV zM9j6S9WX&NRw9OzGny=7u2pS+=PK<=6HsI+lu*t(8C6zN>-k36Flz(fE!k37j-`~g zFBjRH9@z8Bo;}U=>*Y-=Cv?cdPUIl#*$Su%dC=~sd<_fAFL1Wfp9^%w0OV+|Xgvd;lm-hGf_7|oST%o}o>IId> zeU_5#>+k9bZKrtFa_mRI@$C9=g;AejE&5D^%P(qM#Zr83TTe%KCz{?Ti%OX|-s@#>T;e2l!>S$`? z1P}#_@9N>GD_DItyr6BZ(su=`?^xVWE3E3lbo8ztC?Xnglq9DEI<&c~r@gazu+7sbud$l5hx+?F zdkO;<2x=*|(g{+=DwXkVYod&@s;R`Xm1%uj9qQT&rDs#j@?(yYG#O_FBZiXmlFy2! zc-C)|idGsfM?7nrdz`b>O2c-P08|P?Rv`C^ck_7Z&ORge)8mH%;{^- zl3J>|dZEvQ(hpr&R(32`ca~ke!fGJVqPo*s6%u~@*rs20b_%XVa-~4RB55lE$&V@{ z`DJIP;94YC3M4F&wjz*pz!^luo*CA3apA05gT;m7`)gPL1Vy9EYgyE)MXmJ%i{Y-` z9u)0`lIQ!VzgATXGsu-zC_S;jg?Lz2Qo#ZjaxuqA>S}x_-k@Fef+Y&7-mG>}>s=aM zHTe~q_EOcMX=b^LYFSbexTo9IFGPZ(wGyp#mAMpK=x`SJftE{P7*W#kdKXnmrnN5C zyvm!9<=GZ~1Pfv71>z&*!m_d#%plXF83Y_B*;EV#Eo2L-KA0~c6my)URdzFoMRK!4 z(=eDpQQ2@zzUc`m%}{dwG*DQJ7_po-;7i6f?F|mtg{05$Y-+Y|Q?fi+dn+?GeMT(j z+tiY=pPU26oWAxfsTsu83w^%N*%<^fVOiO+T-{lA27yK((W1K3S``w0{Me>nc6JJ` zMRKJ;!Xjxa0?CgmBl%@#r{G#7R|+I7lC~m{bif%z#GV<}baCOVT7$)f;`>tu0D_{? zsEGqbd!giUKS<0VkSncFdSb?acvx0a!F&O^nBydMH9iz?(9R%WiGr#( z(*|n2OQWl%jY892YQ19fy?JnG)B1Ssnxqw zbqJoBqu_unDG7g4f=E!bR-(yBnM<*S4(FMgqnv`^Dd~7Rf_Rc?t&0gs84p>WZGjog zQBby4g&gALm#d#Lnqf~F{fda*!dZdwSK+MDJfcHwL{nA}9f$YVC%5B#1?Xb%o(AvN zH{$&?=(j70e&30+MW7a3zXRFLpo4gaKe3DGFL)<@ENCO>Ebw-M_rfZoIiQ!;620Dy z^Gu+Nas9?kI5PxVc{R~wysuyOAaEam{kw4{1m~a5d4lNhV|ag#cjGf2CHmuDyi!0ydxQy=W^!I_X9M9)2hGf7MExf43qAuiX$=K=VB1JQ&blv~l>UZSaZ zm*26A=-vC!PQ0f-dWxTJw*RRjP@f& za~~)AJ7V+)eI#195s4acX)P*ND?Z#OpBPbQ0P>c`456AWl;TiC#pU zwjfTM5vR-0{(r#ViylHwz~4jgw;TOB4()vz{;qxu`tbR6_`44NcEjIu(64I{%eUa~ z>F|3W{5=7_F4_b+_Z@O}FjoWG;7w4HuPuh3WN9{Le| zmbz&lolZB=URq46XbG*Ri|8);0X0)QT}*e=i*y5BO83*NbU8ghuhCq3kbXheP$ykU zd+6V28O@_d=vQeUv^zAExp2A^H@ZOefLDXd-=*PNYxJ z$LTbhM5ofH=`(Z+EuiIe9d*%sx`ghfAJa_QL5FB5t)VOEA^Ig|OwZDJw28h&(`X|-L(}ON`X-%A8|WL1+Sr2mc59;26wB@9Dgep2C9X@?epbSUrgKl9>nv(>}rpuAMafSIue~ zbsVQ^-$x6*#p;XVCDzBm)e#;01{pGAN>hr8iKGXWc z%T@cn!!9cfD}Z9*c-zE)rfV&Hy4rW7{9OQa&AQM-Gb|s%@O-<`s?W0#)%nJv%FwD? zZUrV?MQG2}_{Pj$x@X3);yw`TMo&ZVeOyuD!DXS7GY?&T^cl6J+Bs)TOYF&G1F0+uxHjshhta~RZPQ>0tm4$|DxI21Z% z2Y%RFB~TuzqCVH$LLk|sW_^T4xNMk7k4JYMc((!9B&iO*7J_9EkO$UiI_Fgwf+` zdr#nky%hx87rp|r!JG{dx*p$|aqsu63C9ZEO&q3BBQ}0gcgT^F1LrDto3jo`wzTBL ztr@##CXe#yEi$X_iN&h!ypI+0-k5m2lxhN(-Hef$D-7rjL(_7`(JY~?d9kW=yATW9 z*1VLebXyAsZd-PU`$v8uP@$dS=<3EU{!R#af~0>BS7mxB~% z90?EvB<{J+Q+Bqrfb{~~k7lWCn&Gj6&hqyvJ!xLC7PoQ>;|uywYF%N^RH=Izgauz6 zp(?M7of7JaYNVYy&g6`0RxF%6H#88P#dRFlXe;EJY^Gj$sFaoU+$S<6;9E0;LARQ+ zg*FUNBV5D{+GU-mWrVC=w4c469~kwk4gaYz;2i(uThCMc#OP>5W&Bv=qd~-dU4Y!r1tC+`{X`Ew|vyg!EVv z#=aj^BS*^xE{glA6+z?d-iX~5Y4cyLi0zHwMH1W))v)GvIs9uD^!GZru-M<_2pC%4 z6M<>Fh2dS=TZ7%U@D457N`Fg2zL*1$UkQ{|{=L>KSYymf?M|fm07zFTsMKBrgqbJ6@eIn(#&nrOKE5W)g@so;I z@CEG=552GwHW^k57n3}jD%LATSQoUYE@=n!!bUlu3%;OrK-USIo&&a8+btF&MpzfL zU0w18O$783#uu~>=sIE3bHG+>yJ~&Iu@DOzW*8GTdNypvkK$>OMJ+lbsUUfnd|AM$ z=Rx}|ALDTC{#p+o!0rWFMJ9EFL?eM&{F{Sp}S_sZ3Vk+Zmecm8!)uI zz6a_~F%M0A!btfGF>?u{gUAEL_pb{XQvoUOiD`ZGtQ2yf9I{}-XK{YWa-dV>NFkvI zr+V@TIY!G9GDvn%hX)q}9fzbxp@-ygjF!hTNOtsUBwG%29FiK}MPtMOFF2-iy@D}h zpHp<54Wk~{mOVZ9I}!F5B&K$BcjNHU|Msg!jpt6&zi)KoxOroap*MdxY3WCBzT$W) z{>Du0=v*cF8mIHW3j`=fb(raV!IT7bD`0qoaQD@S}#=jq2w#a{MVej$@^Sj#ndk1<~4o*6& z>Fi1Ku2^tYQ5*a_0cBQX12~9NT#d*7_Z3$Hhi10-uI+=rdzX(H^RIsyK-S?uc5p12 zX3xZF9_FkzoT7n@bd2FNunZVZrqOYje>(rue{73z(8K+W#qkaNw8(pV(VzKYk#VBY zBgmNPjnlo18Czt`PvM$!nUWdP;o4DLc^Pw_sp5?JrYY!8&KR~k3YjpH-u*P7OMk4T za@@}MxJCiRotmok_>4QEfO+ zC*vgkRW=@`^TzN!>=Q)`k9Qk5!Z20N`W(&}+%4_V6Yi*-R7 zi_`uX#uD3CR1>Yy{E%MIQ>Oy$*a&S}04KmlaF@!Vy)QzWUK6chMmmxwqix3(Xm)?E zE>b2x__U(8lNg4udd_FCj+aS&q!*2fqP8|C(maorrTzZNUkAE%?wCI(nXCQHn((1uxZ1`t1P5EHLpWJ5)11f#C8 zqzBIg>WSs3wKFG&`-yVg+Bwu%l0%}kkgeJa2TyRIr$W64@%8% zkUhB(`Nas+KfEE3D&OsLxaUT={@IFpxViPmv>4aCiIkv~?|V7a=@F_u*HRZXlgH;J zP|a*6JM%q^+RPoPLEsjfV*#9K^awII_iWi1qm|qws-n&)+50;i_xKqxs()fjKvj=! zZsdF^f$R>1NnlYLL7a0fK0n4SAF|a)Psx)Q?;czbBbN-Hs_o6qbQfCGW_=zaNaE^k z%*=FOj?hYyxH@X)4slV0dUR&GuSB?`Khs?tVIG~C?yC`Q`LL;)zqvVQW{i6jX1Yrv z)RLikMDuu70`+Ljbh8ESXwP(WVziQ*MAbaX-S;nzQIFD0cUc1YXv}n%$GGJ~wt60C zX1cjCa>?+i+QYf`m{%}rcxqVyRA0g5R%}-$@Q%!WPD9BK(n(lFT*av7pmi{ni^h&% zos^5_JRc|Btjal)Tc^xtygqSWTr{V8-!+u1?fE3sf&z`d)-6FqX#^2$C|O&792g4? zM!0QKJ#HD4MFu6@E~$)?%Z95B3Klr#o9sd8s^evLEt?W}VHm6SRqjkea{@06XjQ!2 zo^wlq=Y5Mo7_Xk|xgGUu0<83477mOc^K*#T7KqU|D}scnj97B!;~d3p?{hp zNYToDmwOX?Lx5E`jybI50oG{7uvK8;YZ#(~s^80U?Yc3*8qFBC1z5FXSh9n`=RsEl zSon5A%_!zhXtqaab>o;r>xj^5N3vuGiqCO$8nog|EcN4<%f^)fR^2G(uvP_FqZz~1 z0&8?fbXR~inlW4xVAYOcW<=iJ#&%ow`O;ndHzl3fn|Hp}fk zPW{MbknZr2>c=jVaa$Bp@#_sD$K*rT2<|?)aeAjisUNq@INj=SYDX-~&`-)}h@-woRxV5Jv- zm3yq@oi~4j@Bxj;-yb>>Cn$0w?7L6Tc56=Ve(M!AQ$} zXX)V-Uhxw~B0DN$&M29&KaX5_qzp5irj=LQxo`FDO<^A)+}!BjXK>BWJIU}?Z)3^Y zn7V&o^W6!SyZy3oCL)E8d3f>l|ZPRLAhT&c&xy)KX4^&%hCv1mg~32B~tx6 zO=hR>35iwzK9kuSIAE}j(ytyonZOH!De`3m{g%6r9!%hc0j-LcTNypYc!Q(AGJ4v_ z2?JR9E|UATgRl8WVd$zOm3(7{f5YVK3aR9%XXReXjIeJ=r26s8U_B$T>PIlMiv1>I zxgXjSA*=odIybJq#YpSJ-|>@xqBN3mT(VZ+@BDr{g;%@Z8Z(H`rVwlQUhWz0J0W82 zr{Ua_{&O)}{di_(n(xMV^`n_ti+s=Gc|Ywa*95XuGef_h!mA(AOol$6LaZOtlJlbc zUDzLlh@+aJFT`l|#;YC8+}iJDi%WVf9_#L!>n?4VtdqXI-@Cdfp@A zwa;Hs$SBEq}{KaN`oj!EL~Dq@j*J3gAF@IAU~N;%Hp&vB`zIBpHqYk01f2d?M1 zOCC}K@iUC)!ax-7%~l=SR$@QU5=Q40_NpR&0^s3%O}yZ~ivlMu?j7DD~XFX4CR4YC&DOGjgg|VNpAKdhwx9!kt^HqPwy14h@-($1f6NEMA*hlVjh2V26 z!Xr^=agNRLXd}FLmTmAz6O3osZ4aa1m&oEg2Y4=|p%M(oGEhMB!uh3f{C$x!+Yvn&13@c0>a z(5t-bq0?xQao2VR!!{c;0&39Fuf($lrx+C%s|@FL&F?#%jxX_ns`IDWKfHShqfRr2 z_Zz~lQzdJCmhj#k;P{xI(MRk_*3_?mQ0)m);Bw=qSa*^eFP&gB{e}y+6YOKZmBPRi zY@j;XzX)r@WNY)&agIx}9ff7vkC(iq_Th!~$JlPoL{G03;+Q%fV=bHXs znJb#_EN8<5!}vE@R$xEjm2$Q-aJ&#-&U{)77dn))XIg{_XUdqlMN8qQGPbqFLZM$7 zYZ8>|I~sF0)b2AL)&-QY1wrkEl0$4uP=ru*h#d-QChR=Kz6{!$@a__^6R$%+MTQ$5 z5U>1{|QCG5Sr3-HF!?#^c>y{Edgo!+HZo?^ zIJH9%Kw#z41MFhhC1Klsb|5_7Gkl>q(3Jg584=E3FKHVQ$qUMTETwg>uySunP3vf0 zNZrGPHi^PhdstGNHo~{NS$3N=!Ll3vj9_=#^bASrNIE9yqK&p}T`yV*lj`10CZ4MI zZfvox{oQw?R8W?qu^XeE+C18RMXH-6KpDQ@5wZs)8W9-Ezg0T53s4>NGX&0}=BdsV zCG6w2p%Z#jBb)E*;FTikK!H+iJMPp*NPOEvzCrCl6`oSXg2ojZ>_V~CHN+ZcWnAH` zus+?5C9FrguI4W^99LI^59?h%Cu7CgY!9Pd#VzExira?;vCvW~D8)h#so)_N5~YGh zEKHFKVPfG~sSpQUYd{+9zV9ypQX9%E)O(NDWs&PL%CTSEXv4hp5nI!~mGIn0Y)AVj z_ohu?(FYybmG+^@Ylwcf6UUvDeysO+^@`t#dAJKP#d7lil=Hhblvg!JIU-gr>(zT} z)GMrk;6-(3$sI!d_k4)n700R!)w=VSoX(0mpB^l~Lu}&`B5C@{3 z+$(jH6C@c-_O=lvS}*SXPy)S_kuiH~64ZOk)hkRb&|l9!%so=qrkvJ?wMM9upCq_1(e`_OIQU{tveVE>BL z^}RwvzTe13xm)#$w@GTjfWJ}@9D=If2e82%b$#fo*q1HEG)(SENI9c++&!#pD+{P=LN)-+}b>EY~D$6$7$ zQxo^YRBKOQH=rm!0(8hA7T!5hD34&BJB6^I$R=*{TayBo-bu?gb#5XgeZb!B93o^I zS#{^uZFn6jXD7-X$`jl$86{LZaR@CF;ph(5HOgODJd_QJ>eOM}4qCD|j58i=<`7U6 zRf#qay=_dO(R$aJ-Q1}S%A_!(irK-oL>XJuy$@-dk3y`~I<*I;QdxEGeRe-8G~h$j znr4)dqC}gIhtb()_*B-VOL&)DRFqBu+h{EdHY%!7^C9%gR-QabOK?UtwS%(Z?=y3k z*6kwE#`e|Yrn$_z25m4)^*+qfv7fty35VWe>gZO&EAO!`K%rCE@aQOExLD%9WG_b# z7cRfcu1BW|ufEF?x_0MRv!z{I3FD`*EnPYMVoBLOm@`_ z^kcM}bYZ1xSm#*abUJYu*xsRVo>Xuyr&lRiU8ULx4#hG1P~NH4;oOv?nko$y6u&g! zAqb|USXT)_gUxp;=!Ak}%ljKMDol2RE{tvNws7c`x9M0|IvL^_+RsrynEZrLk?Jk6 zDvhd&RPUm2wTZ!2fgtn@l-oXYxIGZ9GfRyM-)5s?#x%)qf^zORgmGfwTPG_k+aRBJ8w5P9n)Ug=vbAT~nybRO#!8}7yCaokPy z7}e5wEF-pq5cd{a8ygf7EQy9RG(X|g)=naoD$lpr(b!IcVjlZ7wnNulZ<?UELcM z5ZoXN`fj8uv2XCkNR9K}WJ%py2}N_+obI7Q+?#A|_vRs?l6+WW`R^u*o%y`U4tHJz7ABR^fp@WICGj{Vw~(jk1&2E z3+>rl*z`K<)l+9)4AFuz^@{7H)8?CwCNbx*r@Woo1i9*SscI0aO6huFupO2JZsF2G zZA&D9HY7mnQmU<#Yd1=@?qrNTRTq~KQzi*~4T07LW!a0-?@zSUQEQZ{nAkRZB5G=0 zV-I?Uns-W^ZkW3_AbV4-@jWt&+&I^u2>ez3W7$ph#Oj;svA!>ZdsE$HjiMO+?&7bu zM~eldy-}Qqhcd9o6T3>Oz%FujgHdaA7P1w~GCUsp*}hdrIudQ;!xGunUiyg9={T=( z)|zGfii{7**gc&&dqtR!$;H-blK4OwkC(BHa6_;;dApn!5AzMw>~^`74eXQ(QZ{g0 zDoEMD*HS^s2JT1&DI4&fEcVw#)f&X@^0*v#*xC;gtbD1?E2CU*L!#*0{8i@c-J#`%z$P0}smG0EO`OD1NPb+XQvu6Ff3a7TQ z#Qwd78QWMv|48BMQS8J1K|J&7jhh@UNw`a&>hlpYsnu2#_`?Xeu?Asg(ekum6lo&N^!R@w>*|tKKPc?nOL+# zY=xQ^P*Y?&uLGI=5?ihB6_EmtG2?>mgwfu2yiwt-GTf0aW8wG2j=R0YzSl;I<>P$u=s%{VdZ94JTOd{vYCA}u)WZG zGrKgfZ`l18uvbN;_TWXhIYQwDC|s5zo@3v{Z}-Ox!Y+BS4@ z`Du2>Fj4r|Ce|gPqh|_4aSoPjVi^gE{?j+nrKVoT<#^dgxY^D)x?E?wW`?oL3I0OF zCUz@97rY@^Z15X`gzdzTB7=LNgTF(^hU(jmEOyYd!i}4#? z*upbLtkZ5_EZ-O*WHI)ZaZ*b)dtAlFBvHlf^(-tgLO8dc84||{i`KL4i7h;THBp^5 zbv-+r*imS=o?TDOYlPo zJ3Yw?m=5TCQt!uuMZLjxb`P>2uK7FJj*{$}HEi|p8EwN!R!MqoPpaKIh}8Q2X=5#t zSGS#S`y0_~38H9{jU7ua6e?D;5l=^Xb`+VaHLKa`r^gG;SBuX4u875?bPFA9c+{D% z6p=IKH5O@LD^fZ(ohtF-3a6`#HiWjH2eR^%nL=G5>pUXL^XY-qrRt+XHf6+%Li0lA z9MRTu6`dtEm17l)N*yH>uVO1xV}zJmaVK0%^)XL{S8-h{SC`hiTkp6(JJM*^uG@~V zu-UdIznZcN#c}5qgz|eBI~_k;sR8gM83$kyP&rn{6J)$W#z$nV#6qf2hjPoHvjAWR zY@F1TV01(+IaL- znOXjmNBMP)-frXz17dh!0X2{zQUNlv{JIAfuQsEG4UAkj{;HBVtURG5+cm09SWoKW z+(oAosfP7P`wApW=m0(vACA%s*l(j!1m6N2WgX46E6Bsg5GtxY)O(dp#0K)|Y_wkU zh$%DKj%Vuolr0=$EDF}?KXy_CvWIYb(LXiVReX{?kvFLKm1pY99Uhs6m@=XhT32M2 z*LsN8&wV~4GGnR}tv~TOXNCEx4^!hVLp?4lO zI^l&nKIglHK8JCwrJZGuS7z$1W%w}nK?1jjhE$ZT3;fiH(HV>S>WoDbbQ-J`Sbt}b zdT+2=Z~5cToS7(|w-0q1GtS0a`g%EY#@dHIXegM}`>Hb)m4ga{J;`6$sqyN)KI%+^ zq7pZ7RKyqhctJt6R3bhE#`<_R;!_K;eAOL-q9#QpNs>Z!!8{~tlptv6Ehx}v>#Nh- z4kr{otun&z`a->%>{QXG?73&E&77KX_z%JN9!3UYXXT?wNfY=0zIlpi?{=r&?WWOjae2MgujbqFh~cLW~m*`LZ%j z;#I~8e^Om#oPx6_JTTctXp(G)GYx(2EF6gCRc*BQJJAobCoVyCD8dyMAD3j0CgvvwWHD2z0-2mVRDCNb<6OkU8xM? ztjm!Ec^YlQ0v$ixW78+Mi=}1eL3>U^OEe5td<5aY%pac?b41npW$ei0o`QZE^2cD- zA|qJy`xjykxt$iTP1|G{OUMWn>T_9UM!I0nWydnQm~Zuc->Ic&(Q*dgpfQ9oY zJ{L$)nP@X=5{u#jjRnWDrz3=CXT)5Lvp63t@YPqvi4S)OoL48s6)sU4ZJ#CD;;=eZ z3R?xWGul)5LPHakv&?!&$o<)N%FzaH!ccx(inrAXZn_+VUYp4+5Ie+6y*JU5R%NDl z`Bl1$ZW(|W-Rzvxxxe{+OwFV|5oWj~khWXcsL}e7`cZoF4DAt9#tr=^6n5eD>w4QM zy?r#EHGb<(L+dvYeaRV3BF?EI!{zpL5>XdJsf$f#vGJy3JtW%Bs6*qp%uIDCLO!{} z23bR4C*J5RPwaCl*L)quUe<^kz^Q#jRByT*SX%8%t}|Swgd0rw?&@=-&U7B0Gn^M) zx1L;Quhc6aB-(JE8P03;wlm}@>eAJr$QPYv(x{x}I1qEM>20SSsfZ2mnt3DC8lK8M zugk_(Qq4mt0o$eS1K3)cwGBNNP0>xK28Pe5fp0%Z$S-Aj>q%#3FU5Ne{ zy$RjlfMY5;C^E>h%z~eDu-ZjFef30FB$Ev`($3AIJ-iq@H(EbQKT-b-LMwJ;38}Dm zS7Ht758lL_A|_d#e#<-&4W?Yw4T1*y=m$8g&lH?nJ{vy17>G$PH}vY{k>h9RHQR&F zaku1p2!Ce#Wa^#eRM+Ql?xjpTTxIv85}JP5@lJtrd0Uij6ermXqK0#j#upY!H^!$2 znCoypIumW#V%3)>Tcy6#2ZO}PJIq(TcMw#UU%@%5mt__iO#Zy0DDRfu;?UU zm>6Jjw10-+b2cXp(|obLwdy9q*+m@<1!|RrK0J)-uD4aGL(Pp>p=hDC%n!jB%FfcL za0)8<_(G*X1L{+S;pr9E)CEVdx$2(BhqdZYsI7v&(9B|&k804eOug6Or6^R=FI%_J$~2G*`Is^e%eheV#q9F5Zsxn{y*II-Et#c z(8y>@y{o~#y^9TcF1s^r(DreKGchK^UC}C;aDyZ`w$rf8!@e)=HeXK zPd>xqcHpY~m|H!c9K-D{WW4WaG<eRmQvHwxQP; z3bQ;!A$|ET9w>NHp>T|sh>YHN#5jLLjMgpCy%qV2__#s*+LLspLq7lH(SB|r1-g4! z)1{OgVhJyjcb6it%AgRlAg9(4MdMPv31Pg1D6nj$J@y7tk;iw;`C~ZxPdoTu#kZ0L zXkt=S=&g%&tn;iO&#Hyt$QRFK7PI2np={o)&in$lZB|$F#LlD%8%DH3+%Q8$mUhPi zoM?)F8f`sMgzQLnJSH{uI6LuE} zBNAX)lguxjaeK=`7DUX&UW5yc-Z&>6)5L>A)gDG9DJp3gT+VP7J*&BU)xz#H5>`07 zwV$|Ze0pMv+f`##e=;J_+~^sVqMQBz&UvnG4-z6V*oiYCLwds~_tR2;`m|$T}IcLhlH97TI^hiaQ(&lYcw%7ak>b$i8KV5{28M$f4V!BTsr`o(z@NTm=^5r-;)E*Fqd3 zsQ1RRRYRM5xZF$59n!EC-O)^Xa&xUk`Rs?W*7l;Y-_Lo(Sn_WwM0SxbcMkB%TIF^j2w5 z;UY69sTE(r4i0S-~tJsafrGd?rLiFf53qJCyW_}Y7ehSv}?=v8@U8ybl3 z2?!+?DKAh!r3uI&g?>DURwijym4qabFx+voJq)WMp7Nx7^=$`&?_W+l$j5?N&kEw)(HSo&HF- z4f$U(G&Xu+r>T?k5qiHl9w9Emjt~-~llZ$;G<$hn(DCd~G2Y%7FHYq|8v-hAc*>|~ zw0ONOH1f97sKBt1PtnOF`T|9T!clxrbi=13TQ%5HJnipn@sezr1))c6xe*0hc6{=G zVN0!K%gZL6IrD!PXkx-eM{PiJDU3G+nnbeh^MkPNzX&vyO!aKge-UZUd?!YlJ5!&G zG!@|eO{8fXMhoeYNaGI{B26|L{_i7=^8Yr{MEwgcqPxlu$iN(NA2&pr=LZFw-H+mpgzu+t;o)SfhQUA8x*Gnub?I{7y@#IHvh%hb$7usyH9?5VVrie^`p^^LDJ( z$~ff%dlJ%rIrI+|NjZp$%bMb57rG?4=aZD7aIq9j_1M)Y;7&jhb}=pmq{17)wa-!Z z)RK^>t8^%wc07MYoT{1(WE|2RAt2LQ<&C|7*9qHc_0Af{8mtaVVcGWl0JeRQ_pBul z#&B=qk|3WJ@^L3_O`LUpNJtco&bitUakzT4Yqb2t;Ua%@3pm&wD$QTK4X!55wqgAqwGP3Ap3V~S z?ub_o!C7eVa&I_==Uo;ZzAK%LTACz0RVs#=qe~-#LejDHGwR@1+k-}_gV8>U@wow= zR<#sOb)-GwLkf0w;Mo%XYG;+z6k_g}R0ZMAl_#E9K5_;Tt><_)`klP{kSh z_#PO`_T=u+9-oMzW_ulQ2XajGq~FfkJ&`S1_EhY)AlPR2T?^#6>qEavlheVGjCi`D zEISNe0?v`@CsO@qsIO8Dp2)simL%kkVcnK@>u(%GzxGv7W>&_OT}^gY7pZ!H<9J4a zyV>eHg$7+OYrof@!SB$!dhh9h>Y3=EC}hnu?6u|Ngk7WAgXKR6F9xz7%!O?ZHKRCj z!m0ffgj4&DSgbDfRB~mMH;%{e$*pO|)>~T7dV3T!y@wGYmBugS7OB>brm+xhEyJ_6 zsuh)Os%HrmsT?CE$vDv0(6mZ*7#z}Dr8)?Tu0d6*N}1XZGdbg|GIGwRBUxBpv(`OG zL6J!r=BmSUh;IiM6LOuKv$1)>!Cz{rqmnyN5aXm@G{UbGr5SCfo!UKGwl1%`ut>|Q z^ZE+W<4WA}oAQEgEDN&sY1(`&ynpOtGDB^sC{($RWz(!r>a5+O!ck)?N~i@m)EW`j;}?;9TY!&WS4yf^H&JOtx`}Vd z7?!vqvgzIV_?~WwF+a^@NBN%+-|W=%*i0sAun?_?U3@O$uGiT06b zds3KG-mPIxS3YG9r}ntR8I8Z!V3LBU2n(L6K>zLO_i{BxYd`O%a8QmLejQLle>y_5 zMBlESgj;UVTsYf|Lj@i{?7mk}t`o4-@V)d8phZ0n+YSuV>Y;S}i1$|zf~&nkw%LFya znRIbZZ9GV9B(K{STb6~ZHl#A4u)XJN;Z)y!OE`-u9O#)Tl_rHVb78D7U(NOuhBn!i zB>l08`Za^Cyh^n#iTzL*Em%je=0yYiyQ9*nw^l3L)DLi~4MnQ1BiM|hUSYqd;EBHA zVor;^E1bGsop+a0r*R9sNfJUAQdoIWw-#?gNUtuv60mS?mC9n0x~WnWyU;ha3IMs%lOC7#P(*cMk2V~GJZ+MD`Y%Z#wjxHFXKoV`^dQdoMg}?86TGM zKV&S`;;*q}15S$A%yBzphD+eSTz1I#=416?vcm0Wr4}n?oGIgRGHxo%-IL4T$oQ~~ zvk4nry#mL|6@fB#ld(%=*kfhg2F^n9AZ#Nr3s;QrO0JbS^|h>N@%tDX$6ax?c43u8 zZSmq-T3T@dToX%-r3crSd&<(D>uhOfiQqCUncQq{hGj9g%<`;d0hi2;v`n&$ zaRyFrsjyUXC%I#m^W4{#FD>Wr=WoARoR)jsRm(5j_uLiBcJ58fPRo1T$Cghy^KR}# z3$twEwsJ383OT!Fl_j6E=B?z{@I`r>`E7YGTl|f@&+`7sU*a$1Rr9Cvs`3u=aePAF@Vp`X_`HdHD*tre!n{R%F25vi zIzK0GTHa*7bzWP(6W<}P7vImE*E6phui>?Mp?N{Pcb*@w)lK1}@U#XhLafcL zO%>6K?$!a;-inUaD1}ZDZcS56wa&B7R4lbFS7a;ZTSr(&DJCe!T8)Y%>tJiVqD*nr zdd7NOanbsX;&a7W>#x?^iu;PYR)^we>%XkuDqgp~rP!f(*ScR}{=~Y^`jMhovC;a9 z^(BSPx>m75k!Q6C1^LhCuNJoCzbtGJ*5#Mv?-dRT2lC$$KFEJN|25&e{2zsDLS6nH z;m`cv^KS|@!Wa3M^S=^K3YwJc8vnKO0H zyah|b(r4q30MoN)%$pmQnLcCo)G1L>QDI(e*rpKPi`{3f%wFOO8lOC4?zF*EvyYC&rDtTrAt_TAPHn8+{DgZXhj1_?eM;)$|7-}!rTmw2 zsf!<%G(S2w=v?f$Yy6VzsgKJ(Au3HB86e6(sr|27i2A#^^qc?vM9Yql3=$js4?2i- zb?_hbQ#2btdclnBsi}*H&z-&GKl;0o{D1O~q*r#$zfo>(*cRk^(UAY%my*2fnt#*5 zllmWVrTO3OQqlWT2cj?kEB8Di|DW7Lo=h=Mo%TQRJ{FHl{=ZO<4n{1QoAGx$$t=Yr z*IJVr{0}S|AD=UO*57sTxPFpvq(9_u7aW_jsofaYUz7`Q815Y0hFyS{K;Xw!hZGM7 zFUMU&-L=Q+kQ{QU)c8Zd765*z9lN$^j*^b{b>aTL`(KsL_%g!l!UH0a0;G&EjJQ6k zbXM=;mIG}kpX(m9=3qC<3=(=zFf5syK4-?_sk28IhO(nCbZ7Tp2%MuS;5hN`&vkR~ zB?SKbd?Uv-1$Oat(a~H4czF%H#o`~O)Ab{22K@!Pt~<4ZE#jZ9M@2_xWa7E78fCgi zMh#3!)r}dbCz%?Sx7okn`A2FJ#hThjdE-dh@dz(jl&fcFq2bOWHK}3^_nO?l*k7us zK?B|jKiIH9`b&A5gd;5cMSt^{64|;1*%`V-y{IAW5#Bga!}P|yR7o!D5uPNs7`)B6 zltwL1eB$zb+vKwQFR|{Sv*W&9aC`O(=8CNh_t_ShB zT0AlUx&8-09LmXLz~qGs!EX3x1W{R%0d&XLfE_h0bH7T~`F z=%Tw4D^0_Oz0_@8w31m~N^80s;|d3Nmlk&@JV)#0(*Tf_JH}0E>6C(k-o;?H1WsWvc(o~(k;OEDz3OK$6Wwq?_r;A4Qjey zR+!bEct_e)G%5-E@kAi=NDJ?*Ux0jmx~3 zlJkPes#u=mhk0_tzW3!4Q+>FnV!b){$%-r?4SlKvGpD-c#>Gv+903CMOExwx^T9q` z@Dw!{oa)B~$NF-?DS`FPY6EJTmT9v1W?o#gR5jNu){kqJ(zISv>sRBG<(&q_oa%@# zM_*T|XLHtx2t@40F$|;JD`i2W4fA%e01h zK$C{{Xp1(~K6-;xcYP(t<*wqyxF*WG37p&0-Gt;OYBx@e4%KL&?&h84YS63@YYy<# zMiR%%S&$nS6szWf7GV5Y{%J0`7a=pSh~q{=ZeS7XzrAfUSJfYO{9BK;cn3n&%C+pd z?Zei!_c6PUf`61tmK}m}f?lQQ5O1{6W%%DA!|*RY5SwXE%djruP$u^k2VXD z*ae#S$%y93-DR112-LkLNCPIYpsp5jHCbrihZ{#9Ts@SgftfZJ!f{Z5a(w~>)1Vx* z3u+OeT)?3nK^E~0Xfp}XL=PP($Dtg@UVU|`Ijb)u0QE4BfVRhWXbek&3Ha`f=xETj zpleaTy&p97051jd*^mPr2D%n>8t7f1EjhrT(?&pU5z3&GL5G1Z16>cg2DGLpXXbXL zLg}+mfQs#)i$RC=MB|YF1ms;90znP@lAH{g1pv^N;lT5u3^eyN3}1+LpvlM4@M~Ew z)Q^WgGh{$pCZKEq&H%)MHo|~RRE9yh2w*0|r}gktGCYz7(8K``K&mz5(0@2q!pB3up`I z3g`z&1dIjD1S|!t0IUUU2D}c~3HTUr6!1@g18@)Ed6MH=oaBac^sjb$15AL4fH{C= z06XAiz%IaHz*)c*zzx730H0GF7YJwr=mzKu7<{V4?QOiSt$Alx`-V3JF5{6Wg|3g4 zOS->1O;zH#bDGLbnVsurWeuq9aN=nf2lj(k4_f}%$_@U!k0E9fPB=azRm(uvY&9R9gLwFkC z66h@8V}NU*Yk(&Na@-xzX~0)nz~tRno51e`VPjKg53_unuV99^ly3mQGlQ}C(17qf zz!=bk7XhY&es~p-t_0ItAtZuN7|+q%8=xQF38cHh(NGK)d|)#d9ma8=qd<73OcP!& z)0%L6zYTCerUrOV1gr=B@J1osEDp9tuDb_E8*mk%J?I+X%{nAupdVf{r0d3vwg@JB z5ZH-$9*_p1hnEfM(lMYtjx6vAX8^X7B4Fv}A>m6Xmw`|C7r^JB>w)t-NNz6%?$8l; z8StZl{X0nm5U(m`6mFq{?ks6oR?58+o)0=0^uvpbbb;yE1pyg+!UF(fKtH^}NH>|T z(J&Hx!VItiG~sHQCVWk%&1qc`OS?&n>*1Y8y88@|!Tg~y;cNa}Iv_k`qBI)1yBH@)@{|_Wrb#s61L>068{c{9F5F@=?(X|A|3riXPC{wp%Pw7l zCuLw;flqiL;0|>R+;s|`3-)6wfL(W7!nda)zXG4IPbTU?Yk>Dp$5eo(JiBU!JY~S& z&&2$T3uNZQOD$b)_W@R*0pZht&7cX7n~Sgsnr?Brd6FW!MSKSk^#Ie2jA+8!=F46L z-m*ZZfoCn0+Gd$SoXeKnNcW_i9BGc}ZbbJWQbc#7V*oLp1Fv{i;?s3#{9<`c0QXoT z@hRCiJts{QCHwQ1N;KUn+;b%(=vMJIz)TB-ZWSYzNfmUfP%M{)fKSLY-70MGmbjpR zw^}5n+kp?|Nil78@psg zd*B;pd>lc?w}9000}&rAGh;K2Yg)ChbFP(ylvn-@#`zQChp zIt}>Ebua`n?*QKfkXL5j0?~iHR4@YjZNP$p&>G-(0o1_`VAV#P>3gv#f$0?)|G-GZ z^pMgX@`OjqG+}xjv4Btbb-=*`CF|C-&8al5cn SQ695BYy0BuB~7Zo<^K=&z+-R# delta 20307 zcmeHvdt6ji_xG7IGh7s$5g7$U8F5hXf*@!rUS?p>K?g;}G(|%}yekPP8ae|51|CPv zZCPoFW;Y*86!VrDh>Ew0)F-p7uzG4pOR_RGb>8nf=YZJL^Sr&z?@_=hfvDHetq_^@SNor>tFUpCi(2`)rXe zv8Ri4seL-={yql_Nj|S`ap9Ao_trjbpCQs5`&`gFYu6MKy|?x$F+FZh#%wBsd-PvV zE+vuUGFN$Wv)elzV`!19;#FTf&EU*Mn;X9A&Q{)d-Gs zr`Sn8guTyq@}D_>Q3fYgk3%&@(`?&FXX$~}^MQ7||_jKd@ zZdG!eTUWJ`s#=97c~HsH+b`hPRkDxUJNW^XY+8p7-dk6Q4PC#Nt?V$D&)v&@?2zXD zQGr-}&0aPpK(Bb2Wd{u5ckf}l1E%of_AsBoG5o+iY-*sM|GI+N0z2||E7+F696q^% zwGB%3?J$kwMmc?^pmv4|wm7IeU$dKS4hrQj?PebYwdX(B%`OFPN!+$fEF@?*NSXN; zFPMM&4#znPJXH!jucub<@yzpd#rF^gM9(o)&ra82kvOp6S3}+ctDt-R9d@u|b?~=u z!$rm&i*N~ZKyAtJ;T;9MN&$z8ci3~mkMXD8W*-Ij;4|N5cZ2uyyLMIX?X+2;`EzHB zHf!|{mKHM3?H@ zqt301&lPJayv4rIU*X?=lO5_3?;V&UKIn`$nJTo4;)lv^p*$!;SUSIc2ih}~-41)K)0e%-N17qZBIFtd&`5Z);fe7i zQ;*z%DHc7n!w#fMs`9i>OO#u;Y#~x*YMz7{zQ4W-;`C3lU_@7cqjKx!LLKuH46Z^m zu=j;m*?ZkW()v;+!M75!!?b8x%2XQRj9V8Z$u~cgn>AjfP)LfRmI^Iqp_uDCtTpbF z#?pEExPFsfW&OKH+Y;MyT!Rrm#_<-%b-m+`LipU`^!+NEBhf$5W!pOH2hy z39Xojl@fX}F+xfh;Vca-%8sM5HRkFX&HghD73d4;0W|wRr;>dkm1_1{ThV+pa=Gqc zztQYJ>naqxj-H@-ld&*)a$+4b(7`5(72pYTXe-VaUoWiMt54@oH? z{*B(vIURQun&KZw7}}47V%k%O^xpo>>804`8paKj(DgXQsdHi~tCzp$HD8mnRpNUk$xX~&j0p97)&SAHB<9yUjQ?p18`!%Ozkei~)Vpg~moR8{jrtG$ae=gJ ztuzk!nOj(O?{<7?GW)c5uZX*wF)A{CvCMh!0u}- z!C?6QnU}CgeE!#}HC3ws-cYUAUP84D zY(*bE|Kv+-YoE^iu$R~eAiFcz*L@=S8!u8yF^fe;jp1!CGFwzCZ+emaGpe7$kF}2O z%zvA~dPYCavkc~l?q>V;S=1orICd#RlvOxwb*dXOAaPm^`okL3&b8R>c4Is0iK@nY zkz8^hva8c!&E+&$YxYpJz)L^~&64t^6m&XIK zb|F%x@J;OdzLVPi409L>R%|IT=Ug`|Y)nj-*fr0?$(-A$0s5p`t2ywwMftH?H#Hq; z!FM5P9o1fz`wtV}m;FdQ!~( z{&P*)&$@NlqD=kPb8JFvFP_a}j@XFk6tbA}SyS;AB@7Kx=6)?RyQYytb(iPZm$9As zz*+2mYzSY!k#+9Zq0??r=Uau-yi`~C$dT-KZDiy6b?dtYW9+6TZJ*MP$IR07Ik{w{ zTQ^b4HoIlEj#9SNjcjMX&b&2?o#_`B_zWG3X)qKUC_l!ia2IV;&sgXFLEamuQq6qd zXUx<;HgK4fvNH(FRIM$J+wQ!!=olMY+h4C}&vy6k!1rhDRDXlb3#KJin&KPeQ}9(F zOU!x9sn%}YKhq@DMM?Gj1`H#LM$E!7$)H#^sFVy&kO7TLN&C30MFW!OH=wmRQw_$% zm@3I&0Svm9RORMFyIR&-Bvn^2Z|*c`vNy1`kA>KVNs_*3elu)uYP7zom~>g1g=S^I zubS_xZfd5Tx~X}>HxkmDnzn0{>rrln;#xRz_>uP(>%{pflve*q^Q%^+#4K|6MWxml z>{M3_%PwZjXXh3J`A8C`=#yBl0jAJe^b5wf`i4w37$TJJBh#hR*t!9swt;ezp=n87 zDbuqu{gY_(VslQ~(uK?D9|dx{uK(e7<2aItN=XNhu8>OG{3lSIyH%|aPYeE3%<a zydhTMRyCbBY)1!t<#tD%&QOk?kmn3aQv$n0MREf&hB<1jCzq2-jI`ChwWy>aXZH0owplR<~mO7}rrfe-%S`0V}9egv_R<0hjL=kcY z_Xg77U;H?6>R%zSVy#bs(Fbc-$lxx0Vxhsxnc_HuWk1)DUV=fJW|*WgpD_+<$PGoN z)yQ;G>v;PbwrX%RpS*@08a#+^5ZLd7d+^B-vg_1k_Ig{u)PXPGp8iakp)7c|ez#kPWYX!GjIc|#{F`gJekI8&)r z&0V9J>5Y`}*4G_R7gmq>&FxMq+a>0LrUNu(*3S%Je=B8ohYbil4}X@7%feZUbMO?4 z(p_u5Ek(~=?urHPEoG_39{j>mW;gcMuKPut6s|u>r%Nhj?;At-@KW}baS?yu88*h$ zCEkA=cD@AB$6*he$7KnK?K-V^hFa4ar*-RYjwPu%PAln!PSZ)J{MsUn3UKQ#j%9mI zR^H>84e@&ZyHzYSKAbkC$4WfOfmgO?!Ehri44_pcOj*PphEy%|4&_gux? z@m)ePAw<#5Wn3(2QO1ZAHY{NpKdXdoP3Y-;c#N1ori5KcNNVRQrXaM@z~!}aj`t8g zc4>ZQ_L+J%#@vqIUd%GhhTwan#SD3{6wZz;GkXTO6t`)URnI79JIqV@1_$eu7!~pu z?8G|UrFIZHz2Trbd?h_+&}cS4(ZZ)V*#5+I9X}|7O6mbT)g3Rlu6MFn$m>NceRv=* z6tSm=kLUXrvAW@b-kYtY)A<*%o5Mr-#zNM9#FHJ@75>%5eH{EysU?MM{fJP0Tp`;x zVlscr&a{?5?ihUu{{U=-20Ib~kxWw{6Se zS4Dn>e|M`AO?_7^XJw;Tcl%}8e=$v^eNXWHa2Xporj$=u#%jhydb0!)s(qHRyJM!P zHs!Zy(u{oeYD(Xb-SLk$X$WkZ$J>T@_FGC%zke+iWyaFkYKwr=#e{ekJ$5cXXDNGm zY^3)glUPRIrR?I^7x_&~*rIXWyl)sq;p`>sm2r>r+9mAPxEQ|O*W#=gHQvY84-baO zxLR|#(bI9;bLj*u?TW2fAzl#H6ivcG)1o}%zKUgkB%Xjay7`m=beBxOlc@>~Px4+e z&6MdznO-ES3E_OGCa{5O~dxPIFu}K72VLP%aYm&-1 z+KDphXQbl+FK$N$)YlaPx7Ws-oTC+*11F57gK?_9lq7Ij)jxVw-_Vx&E1=>bfQne9 zs59K~qV%<3&4CYz5rrfxP$;f>%8ppHIi$7ppyDs9PYu&|M;p5qf9`hUc;`4CUV|Mp zQF8#TD(-ySa#+}eaeQ(P_QReweGc`_X)HLWyfph&ZN&_-LnC@|m!T1{gQf7g7IOt# z#-#ZmboMQwsKzRssZ|*`PHm4lUu!m~H1<{;s8>gOXQDp-Tw6P+Hpbqc(*A?Ffs_si z=Xw(j?ryV(l0u(h&mwA=&&?r4cs{p+Xs@OA#UzhP;U-Wz_DTC>N)H%iA5C1)n+Qi~Din7Am#L^cO zFN3VvRJZ}c^%aVDk=pn{;bEj+_($P8AX|1Qwn12Kt5^IBbjOXtA0d77&%y^FyM9yr z0%664!cURfcSUg-se`8!AA%gIEj$Kcl~Iw1)bTNeBau2arEnU^xm3ki2=OXq2~rme z6w8qMY_?(n$dy@zGa#(*TG$QbyIzV22wekgiXouaA1mw&X`@!5L+ZDX!XTt>w=Qf0 za!;jDK*%W_9?IH8m551d;?ZKAPCc>*Hy z$Br|wvwY$B3dDL*`3Zz6zdCLqm3mKk2dPOe>mZrCly5;e`=IiD zkogB3dm+qTuY3-v+^vq6l(n|Re8I66(t=`Tp`*40n;&QAONwesiovZbTFuv%&}nOP z(JSC^qT@F5&q7PlNM+G}$Pg`ZNBBdKQOx=#|2DWS;NB?O4sAKOZ;QSMw*%aDz5&`d z!QJNXgWJW~IPQ<4n^0FkSjYbp!hPVrF8Um@gW%2&rqV|ye1}>NngzPprFWwj2J#d~yJfCHXtIHXT)uzgH z*bSK`#7v9menqk~35(w+wB%*Q)Mc5vp4S{Wra54P0kV)bm^BAZYW9!tC^Z|p(Y?$l;UvY+-Lo_y#jwHUj?vSN?N2qJl()E#4Zfcj zjE$qpUNFD|(LRXUo!9Clf8SjLt@}il$z4TyQ(U#J;Dj}!#^fBXrrhqD_)@b6kG@nj5Y>&VDYzzJuUVwF zRJ*)NN1z4Ph|NKbIywYH2QhV&)=vzo!;^%0QAxtLrfE-3t6|G0p0eR?-bgoWf^QTS zeEZ;NE;krW8;1n85gfe5+u{IvyXH7NBne}*)GeC*b3C%D|K*j{+I5hwHL`4u6P{Udt|b8| zvjVm!RUVwFc7!1cN9=|l(BLN(ZnHBH4n}BWPSbFhWI-XbPZ||&lASd2_a&;trNNV0 z3+}-3kymrzzH`h2OU5V8G44`T5E!aL7Fx(M=PR1OrK(nkTVcMSfqlbKu(Z`5jU`S! z41%UGur>I^7`IudHKX7ZdPIGakm`Y==)$HLIppxrBA{Xq!^5n&hTKkY_W4{4&C z7xfQdO|@nZF<`pp14-w9LX=om;9;QPa)3pkCWW6UskNE!y{SQKDKtafkwR;Xj)-m5&A8d%_gTs zwC{mb{7IFbbF4)4f*6%vc*I~_)UvkAbvBETpf#4}t76a`30mRONuydR z)MA!l6+_6TwK&HqO3kg*?kdM^zThX}Lsxq`9U-VjAp_A}d9UFlyL~MMIR>m^(pW4Hx zd`Z}89t=o_NV{Iv1;DLEu)!#ao?7+50_T`UYGqbd^CBb4#3rz6)$VG?9lqc?n&1Q` z7Mh?vyqX6V+%|~AyD^i7cYzuOr5W-uY@6VR=@+q-ERm^9{d zS!U%gC}ifxVj-j93U|H5txHkLl2=h>D>*MaA_}OoHZCi%sdd_!v#|Fh$Mn-yNQ<_Cu1Fm_IOfX@85mf|w6Z(6%j>OzS#)t8 z=6KJn3X0e4_n{Uz7GLVa$DJtnDl4()FAYn@SSIa302V{xg4t>EaTPUEm@^(PCP(?u z9-GzrldQO7d9%@p55gTMZlVPr7^tQ&P?h>9s7RYhs1-|eRJE~WoI)|5P&HAeN)cbG z;>G%&p!zC*)0EI^bo=;Fk6)8dS^S(LYG&5h!&=GJ}HgL*|b z3-;)fn_83o!Gp!EvF+Uy*WhdO;9R9Sa2CCC6FYK)7aGM=Oq?`|eRY$X1yM58xVi9> z>|(2bLPR{&sSmhQfj zn)aOtNr`>u{)5Fn^1jpXIvR`G6|<0@7!T4k96bLr9C%6_#pX{y>--GcZ0xS$Zqc3UI zju)?gF^=i-(KlS2MysF@KLruaqTgB4c?()+q;@xGOXrkLU1$UPQ?!|C%F1%5mj!F~?70j;HXJ=09KZUeJqWSRcnFuSq=? zW9ZxlYuD~qC;Yce2~wsb6U0o_a;9!$DU%AL{_n1R_k~bFzP%^l+IO;VAO>FZ_JRVt zZA<+xc~w&06{(b0J%{qL@R1SYe;xmSHX0K;i=*)fvi--=sL%aB9*sYLFOJ6UaNBgd zANVU?|NQ6CIIPp7qj5K^n@3})r2HR`MscYAUyMd|gZ4-4s@b!GZFnO^A3J0;(Co$( zx?>XDh+xH2xK;Ukl5=7k3T6?;Zb={sqW582hky=z0 zD^kmI@YgvT2meEF|D#mbL_pAReN7-frgVb#k*J!_@qnfaXcJzk;w z-a*uV58}E2eXaV3Q7q@_WIlK}JN9(np{_*w+^D3=ri!V$mf}8Drv4NX*Hk55{;s}_ z>#6~cAqk`K0eMsDk9k2o7X_4c>NSe>Ett%wB(k*y|KbDNv%D3hVI%xepn&gXhJ$hI zqQvB>!`>>6UM1+K;QK6pe-^s3>%0+Wc-o04LO_8tYMD9`C0p>Z5LYS{U3IiMx zI*_p(Y{h-u7n=D}#fdY)1uE-iCu1H+|rOi@J1+@R3_Lq#f&G>&HLvW0P!y`MMF6 z&)fX)N%nBI(;nw{U^rU;^m|kdjk%^&{l;+ihy96&V2E9w=s0{Fqv~6AZ8-|klk8Uy z@r#^|Ro7F3q%uh744vv(#Fw(@;>FQt_l9&K(ha-{LZ`X}yy(Xz?8IX_yi_ji8^rKU`IYLo64=z@NPa*9a~1~$ zzYjka;bj*U;e75h@*|u@f4X&>eOXQMFn*jbQRNU0IF`36itlP-Z>$>D?!+L>2b1HJDy(ssTVpO$e_~{JRt?Z^G9vye`64f{@G7Ti z)D+&~H0d1T8d$<;nURfsrf*;(j7*xtSN(Gq)~dDe#N(-I)vX4xEzd+nUKxl8<&;;g z`YaeFG`A96`ZDziq;lIiPU&mad%>!qC{tGqWOttlwUtAld9JGF*u(dn=iFiOxb$&{ zS;gO>;_rI#w@CcW6@OnBf78X^4dQRH_`5{>oh|+j5`TALp{h{SoQtVK_hJYn3nql3 zXOe_ZTx@e`$ppx>)-r#Cm9F)Y@#iR*XaUxqb;+9e3p1@ka2UcME;;VP&72NdrowNy z#$@Ma4wn+9lS)yXcf%?mH%6Qn#(?&wc)QQkWqqtJTqvEx%SZ8&@JAPYsI)p+{NjCT z!?|W1F3^6o2nqo&0<4DcvQ&fKib010tU_Y8FaZ}5$>}Z=vzOT`Q;zBtwu)1z5B?pI z=_#3BlztIoUZOVcxGdNy(~UA+DbpD; z9WB#AG7Xj~C)4X^CCBGwdQ_&8l;d{D6}TePBO9mxiSrv?OMt7XIXw;rq9b%^lQYgSr&xLw0%nh=%@W9z43X@PHPN4m9;DIH(H}w zrPs-lPgv-he<-iwEnNNDa>bC;*>iIAS$PXHa_1~ss0W`pGkfvOjOn>EGb8mAa%Sph z&CE^BAD2IFW=`JxT>YGdIk_{ZXSU+Pa$3Q~iuFpxu>XmRarr6JGv>|AO2KF)#?JsYz6ERogMUprAMn^{x!cg){)-N) zAeV~FK0ARIkib96$F9G)Kt+x5Y?pSv72Bj%IY{)`F8;A-v~lCj<5%{0H}-`;507~} zw&&EH8-E;+J&Q{il!o?LoRgL^e|m1#qQwi+%rkT5`cXdAimpPq$f&4{tXUja z#inm=H{=wgUL;Kzmui@lFqtgt9+4%PNcP#IGSRM{?b+PU=6XbvB5E2Rk)?_rZa*p$ z?YQk|er)GWf38Q}aSqKZr47rMFVCETs&eVO+=1w53+kc_LvL~ha2u_U9V zZ8CO9x%K;#jQ-*f=X@?w^3SDEnkq0OCr8xROMed;nJpVM%Dpu!Yffg4VVP)yV_7$s?8lem`QW!%E^_YP1cJAIgD-)!ygcTX1UdtqJx_ugSW%6r7e?v|=x@6B<$0ZJ=) z1;Q@@)rapG+nVo)CvH>klifO9 z((ARTYAY4j3e{0#K~bc7ajCy~a3j9++OIG5vo25!s6w@fR7 zec1TzK{l-yr;XKc+HpROt?Iq9J<~l>#P&Vz%avzy+&`Ye5ZxoU%*8fhdiG*`sX#K+ znDh_R81Jy*{*o7F7@r*1R_Dd(a=kfSrYEOEPwV=&t+$oqxk>qC8Ab#^s~G)jtMTA8 znO>X*hMK;uvzzQzt;TK&1j=^uph)o!^5BB-AVG`U*ZXI;OK-CG7O)Qh^fwt4Wn{4N;$3YL62isfg+2L15+Y~AVr}C4klqLVo^P0m_m5)J8xV;xY z`>{A30!;yOIZi(t(-KQ=-53lFv?DhNQ|d|ZtDpl<@;WT)S{!f*btD5CktZ8I^m)iL zn43&L+KSkdz6o}c%gBaPLKT)MJK~%AbWr3?N4mlcu%C83 zZL5cOLOO~j&}cTIw2IO2x=7-yz*m4zfnJM%CJH4q!lQjU?BR|6B%Dyy9~cjR`KU4Y z3h;H{>%bdR;UDXl{xReQuU!t>AMf<*k>HSsg2Fxlg@U((H$ILGPs1_zDDWxZ*HdQj z+5$L2r3pqjuOEv-mOu_(3%(w0mkxgYIQUwMO5uU1z3sX1g;RReRPaTx8HjaTI}Hg3 zFb57{7&Q_O<{>lMj!+eg^l(r-Z50Zv1MEi7VJIAWLV7%G;aDuB7!i6*ZCeRId3@`!X zfHYtMupB4_o(HxA?*iw5?|^%N-w}@M4DFV^$7a^S1{`L zkrC(x!~r9LNx(v26|foD2Yd*83)}(P9z`nvj{#$Wxj-?n8F&l$0JsEP2h<0bc<>0rvr4oY6V};Xo{40!9OqfDC|EZ=O?f zDz0+S&RhkCM-^Ai-u}m)O6RV0wJm$`oQ1iML>1h>i=zKV)>o1}jA{OwmNPvx=*ule z$P*pEEO+L(e3`Fw@0ozF9%`wc(!b|VgO=m$*+TX`WG=|OPDwWOJLoLZ+psFMkWGfn z4q15%*>cFrAq#II+X7iQWb(gfd$j%k!Ff|-{J#m#!%+PHJ~(Hq5B*lT>hN+Uvm9;Q za5UDtxzd%&wegj_znihaE-^MNodNmM35PT!(n?YD$sIZ6O1a>0`n?sF`Shs_*njr(x zML;@uqDz2m@GWBwialm`#?1rdMDam8w+npBxP#)46Tm6RL2X==9?KmPMCZyp(G4=M z?Sd~CfkxQWfxa7x^&9-d2t|rij&#MI@D73-&{`l0d>!Zu25isZABHVb_%f#(E(zYT zaU3!0fY~rw4|*A(Xol#paO_&(iDm$Ak|WTjsD|hj;1uLUf2K6}M$n=NPHgt|pb+x3zjKn#0qNKhO^@lSehTvzOt=u_Yg;9CYk6b$w3gIx-8qQii6@GXNO3W}nE ze8`D1U=4Vpr(~Y!b(y!NN8|8-LnRHshoO=bGL4Br{~NPn;yDBib(j$>}_p30x#Up!)`+|0z+AMD!48#HN7023&!>0@PzD7E*2gaTrYlPlwW-$vAj`rvv2cqopUNqd6Tq z$tOh~^8m4>LA}O8Zi9l3#8&_s)pS%A=vWLn9gla6#{h&=I=9EBN>5B@_45FYYC5au zPmo&zwA38Lp>G=py$J5x-(bsh%c9*KSl-T&5g`NR|9Ln6FmuR0Z)--EOYFhZUWTb6qmgKP`^?rHvDNx zPN7(<0!dEc*Jl9PQ=swX3aJYy(4atux`Sv29^OVZqKM{KfOyW1)es?f*v1g>bh_7wjbEQ%fRe*j197Ho- z1T~aNeNS}EYOL#!r+}UZTx0`!TEMv2i?INzUn4g)=v08ZARTlgKy#hwOebbD>}P{s z22%Fosjq<1t(6K30JX|I(djau3A#q+iEfkm9iZxUQo&xJ0{~hxh+1Wy=yL#7;swy@ z>(LUZL?-Bc8-CJ|;GV@317t*WjLfHiZk73R&;tM!a1bHrG%R+^4>Q|vvHgsZ&Dk>?I8`~u*uV%x!OUfZ?XC%u*Z NR{mR+ZO{Cu_+R63y_^65 diff --git a/c/build/win64/output/dxl_x64_c.lib b/c/build/win64/output/dxl_x64_c.lib index 3f350e2c78b629f4ca6da042aeffd5341f795887..b14111ea58452ab44e95539866cc8aed3863bdf6 100644 GIT binary patch literal 39780 zcmeHPeUM#6v2Q{^UQ|Q~;Zs-;14Inj%Wn7(V@Lua-^<+%fe^CU>~4}x_KUlBlMRFr zAOr{yLVzShL{vmXRQy83$n#N_Wm%MuvR?Tp|KL^mD9W<@gQ9p<7G>${o}QW0J?ETp z4`(;;pSM-L_e@WB|7Lo6=FHc<=UmxQ>)bGF(!~w>ud%uL@|lfIGb=MSe}+w7cIk{J zeq1vN;HWzR=IsW!<}kqg_W@S#utd*DYhGt+e;a^k%?(VeQJ1K_m+9vH0EVXFCsOAg zrnOH27@CToNS#xdI$i`YGzUMCx>s8IEq)@cf0k+8s{lmnD@Fm(-LnrI@^ z#ti^OJtLL?KZ)LD+OQkI(3$v&wB&fEMQ;EQJvfYDO-ecO@1VFU;d8Ru0h-et=Kva8+X%PKG zbjy=W+y4qcwCypb+kXW>blvq#OIHC9?U=#TikL(T?_=smK2aa~jcCsyrk$$+h#tba z5-nfMw5tX{bUn5!(TYDatvnro=%zn1^&SKu+KA;Qx)19@bni<{2hra|x4p_#MO>nL z_A}i$3xMeU-Av1#1t4nK&a~+@0HOg*6YXBdbkjz}M{0YMX%m*4=svVfbpK?ggXjaI zZCECvR;)YGE{qYP8=qsk|9zB4YQeG^dIvv|dZ#fB{0Z@qmTY5Md<6i}gLg4KfbCCo z_o+;GzJc+BbfCiY_}dsiNROefh#pD=$25d?i3WekR67>q3F(eCOxr#{KOk+ti0L}?Ez#27Fzwin@q@IW z%GCN7^cT`X^bJuz;uH04V0svRNwo7K_@zBVvCIA^$bQ?&T1@y|$6+NJ~fOrtZ2{6Z{OVY#q+luD{4LU?sTO!JFsdp zMfH5!hZ&iA8#?;ehZScSESS4D~)?-B}k@aj3p^$7(%Y1Z6(RHOk&GQg|-^Ctt2UIS!QBOGK5@G zJ@ce;5@p*KoLj?|OI)K*%Zx)V5Z;hj0p`5}e;jW6F}@ z-g-~laIGJLq$}atfq^e%UYcEEJxVPQawc0?9%%qu0p4v5WAPEbOmrPmJ3@;~i5n7~JV$e)yukGmX>g}$9 zPO(JK5KlYXdiuHthU*ZfSqiJK#Fn&ncal%i%xw9TtZhv*O4f6C$>N_Z<79j z`B=+29m8GKjyg{6#k0rtxmY~^>~+cH(vCi(>z}=@=TOz0By@40YQa z_ry5^gWdfm!#^;85Y6~D5zm~9*u#UQwxXxMYhcR|`A#!fj@la=t+l7Wv%9t4k;vy} zc)hv9wOV(-QFkDyl)+_A4#K`sc?S=L9WvzlT!IUA*k zT)<#C7qm_+OtaKr62DF`gT=DJY_2h!-Zk1$A(`K?NY%U!U2ZU=YlIYo(UOTBi)bs! zw5>YQsHS-iCy}6ujFjOtqnHr$)0xI#s^@G;Db`MNggrlHvGzndEhX$(xm5Z5B*oej zX<^TDg+0X)lJuUjrub3i2?IRwb6%i+CR`OH*@kCwv-rthh7D>GZ&2n7caelhCK!h4 zFnl7&Z!@9cEl3RELc$Qq#D-xy44(+{9fq|aG1#|cUV53*&M18*_M9pDWUib9HmWJ1 zlhBjE#$ZzDqvMIQr=Ig zsiHBJ!BrX*48o~;3MtB`ri{jN!0}cCi!#YF!N^?+NA5~$Db|*9DSLjbvGzn-*t1+=PjQ5#A6KkB zkxokqdsZ%0K5ANPiXVj)9;|(?)TJ@UkKE)?m1G;9$<5+N?xa<`lCmK4g}ca{NG2GD z=`egE$Zs>D;VnoE;X=X?$;5_XIt-r(@*Re?ATijtWL|oi(#|M-Cia{u`ed#gxhrbq zb`pBzt^^~ulj0GZ98M#*VG6;&(?H{oRq*08ifM0UW*t;Qje{nz{>Nw^HzV5I-j(ZPv*s!X zz`OXl8&90iL^^&6z#EGICO-)9``rL9+=Vwy@K(z&@zlEhIO0AA@CQ7F-TMf@?7aXN z90GXfAfDph3h>?*fTpbg&*SOn)H-4e1H6SNxhn?&p1cL%uiNo-ejC8AZpYKq>-c1P z#tzhN#ajh<#-aj3+sA4z@JwDoW2s^k2m41gI=_a zb(ne|z)SaHxv>nd-iEqW^v^v2vu?yX-H$$4h9|}?0IzMr&jGyUf_2)6`fuXN_G086 zLjB1ow;A=PV%a8QS?KD*bEyA5@{dQ|caWwb-k(r^8~W#p#du1N{+ay%z^QkmztBIG z1L$M)&q4Ih!bbuAj{bRZFZv1n)A9tC8U3?r1ltS!GX?#$7ya`)^v}W}^z9(PvFN8Y zcL02VWw;3a^cwo-H%qZD=%4BWfWKh5-bWujg+AJVKAQM2`VoEf8}!jj=%cr=%oET* zD{sJhqmSse%3rXo&tO^K!?He)W!;HoorUfBG?uju+w)i~?<-i=-hBWKSl$n?tcS6z zE$GKzV_7F*nRjAY|Au9qg>CvWmUYH0d@}!QEbAI<$9-7V>FD#z(9eIvvc8OEU5mb5 zy9j-U{(2qD+K*+Oj%`xGc6}Gia2D3%P2`=6ZMqQKZZnqqbu9M>Snk7E?mLgdn^Z6X z?u8$~&tNv(4?luW!zS1d=fXyK9KHbez>9D_tb-M>9Wa1A^R zKZk4K5%^bF0Q=w<&<0(w5FUkpgPULxJO;19$Ka#zFE9~~fl2TYI1Y}56XBEa2{;~3 zfRDo&a5|g{C&6Sm4W_^;a59_&4R98G3eJWzVF}y}H^2s140GTCcnPk8-SA_$5pPCa z3U|Qsa2f1?Z^KO34&Q<%*aqK(X1E=mgG=BxcorIAD?9@gxD~zuGhhV14%a~kTmg5% zci{7IH+&Z^hdbc~n1x~ZeK;Qm;1EoOes}_2fqC!{ybP_-3G-nuyb8-;DXfNeSPtE= z5`z5jpe{iAWl^Pz5$@QX?>KHbE|=84xhbJXm_En4J^#jT%| zpnH8L8&gizpG0~+&yh+i_zDC~sfDKCN_D|@HuPN2n$S#VL35P>+BcNCly;kT?4HhE zy@T!3T1-w(twG6hMUgyL5SnAU{d>j~9F0O5vT5w8Nurg`bjaDNq71ov-Kgm%ZMJ5D zBg{J?VKX&DOAMs4gr!toU^1C^X?qDjFqUKpOVrlp;KRGmaZ*lK^T7mDu?3{!3&iZh z2@ju?GJ!~V!hXW^#^voWr!9F|HxK66jyX5ESYgW|HRp5lXBm}OYce!*E=f38=cO#m zZFYr{otLL+hKW$cF!QQ!GIOqhP&qk2*FPpZQcaVeRhL$K#X=U=@v_S5^0J%Cylb%P@O?@&!PPQt3;2kx6`xhw8j*b zEUl?a>jkBc%ag}ZD0^L%o z_}b69(1CZuqEb33rMRG@k7e{$U$R{;W}ljwxYFHx(|f;;D=M6@(#o=s8GCCrJxIEw zw_~$iMRAiXm@o>C?!$6F%?7DtIRwcQC_Hq#doVmsp{Qb;doTG}sp2T*bgrJ05t!wq zM6)h{423rr6Nay<7x5KMMt>0xq-oy?#FgrT?QFOmRqJDybXqQ*hzIY*x_?n7Do(^H zg*&TTXa!|=+C{-bwlf&=omt8E;jEciCX$dgvUY?E%OTjxh~TSo_<_KKvTyU#1BYpO7cK!XJx;`0T-LONf^x`__94PN(-=Jiyv(dO)Jd;KDtWMGW5r!KU z@^4pWADMdt6f1V)0KxP@iC0a8j2?MAyd)@GlPZ&97^8|~Y-X>9u}BFvc_T>~J4q6a z$aSht`Bj9H5z7O`pKsT=iYb>&Dnl-obcTD6E3RK41zhKmq~NA|1j%$ojFeondb^yH ztX6eKX0dILIbs4FW`3&Vy$JGu^xZ0t_7Y_Bw zbVafq>J_r;XjC$btsNSy6~nv4t_!(kBDe>aF{oCGW{t?JLtYn#E5ab1x(`#M>2~xzgZQdm@9cD%gofBIT}H*$gFxFDq|=Ixyc;vy$}Yq+Ijvx03dmumu6eCnN&C#WHo+F{%irMIXCXz47Ald=k=7DipUJZ3T}Dds zRYqy6?cC(bX)EpO>mbR#!A^kai7?E1$gPCj8b~j6P|7V_c$%xzWX0thm?S~9Pf{eP zRyH-)b=?EX`*jS?>;21CJi91F7QF+x_sWF6HfF91sP#nZQhn~Nd;z5_NWOdLVF}#( zPh{)$$B-Q~v5}HTdCN9+wJW^p#lm*@pteZvY4{5p$)!7a^+VhOk$3qj;x5LPaIFwB z^fg$9monJ+I;j;X-b}vjTW0F6dFa*P@2#&?@oiDi6rWHJf z>71qlvUeJWowJK)Ys1acZH}uB_e;;L#J=n8zXd+MtG5@gl>D<_AZeb_*uZ~lCUxyP z8ou@)|Fh~7c!GW$USy!Z>0RAxhu5En_XqfIE`H#J0QEN;PM9;jrwcpWc@>v286W-~ z>Ax-GX#AWFGk#&^W?D9$nB!?Z;yF3u&xVFyOu)~{c*ahDA6Jz+A5J>qBglQjL34*Iw*`642WE{X9JibZ*Uw_K}NDNO(cU#c=T^M%?XG2=h8p>N7exk^pn2{ zcx3^9-sQs`>qdSYV3MlzC?clPToDm7!9>i@uxMQ5?1S3Nl#9ZRCC}O_p684iK zhU|_*B#fqYKZVe_Ke$lXZfI(6lnwMtO4MDucF|Zi#ng17zfZ61f=Z1d_G2hV;c()v zN+`RAIYbb(ugYViTq$(q*+)SPl`tVZoLC_G9v zMbM53(JH0UnzQS68rJPtLi0CRN+U&L<0A?wbfId!(ZqTL={SWHy00iwvl|$LC_D?j zN4M;Poxs3_h0)xECqSbCX;K<3bYtO2Y>wc4G>sQJvoKyP@;`=nX7e-o#=3G}@qQL- zyN{>PLT4)QQN&~n?f4X0=*psKP4<3uLl7yaVx)Y+p_zHUvaI8CG_{IE$O#h1Egm&o z@d%03>yrl0-B{B=Dpj&xCrX^Ls@J92qwpEnUMC@*+R9gzDIWJtkvHe$0IO`&$FNQg zuu8{#WYnL6Sh%0=H(s<0RcbWRaY=S-orA4)ibfiv_-M|FkIx|DsTMKgh(=Ycc%(Gv zM9Ne|JuMftY|O+^PtQdy8$HcA(Q_Ww^$bSMIK9#iR;f|MQBw{k&6dw(Om`lpM`oQG z4N^}0(D?ExjTAOt@i97rb(Y2o8?7)_bI$Db(^#*w87p<6Ry*%Q^opETqeyAU!3>>R zG*V*Gc}@;y=-k4XIqT8}tmnB2CT;QABUOc<-8_mIZH|nppU%PyomxD4B8cZ@A%-q3 zj2P?jpJ7C|-LCzoQzgAQRU?hnJ1R04Jf9KWDJ7rZ>u@RTOTU>H%yB6`FUY_P!$rZ5 z#-ow`aA5{s7%YYHa`pkv$NEiUyzFZP3aI$_7Mrtu*5Zy;pO3BhE()>21}q#gF|^Nx zXkqgeN6VQ#(GJygLQ^+5bfc-%Xks(+PP#b6^0xpKO7RgUr+zd$oDpJ*iv%T6BX9i1 z5Y=79(2#{&vN_TdDM2r8{I*ywMW`aN!z8 z#-dpvR!;a9#*Dn#z8GR2kvH4y5cLSW*{%vPkIg(E2TX1g|pdSu>g3(~kpqWwrYrgOUXn%|qkWpDoL#R|(6dVs)!oC^)%g%J z&zw0RosBOOIN8-wo*jiRV{?)gMANs)m33XwQD9w?Gs`>)Yjz!B(f64(MBzwm%JClE zHLF^Ta6?2vj-nnhj8=;gZi5uXi1ny8i-D6F_Z9BIZH3Vydyvc1XrTiOw^Hne#Pw;s z(3yqtV*AG{2v2;)LHSPmbri7?+l{|LBV~8sF|FH;h)7=#u;0nhwb7|j)U7G!-9o2f zD>YK-2#I0cq_M^|I#x+6ys2Lj-Re=s(_^=Jl+qrH^qg%TWelP$a>M<0fm7OR5uEJ;r?lT9k#>i{ zG2hfz0bG2qG1fPCc$CsUi}cMqJxXbhMcxQ^85H-^1Lj-cB|R4#sqapqmGxi@ZD$It zv?n8Tyn7Vd81&o73}sh{=>Hm^NGFN`=&j)E2 zs?=zrF%lb3rqMz-7LJYB*!kr&Ug*ric(FOqQ;1hT0&}3R2%OM?McXU(UG%2~PUyJ8 zIFUa5RfCgr&8>I~MS9lP6jEv5MUcL(kV<nDz_IDs47{=}7W-D(H#6``w_9X=_FRBhew7(AKtT)rFNjc;UrFNIdxmyyVPF@;vv zld;JBzC#l~`#7GF`GX9+(%y_j<_|OQ%K9@FnLi5f#y2v5oI)$@%SdFtltL@*$;hnX zCk`#+KvB&hO3wLTmN;Xy{*0}yf9mkYWHl4JN%x9I3PYp#yfw0u_A`wY21aqLNMsyN buu|QtXk^4z?mw3}<-HeKU%V=jQoj3NwkEXi literal 40458 zcmeHPZE#*ywO*83xrkT+wPJ;WRVpGjX;KOzhPFUUKS|RTN@?OM5EuuLm5zTEPTD8m4`}hQ{e#21fyF^T@R~TA#3i3g%J%(;LOq9?C_yn~d zG_>X@Q9@Jj32L8UsO<%!gl6Lt)Vb2q@9+s)_q3t4uM#n>YcSM-GBB;3W2mEsG}Aak z8#WLzb#1dW2A@oSGqnByQ9@_o6SNTZVOlWJ(A_T+G2L~Oq1&5@n0B9J=waAqI((*~ zhfr3g2X`8JU^)@geJCT-qwpWoBfw?488}Sa;4h}_e=xLlF%i?|*9{GwO2jm{+fY9d zF%8T#bnD|pOt)NOXlFMO(>2!`+VvI@(~==W^WG$4>Zv!h3I1Zbx5?1nu|!MY5mWaOLmU2x_5kgF-4gWngO0ptXh#PT zQ}d&S_FYQEbREjYbYQBXMNbnkE#7Hp<7-4ry+||Nb&8?uyMYgCfnS+6q8?0l!d5~r z;}i7AL_<4JE~X{$1=GH#3|;pO@IeQT7+O3YxJ-XC)O`W!2kQN^p@qLi9Dx?>F?7!q zBBs0EHFWzi#1UxsWma{bkl4@TVFvOfwn-FX=upMAnY>rZ!k3QEaC{X3w36?<*1>ZzegN_u7PivZbMrz zUH!PBC4YsVK=a{GrXJ`qZGv5g!CEgy?G0$sb(P~RJf zC(w!mhH8_Dm{u+}v}gv}AG829k=%(l4U(hz-Fl~9l&=9bgHm@?&{}%iU8k}Hg z7xbBS!pBUv&M?$G74Z(b4R)C3jWyKLfw%?Df6h?vc*GZI(;J5FI|JhiXz!bb4!#Zl zg7!RQXx;|c0o}L5(6Y(sx1c-TGqijNeg|C(drUVr8CvlV_#IR`XlUgz`2ARG>)Zv4 z7d5xE&c0&Ftme6kTNX99b_{j54oz=pZKu}Og-hqp&x+73UdBkY%vri{UhC}3TP}xA z*QUPKb+z8XzL|sF8=E`ZI*?B@_G{t>(^6y_-98)MQ4E-sK$~ zIZB?JqoGR`w&C(x*Fa~s(wZGuO)^FGeA|Z^xq9o{de(&%H;N)BPg8nEL&}^yP46D9 z=Gl2VsoRpmNxv=G+S8ti{g5eax-1#uNlEfDa`Z%uD>cE-(ehEQbUZglLx+JYoag3f zghAkR1V2YhHkU4(=oC46zP*%^=jLdbMs%eL+c0TZUp;SBvjeLpQiCqf0AWV1o``S_ zH%sK?Y38~tfs{FUn%+Gc(6jS&Qnw`#)^BSt*hiDs z@BCyfgy~eusGCE024y5+t)Si6tqOFoaya zwv{HcGN~;q722xPw$h}qWtpih$q;gB^^zx*lPcS`Fu66fTL)yF-8~1n*1FXe)>D76^)!|0Cp>H2JqNkgy44oe6F0J9;ZIIlbIJ?W z2tJJUwQcPKy|t~)o&A`?sDwjb)7v`$rzIbTx2|(wX05laqrI(vU~yN^Iw%izV*-@V zHacsh0_l{I=z}Fp+ZOb8bapQs+(cnIl}fT~`3KSon0Pd@H8*MU4~9SB`2NB0Q30Mb zHp6vX8UJi@;UMND{hU<7YtM&6+?(u*TCKOnX0l8r&ux}Ekc9=uNcPpbdIGySEN?Ya z0?iOM1yW*Aq`fu4LuEwD+DRtAbJ}`3x;tysr&30utKUpgTe>!N_6`nEm^M;ys1jSS zq_ds9oMq}YNqz*0awdt9H3;`wK< z%O)4LZAx_gv)A<;u9}lHx$Vi@n@gHLxt!kqPL@WFdonq_eVsi?hJP^pJ_!3Z5zi(U z*n@qnw!EvSqjyU``%W{A9Je4YXhfQmm#51O=6`jRVHmV@8fZkcm2{HVJXEJ9g$^f`;AxMPF=>O6 zgqWZF)CChmXG=;M?JP&w^Aj9vPo%R_!k(4Ol+RCTtUZwy_AFP}Qyd}5?-^^#JgPil zz)TaJ7r37ZR|QF9!!u2@_^D!!4Q>)|Q05DFv4lvb7zxv1_(YK3l7xo0ATfjs8ABvf z8wt~4_(YKJFsucMVSLNxrI$JFjPhq{&za&+!kLH z$t7!(wxM)%MAwh`f#L|a!xZH z^<8c{jyDh0tC2n{!9$mnF=0e=M`6Vb?mk!Q@)+eudUmKv8XKNzn#GUwX{&f8WkKc(cd%);=%9%{Z8So>0y%_0T zt{dM`KRceg95=qRmKo_?PA%CvUNSJab}e={;21t#@k!&?wvGXv3{bN14NJCN_5FBxR0<#hZyP-3MFO5lzK8{nLw3=EX#>ZNz6U{D^vWL;nvgzyPo5 zPSh7P5%qW-`r}Zhr=b4~^p8M)JaqpAx&U~8hW>BiqdoA^lzZR<*g6IuZHABDhL85c zN0%KUdJjH&5mcn?0>03SUIAB}@gj>1R3 zhmT%^k1o9pe!H6JuP9T~eB{AT8{nsB;HPf*sqY}sOYqZf_-QQr=vuT%AKC=<+D_l0skD{8P0h51E}`4#2lQ3i zP0!QCw2PjjuhAZQfzG2odX&CEz4QqEoMzEo^fPLq4!V*K(l2Q-EuvOhP0MI4T~D8< z9y&skX%jt6v*~VnnP$=fdWn8PU#89U1YJOb^iBE_4bV|KAKmmD^hK)C<1~eCq{rwQ zYNM~v5Isp3(iZyG|F^;afi^f1Gp7%9*TuZ(^wQW(qimj-G#HMW3%SLQoFBRMni6!c z-*iLFsrvI$uje^ZX}P(m!BcagDY#Nyu$>LRg=n>X+U@n3+Jzh6KCQ*%9Mu|>ELRrE za|OZt!0o15O~KJ9oFP4Hk8ey#^D`ZCey%7(;TAbG-3%`+pW_JgjwNhnrgN!*OqQ^e z$qP)Tvny>c zr!9GT*BfTqel;t-yhkiN%H`%XmCGthdqFA+wzrXv3=f*g@wl9mj$6`F%2j4k zwzJ{4sMNg@yCvmxg-}M%-#zg{>2ZQ!<>+M*xp)~&W=d_lC1-2P5SAk~i}&q9Jzd&F zFWn{c*0~T_OYNjwhO{4A`+NEQesLatMB&8SM{0F6NmC{2_+Rq_o-bGGVLBuY#ix-07I< z6IMzWO^%CRz#YZ7!*`^`Zi3n#&?hXx(YicP6_={zjT$4eTMuSKjVZo>ux8E{* z0e;n=UW9Y~UoPp@;gr6VkQ^)cQF2{6Vmdp_%30gzvx_b!Bq%v6d027Fb3W*D&*~C@ zKT&c0y!aw%{)xXgz>ROWCIF_-ZM-jVm=)JA!2+)HNLuhD-h*VeB8ik- z6??lTCtVNgjND?|E@oaP2AbDf&6u6(lrD#p2_5SA%At;#aj474l+0%+hdQoyXv)EUfLl1?c}hnq|atfYN5ayDTs z+Nncg&prz&hih}BwY0uI(^yO<7+hF6v*5JVc5ZUzw3X(y7E3uuU&|DTpBN)qO}TZH zTS4h%5~SR+$4ruSnyt9}q*!T!OOd8nP_2t#lUUC7JDjJgh? zuh=Da)M|u<6{GOG2?9zfNWOc)ve94-1D0OB^xF{{jg­T+LdYvBbpBW%YiZj1De ziodLqUQm?RUc?O;dGE1a+(X$Ct~5f1z6@;Or3@NhC$$2{Tas_PWHNgX8CFGzXeEbX z1vvht36Ej>QHmiLRz+|uhVOjAT|KSfF_O-ipv&HwFzk$9JX;%XmTz-hbxgnX%=*~( zJO^^=mGTQ|s){ysSRCW6z1S_Q#V}d<ou&V=Kn3`PgGS0xme}ewUGET&26HR^9%1yUyoao~o0q~q0^P6bW zt7Gta2JQgx-$zxY&ZE=Ee;C}~C3(2bg3m*%PFv8`UhD1eT{|#oO7j;d&7Zpv7a6jD zr+~#pVZw!oE9S!9l%fJe6U02$PX%h^cR^7ZEciiI|_G zXr{>d5z~>@BY6@LGtFgj#C*pk>?cPI+Z}~S7*6Yc7SM%1Qc>D(7rS3jN_*OW10d$N zNKb3DE=qbT_cZy}L`|-zH8?)^=>KvF`^j>n;NRi+_G}a(5|(AX+u(w768|a{ch`1Nq3o7NnQl8+P?s}NmobbYws0yU&B#ZZ2&5B% zq&J8vVqKh%#hq+yh*hVZMx{roh6vh+LbUqIXpQ-G`!wn{j?w&mn#xF#*!ZwQ3SFpL zZ#c0YK{`nxh3+eh)aVArAl}b{_xKiIu#XtHur!*R@C0Z)Af22=3*A^c5*s6UAIai{ z&Mb}B(2yUC6HvcXfaiBwN70WTl{juiq#Ei2^yo;vPEGLK_oX$EN)03KW9{`Zi8E65 zx+uTBK7;le4?MNott#^Yd>9$;KOSI(fv=#4;m3vu)@cD&81$vFB4gF*z`~ZZ+ajnM z_0#fO>m0P!85(JX;-j%3K0Xh`Pgum9Qw-(8@{!V5(0X40>L&|PtHw+W^;3nYRime| zAbKXFt`iJu&H;~huu2W5cNAdq9PiTx(;XRAjM#>P_~G&8OpO#aU-@@W1nV;zD{QpV zSd9g9uFs)f6Af18R%_tO@|Xp!#*y;b0?g25FUX~c$t*x??3u0eF0#M*y4RneQD(?}!r zj*852CmTd}kY|p#b-0xFrQd=I=I|V!pU=Sy!$rXl$D@({@P!<_Fjz|C6|7#*L;cP( zc=;#o3aI>BKQ?EZVsS^R&&O8iUktIr1}q&hF|_kTw6OWgqZQ1acwgm9jHWI*=tfhi z;lyUaxWezG3qmY^P_9tQk1z%GgqZR& z#3<8xW(P2bmYd?(M=iL(SNgD9%2@B(UFYcnOV%^@MfDOQAhpF zHamk>Ff^2opxB%3iVW)Ud9z)a#XT->wyQF@#a*>@1Q+Zg@{aeM3~oWUDc!oUQ^>hM z4X^#GTIn}k#kcp>S+o(_r)enI_4*V%I}fPtsMua@%cFnk%C zlPmz5zHqIq>xvEoYg)l9^K{f~A!G5EiZw*(NNgzZ9^a5!WHG`G5d}Gndc-gmTa0iU zq%20PM_pqvFqv`RqYm6w8ZEL1*_=fS9ay@RV&}w5vUs60OXJ1%k6Rc|d<#JNPWyEj zu@T#iU#gMvJ8GRUg*ryc(MMs5_tTT3i|~Y-Q#p>7?Bb?vAsbf zRrX>GYn8?tRS&jGEPMw-#kx*a^x$fZG^!qK(^%C#Sgy9lo#G z9%5DZVg#)tM62${f}JHki|w>%$(Kl~d$C|G!?!QiYNYBuj9{(PSflE}^%84T`*N2? z8dVQ&&{)+y80pI!HCFW~jP$PV5UaWuBWRmKwCaA0^yMClmV9@sx)&q;t5+jc_hAI9 zPh*X$2XB;EquQ5i8fjEL*srmwdoa?M2Q*goD2(*3!4Rvu7b9q!L$vCCjO zWxqutZC8Sm{04#w;PU(7vA%hmN2%vF{E&n1h%63Q)zdV|u~c`FzZr z9xA}h4^dT+VXQx5->N&5gFG^*vGbC{7S;VglB$tz+~L%(VD8J`$$VHNe{`vv{F1OXJ1nK;H!3z;T!ZJt1&H2bOKG*zYBL zOW=f#D~%KB!%rqS1y?c4w@{>KeOn<__FV+&DTP$ody$#ycYu`sGPY`$^6!#J?|m9L zTf*PL({QERD)vpr@8;lDZLt{MGdXyb+byy_`(A)oeU%$qzdxHntL)3jd*%BXw5pzr zjq}erH1X4jI`qr$S;Zpd2RV3^y;(3no`gBh^Er4`{Tcf%)(-=`(T&U(GH8{38Hvmv zWzed6G8UOHIyCWvnxh$+KhD9c?9E7I{v-#lsy}0q`O^SzbR+Yn3|eJhMk4cP8MMlt zjLaHdc4#>Vit43aanAp9i8Dg$&)C}f6^Az>tC`sSz+Y&jFf>Zfg<@F8G*%cG<*_1> e@yiq|)4j?@Mr`H&s>G@8y~z6FR}v}XyZ;3%;EW>x diff --git a/c/example/dxl_monitor/dxl_monitor.c b/c/example/dxl_monitor/dxl_monitor.c old mode 100644 new mode 100755 index d04db217..be01c3f6 --- a/c/example/dxl_monitor/dxl_monitor.c +++ b/c/example/dxl_monitor/dxl_monitor.c @@ -488,7 +488,7 @@ int main(int argc, char *argv[]) printf("Detected Dynamixel : \n"); for (id = 0; id < MAX_ID; id++) { - if (getBroadcastPingResult(port_num, id, PROTOCOL_VERSION2)) + if (getBroadcastPingResult(port_num, PROTOCOL_VERSION2, id)) printf("[ID:%03d]\n", id); } printf("\n"); diff --git a/c/example/protocol2.0/clear_multi_turn/clear_multi_turn.c b/c/example/protocol2.0/clear_multi_turn/clear_multi_turn.c new file mode 100644 index 00000000..5fce73b8 --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/clear_multi_turn.c @@ -0,0 +1,311 @@ +/******************************************************************************* +* Copyright 2017 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +// +// ********* Clear Multi-Turn Example ********* +// +// +// Available Dynamixel model on this example : MX with Protocol 2.0 (firmware v42 or above), Dynamixel X-series (firmware v42 or above) +// This example is designed for using a Dynamixel XM430-W350-R, and an U2D2. +// To use another Dynamixel model, such as MX series, see their details in E-Manual(emanual.robotis.com) and edit below "#define"d variables yourself. +// Be sure that Dynamixel properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +// + +#if defined(__linux__) || defined(__APPLE__) +#include +#include +#include +#define STDIN_FILENO 0 +#elif defined(_WIN32) || defined(_WIN64) +#include +#endif + +#include +#include +#include "dynamixel_sdk.h" // Uses Dynamixel SDK library + +// Control table address +#define ADDR_OPERATING_MODE 11 // Control table address is different in Dynamixel model +#define ADDR_TORQUE_ENABLE 64 +#define ADDR_GOAL_POSITION 116 +#define ADDR_PRESENT_POSITION 132 + +// Protocol version +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel + +// Default setting +#define DXL_ID 1 // Dynamixel ID: 1 +#define BAUDRATE 57600 +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define MAX_POSITION_VALUE 1048575 +#define DXL_MOVING_STATUS_THRESHOLD 20 // Dynamixel moving status threshold +#define EXT_POSITION_CONTROL_MODE 4 // Value for extended position control mode (operating mode) + +#define ESC_ASCII_VALUE 0x1b +#define SPACE_ASCII_VALUE 0x20 + +int getch() +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + ch = getchar(); + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + return ch; +#elif defined(_WIN32) || defined(_WIN64) + return _getch(); +#endif +} + +int kbhit(void) +{ +#if defined(__linux__) || defined(__APPLE__) + struct termios oldt, newt; + int ch; + int oldf; + + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + oldf = fcntl(STDIN_FILENO, F_GETFL, 0); + fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK); + + ch = getchar(); + + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + fcntl(STDIN_FILENO, F_SETFL, oldf); + + if (ch != EOF) + { + ungetc(ch, stdin); + return 1; + } + + return 0; +#elif defined(_WIN32) || defined(_WIN64) + return _kbhit(); +#endif +} + +void msecSleep(int waitTime) +{ +#if defined(__linux__) || defined(__APPLE__) + usleep(waitTime * 1000); +#elif defined(_WIN32) || defined(_WIN64) + _sleep(waitTime); +#endif +} + +int main() +{ + // Initialize PortHandler Structs + // Set the port path + // Get methods and members of PortHandlerLinux or PortHandlerWindows + int port_num = portHandler(DEVICENAME); + + // Initialize PacketHandler Structs + packetHandler(); + + int dxl_comm_result = COMM_TX_FAIL; // Communication result + + uint8_t dxl_error = 0; // Dynamixel error + int32_t dxl_present_position = 0; // Present position + + // Open port + if (openPort(port_num)) + { + printf("Succeeded to open the port!\n"); + } + else + { + printf("Failed to open the port!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Set port baudrate + if (setBaudRate(port_num, BAUDRATE)) + { + printf("Succeeded to change the baudrate!\n"); + } + else + { + printf("Failed to change the baudrate!\n"); + printf("Press any key to terminate...\n"); + getch(); + return 0; + } + + // Set operating mode to extended position control mode + write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_OPERATING_MODE, EXT_POSITION_CONTROL_MODE); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + else + { + printf("Operating mode changed to extended position control mode. \n"); + } + + // Enable Dynamixel Torque + write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + else + { + printf("Dynamixel has been successfully connected \n"); + } + + while (1) + { + printf("\nPress any key to continue! (or press ESC to quit!)\n"); + if (getch() == ESC_ASCII_VALUE) + break; + + printf(" Press SPACE key to clear multi-turn information! (or press ESC to stop!)\n"); + + // Write goal position + write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, MAX_POSITION_VALUE); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + do + { + // Read present position + dxl_present_position = read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + printf(" [ID:%03d] GoalPos:%03d PresPos:%03d\r", DXL_ID, MAX_POSITION_VALUE, dxl_present_position); + + if (kbhit()) + { + char c = getch(); + if (c == SPACE_ASCII_VALUE) + { + printf("\n Stop & Clear Multi-Turn Information! \n"); + + // Write the present position to the goal position to stop moving + write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + msecSleep(300); + + // Clear Multi-Turn Information + clearMultiTurn(port_num, PROTOCOL_VERSION, DXL_ID); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + // Read present position + dxl_present_position = read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + printf(" Present Position has been reset. : %03d \n", dxl_present_position); + + break; + } + else if (c == ESC_ASCII_VALUE) + { + printf("\n Stopped!! \n"); + + // Write the present position to the goal position to stop moving + write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + break; + } + } + + } while ((abs(MAX_POSITION_VALUE - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD)); + + printf("\n"); + } + + // Disable Dynamixel Torque + write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE); + if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + printf("%s\n", getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + printf("%s\n", getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + // Close port + closePort(port_num); + + return 0; +} diff --git a/c/example/protocol2.0/clear_multi_turn/linux32/Makefile b/c/example/protocol2.0/clear_multi_turn/linux32/Makefile new file mode 100644 index 00000000..ee02816b --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/linux32/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m32 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x86_c +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c/example/protocol2.0/clear_multi_turn/linux64/Makefile b/c/example/protocol2.0/clear_multi_turn/linux64/Makefile new file mode 100644 index 00000000..d8845c85 --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/linux64/Makefile @@ -0,0 +1,80 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) $(FORMAT) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib +FORMAT = -m64 + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_x64_c +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile b/c/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile new file mode 100644 index 00000000..28874ba3 --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/linux_sbc/Makefile @@ -0,0 +1,79 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_sbc_c +LIBRARIES += -lrt + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c/example/protocol2.0/clear_multi_turn/mac/Makefile b/c/example/protocol2.0/clear_multi_turn/mac/Makefile new file mode 100644 index 00000000..7bb24f8a --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/mac/Makefile @@ -0,0 +1,78 @@ +################################################## +# PROJECT: DXL Protocol 2.0 Clear Multi-Turn Example Makefile +# AUTHOR : ROBOTIS Ltd. +################################################## + +#--------------------------------------------------------------------- +# Makefile template for projects using DXL SDK +# +# Please make sure to follow these instructions when setting up your +# own copy of this file: +# +# 1- Enter the name of the target (the TARGET variable) +# 2- Add additional source files to the SOURCES variable +# 3- Add additional static library objects to the OBJECTS variable +# if necessary +# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are +# appropriate to your needs +# +# +# This makefile will link against several libraries, not all of which +# are necessarily needed for your project. Please feel free to +# remove libaries you do not need. +#--------------------------------------------------------------------- + +# *** ENTER THE TARGET NAME HERE *** +TARGET = clear_multi_turn + +# important directories used by assorted rules and other variables +DIR_DXL = ../../../.. +DIR_OBJS = .objects + +# compiler options +CC = gcc +CX = g++ +CCFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +CXFLAGS = -O2 -O3 -D_GNU_SOURCE -Wall $(INCLUDES) -g +LNKCC = $(CX) +LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib + +#--------------------------------------------------------------------- +# Core components (all of these are likely going to be needed) +#--------------------------------------------------------------------- +INCLUDES += -I$(DIR_DXL)/include/dynamixel_sdk +LIBRARIES += -ldxl_mac_c + +#--------------------------------------------------------------------- +# Files +#--------------------------------------------------------------------- +SOURCES = clear_multi_turn.cpp \ + # *** OTHER SOURCES GO HERE *** + +OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) +#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** + + +#--------------------------------------------------------------------- +# Compiling Rules +#--------------------------------------------------------------------- +$(TARGET): make_directory $(OBJECTS) + $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) + +all: $(TARGET) + +clean: + rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo + +make_directory: + mkdir -p $(DIR_OBJS)/ + +$(DIR_OBJS)/%.o: ../%.c + $(CC) $(CCFLAGS) -c $? -o $@ + +$(DIR_OBJS)/%.o: ../%.cpp + $(CX) $(CXFLAGS) -c $? -o $@ + +#--------------------------------------------------------------------- +# End of Makefile +#--------------------------------------------------------------------- diff --git a/c/example/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo b/c/example/protocol2.0/clear_multi_turn/win32/.vs/clear_multi_turn/v14/.suo new file mode 100644 index 0000000000000000000000000000000000000000..4674a53efded64c64abb67090e1f65e03f70700f GIT binary patch literal 27136 zcmeHPd2C$88GoCQl8^um31=y6NjO@2H+y@Rkd!^0!;T%V?IdJ_dER}t*WQagvTKtd zwL+>;FIrU;Ar+~DqKZn;NELz#(ZWAfD-|kK(W;l=kBYx~s8XdC3hwXs-j4ltv&Zw= zCIog?-_AYX%zQK7%=gXA`_1dy-}?T!8{U@c%zkO3^ugj5=~KFJ6Wkkw|I?Cm3ET|( zU~zGg!5aZ^cFjf910zxvzoKN8!cqoyUYaK<4V!DEO-nStxlJzfoBK{a{q7s4&mi5; zZ_*ME17lX2l@0>?6kK7c(x#N!=xd}6CKiR^sMe!4wy|%anx3%&Kk??I6l#!{6hIVx zAp?}gMJ$Ex27W!cmm*p?%!qr669;BUDgjGMN}~OQX&vSeLh@R&rvJph4Y8sQO%v)O z?t^=llNDw=;C+#~YI8o*T!Xl+0L{0!c&*MY!f5ZPhHtLg%zri9*8wiAhB4iZaDNs+ zdU33n0iOfh0@wxU0We)N(~EdpT^dK#?}Y8q#r450+R?1MZusKjhdKXqm-*LY{@08d zkiD&0>-o>IE5=e=46ZwFcGnd0J;;w*O%yI4qn1=jz3qbImop4`S zjT8Cm?e(7jR{?)L&aS_850IAJ({VZAer^+hG$!9BKPQbjHn z0Qo-G4XzdB{~`_7e9~X|g{|lRyAgjY;I?YIJ79ml>gL)&{%-+T0eb*k3+w={0p$NK zfE&PdK=6Mb+;;-@0`3Cr1MCNU5pXxa4+sE)fDj-IhyeNl2LJ~FhX98G1Asxm5x@{& z7%&E4TcWT>tL|~w#{kCxC#qqhy{F*6R~IJ3Jqd^d5&-TurU27`6d(zh1TBQ|n zBXB%l^|Zs!x!uZivj2{uz?Z6pw!=@p(#jA&d6<}3taQvm}Ii^Y-3GkCLc$*B~B7^r(01KqDa9 zZWKRrb1k76M|q>bo&~p?#D4|y53!#H?l@fS%q?g?*CeiAM)BW+v>dZE8E{Otm%OtR zv#o>nn}8_B3d2Ov%6L@@Wt$Uf>#Yc9k5D#D!j%Cv24KsG55g`XM62G?9{}a!*xgKH&THd3u{6>{h@%#!l|lcnSpP!ZgIL$<=NV_0 zrUzp$3}KHYW?Q^dl83(@`R>$82WC8M=B<7o<>LH7e2o#Kff;55gVpZi0E!Xlt`rpK| zI-URIFXXj(j5--3E&}{1_zQI-LyXIMu6!r(->?e&YcT)SwWK@$wGps9GMc-@d|`?U zJ^#D=zg6%5)b)pZI-~sOqqP5PCx1|%(#mwQ|2vHWUu#w93gZOtHQN6xEWT~>iy1#x zxJj(E(^aYOn7Z4DV->EK^cr`Axr6-&&w#jRq^ZXrz)Gl~4s%#{vseqc7i+Z#xC8jF zKsna~jMAU$O^;E5OflI-&nr1Nl$IPkwH+{cA1%QTN%E|Fl_% zu4rrY^Dl}O@URraIupapt6=3#W4uuUjlrf)h9fZ!Na37~GH|TALMI>2|bDO(J<=2ba2ja(JvN=Yx6f;gXx;T)|1e;)ra$VAjh7S;Pe)PFD^cO!FZ zU2^az;HQ*M%_05gm%IM$I`rASzuo@ImbXGz#jf4-;E>8t^qkPxZ1`bE?O(h0hE(d7 z(94=;LC@)i5m!*@t7)Ga@nGsdct*@Ug|QY(k{4-1JTRi&0>2m&t@MD@4^@^`G@Ro^iFO zkhq1R{*`#Sr#6cJcBK7swM^>Wjm_f+uRJu;dwu1l^0}|Rx95*Qo@K+nP0;?YX3bKAIlCFjPzY9G<9V|zJkxuE#|3-Sr zcpCi-G@eUK*^d6=oTOQ~)W1`d?4JK?RA|;u`tTWe*82Qki~&8KW^VoYf4%&35$b(`jw(}G@DHodd=fXzL3mj_BpLC{OnGLz1JKprHZAzvM-~Qig`KJYaT95 zrjqf)%KT_{PRZ<>v^l5TQ+-o*d%|s#o$@A@f0J75cr;uoDj61ORRf|*v6#$E7ntPc zyN)F@iELSf?Vp>N2*~j{#7B}!DzWif8=~`tqLQ`-v#FF4FQSx!wO`37`DEN0N~!^J ze*Qkk$&=ND(PAFCd(G)WJeyA?Czl)KvfB7F(3-wJ*&TO#>^`SUv3Y%`dQWOSG>odr z)5@Tn!GBuG6s=2-VLgwx|vy7d2K)8FYnb&4}~ z3-u9~@UJ^TY9-@`|B+BAJm>OKFf% z+9GuAm(bB9C3)A@iR5%9n^%HzL6J-*Ua47kBiQz85OMs}o7IHXmu19He2)S&ZL)T& zhB`Isv(36&Rc72gt3a>j!OM~u^lrRmOf7c-Fa`axS-l5afbNgCvCQgyxDs?^)PS1R zdzhLIoVvO+ems}yLrDjr$qd6jjq>QH-Y|vuDflJnk&jT#*xn-Qvo=PI?M_QGA>$K( zPEG;VP78j%7PJhCXYi`X0a|LN-mitS{;M&RT?sUul!bABne^C>Umf|IC;ga+O~$B#phro;{h8^%Je_WlCQN(pNDRmRwr;#Y4_Im{XJiQ<-oZ=JoEaF z9~`@KK)T|WH>CczW!KOni(mQA>#sf)W*Gz0J3DWEP-VreJ}CscW?TKZ)N#$19w&UDT@z++osUUq{?l154nht+|u1hzS`pw%vXG@ z_5=72gJbx?kDZba+}r}58-{I%%Y```!8k@GfCh1?~~!md-vb{v1!&NQs5;)qM$9{@wlB4i`y4= zSX_Pfu*Dw;*exNy*A))9{gFu6bM{Q4lA5S^JrnWRlFI;rWI0yIBa5KZL?JOZQC5{I zAZIpTJRoNhDJ8GzSqjGK68PDNQT;e{JGodg6Hk>AN^L7*!(xz8?V^Z=SZ9omtibO? z3+xfMFXRh(EPiLuW^s9fL5tTO@>-mZklpXKMLa=!Ku3UFZkYtR+!7JuO=n5}!O;U_ zfx5}k)6=+J6RBjTREgz4n~52XI9iZ_mUZR-^Hh(u3bL;JkJX{IS&gjUC~s?Qjbpp= zKX*>No!3q?(Ut$>km1_hX6(xU;$~-8{#P)wy7GTx{Xtj$=bPcK{NIV@<$US1EB|Y6 z@yI&D;ZbUpM?>r&`L8*No%px|5@$k$&@v`3^Dh$Hg7xKpwr|<7)hQOZa*hpYJG&5|!$6pC${pDcz zSpI~Aa@UIwZ;g3(j!ECRcKdi^>8yF^BORR(${0}F-OU~s|j9-U6ev-6SS(YdiPr$;Wiy>eknS@78^?&0~Nz>x*N|DK+3 zW_rF{P9GWcC%rv`v!%J=%Jjm*Na#>9kWHSb<^93Ri+)~ zo^cY@A5KL^=c1*f>0nUx*ZiHYpzZ4anrfCmhWfuQ|6lPrM3?_}`Tx=aaIy1${bI0> zN4z!WI*A|G^6A3-aPynIyf>ZC*t5|zu$rTaV|_j`kmv`T3m!zCB)_SJOs!A-i!>U;72Og2X#)ygQ{ zRD8ji^w;-4$AZ59nXXI!wSP7LVbPyg#2)MD_TBo=0qs@kPdlnz0`u}he<477W%Eo& z^fJxT{L+&@e)8pWXMdgf$pHC~ kkj{k7uy#hAa%f+w;Fo;9-4VUkQzF%_6u!_=z1mUg|1Ar}A^-pY literal 0 HcmV?d00001 diff --git a/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn.sln b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn.sln new file mode 100644 index 00000000..12e7d22e --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio Express 14 for Windows Desktop +VisualStudioVersion = 14.0.25123.0 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "clear_multi_turn", "clear_multi_turn\clear_multi_turn.vcxproj", "{4ECA1398-7E81-42F5-A613-9EAF0D178405}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Debug|x64.ActiveCfg = Debug|x64 + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Debug|x64.Build.0 = Debug|x64 + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Debug|x86.ActiveCfg = Debug|Win32 + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Debug|x86.Build.0 = Debug|Win32 + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Release|x64.ActiveCfg = Release|x64 + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Release|x64.Build.0 = Release|x64 + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Release|x86.ActiveCfg = Release|Win32 + {4ECA1398-7E81-42F5-A613-9EAF0D178405}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj new file mode 100644 index 00000000..73d8838e --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj @@ -0,0 +1,154 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {4ECA1398-7E81-42F5-A613-9EAF0D178405} + Win32Proj + clear_multi_turn + 8.1 + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + $(VC_LibraryPath_x86);$(WindowsSDK_LibraryPath_x86);$(NETFXKitsDir)Lib\um\x86;..\..\..\..\..\build\win32\output + + + false + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsC + + + Console + true + true + true + dxl_x86_c.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + + + + + \ No newline at end of file diff --git a/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters new file mode 100644 index 00000000..30c571fe --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + \ No newline at end of file diff --git a/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user new file mode 100644 index 00000000..45bf49fb --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/win32/clear_multi_turn/clear_multi_turn.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win32\output; + WindowsLocalDebugger + + \ No newline at end of file diff --git a/c/example/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo b/c/example/protocol2.0/clear_multi_turn/win64/.vs/clear_multi_turn/v14/.suo new file mode 100644 index 0000000000000000000000000000000000000000..6e1118e220ab531784be9d069488f55002e20a3f GIT binary patch literal 24576 zcmeHPTZ~&r89q)@nlzy$G^A}PscF&+WbO5R*J+c+*Ue=&d+~a6bJ(7>&w9P<8@|Ne z?S=;~LI?rnrA0^}Dz&JJ5GXH|kRl=af_Nd&2arI5_5tyL5O1g|G~xTs@vM&>+k4i# zn~UOE{b%OP%$a{K|Nqbb|1;j-U*G-y8&~&zAT@=f(pKrl%^lJwbonM-TKbeEJ%D%S z-MD%4CX1LxvKQ{58JLiA_$x_fDI{eP7o9Q)5$@~0oYXL^){ z`?MNkz?hTfr4ztDi&RLew)(Vf-d<_T3V!yZZAD!{5^0dH8U%jg%}Z(YpdcxL2F)8|pR8(0c$b&nZU3UIAOHvgLVz$}2yh&50&o&=3NQ>90h|Vm0>%L2fC)eZFbRkPrT}7mBEEpUSS|lc zh^GNB17yGqfb|lHsc+2I-kG=AfjG7RUvK^I&-L%5e^MtVe{~AfeWZ@S zNL;JEtcIVw-6?dV|Hjea?>aTQ#xgyRuJO|islFckXH=^r0lTLH*(SpRkzs?-0EdiNWKuHGaVnd%jUDzLNfO`qU6xy2v_8e@W89b|yq{My+xZ_Bz7M`x*XM0BJ z?+ogaW*M@uzc}8K_PXZht}e!J0+tvBE^b@W!`b4F+zrjW{FHHHz( zC=VbmBS-7;QSjed*Z&Ccit!&;aT045IMaBBRm@sH8rNFwaMJ_xZ`y-A>IX*WpL>pI z#*Z<@r3I`3XMp2Mtc)~>GFsuC!n2tF2T+0fhEe=ap{|f?&GXFJ)%+lw|55k^#0s>Y z3u_naFYFbLOZXoY%t8sAP{14%krMup0(g$Ipiu$8XbiS4@Hfssd2d0*Qb26f?;(2e zB=C#z7@hxf_?WsK!z4ym1m0nckmHU>bLdY2sklo0t!G{PmQU_K#4AF*qyce4&L(nDpw1iR-4g){+YSMH!_@T4wsl?La!Tpz{bO-IfHShmD z`>(!`0cac4z>3g>QjmKU)xMzAZPqmE-{@09|Dri#l>hbmPZZLQr*5=tXlFL+!*xAJ zk5iwf{Xx9kQ#J!X`Lk1?{HOnnxEVUt6=iD~Klg`A&^}$_MtZ;f_FuF9aS!T$rk?)Sz5W-3?4_km&mN_|-X0u7SrNN}@IJJX#5ffyWB=&qzZw4sRy+f&yoaQx#a6V(j&-yD?Z$VLwNW+WZ*70-ds6$b7P-3E ze|c`+&i>Od(G#ZKMDoEB&4WJZl_V!JS0CViH_@IYI~k=v@{92Q(r;cf1(E6^@M9tt zjqIW}G=91~q?D|axm>!~XP#0D#Z)eP#A$Wm&+c^C`^PPGN3u$}RFKns=CSfj zIu$>qEKcSYl8^uN#CzGA&2YnfT6eP-4<==R77r^lr@-4`!%#dc60ZR4Xi zLAOj0r{%#K6>ksZGI_b66t*9ii*u3Gl7h4I?R#sqGFnKavT}N*4nCB22wvO9M4OtV z-JR2^WHwh&0&-E2OeU(-n;rz)t_Kn6r#Y-AuemKF@5J{SAb{H*v6@!RJ(XvcW}R2v zjFX2d_EisVmc$@edCJI>ry^h$^3|-`!A0!-^v0Xj^N=#^Ql7tRr?`j<Vb@J#K*vVqQDN zdi`fL{|EJx&9whJ_0ve1kZnflwyI-7=8pjy-wKVt2u>OU|B#D#E1ajGG4-r~XNA;) z^6L8{v?6kN3Ouc#egt(+p(GAakjFCK>Q?ZcSNWXZ#sO*E8q+vgJ8wwfjIV+k)UjB* zf>ah#!iBUJn%}it_J2Krwkv_5o3=oE4@v*J_J`ruFPBGuc*XYIJLdOoq9I=7TP5)B z8aEnzVv_c>nu{&1vme)=Q0OJ>$69OZX#Qxro7c6~Xk(xOo&zp= z(!;;qm;T?51Ea6r{N{((-+hx;8gahh|BAkgcsbjCxWlt&!B*KD>R`Ntkw{`^qCHC;FbKUaMUF_J8~T^4|A2CQWCk zKiiM9UCA4#qQ%L-#xH(t$M9Rv|Lpod+tq8AACU%U_q==K-TlLF{wVSD*Z2S1yEgfO z8#wEdKjg&`XxnM*yD3%MmLcCt$jPtx#wF>9dOw-BxGABZB6vM^#dQeNEX;hzP!!)@5_2T}tHs@||!=*RT9@%FDDT4Dm7u4~@>)yPI_w^saavQZbUs{S@B zJbt&gA9Wwda_!97$b9e@r5igR`hFOj3*NlY|7szCxl5|6wq5n=wVvS@be0hBVesyT zN&1Z`c-V%&S6qRh-5&@AEdxRCfW;Laa9g}SpU>j7IR^Y5hb?4t+Ac2_6ge?nDWpnD zte&)9idXZ6-28IjaEzyz#n@O{F3si&nOIOME|hZlSa2~bXHr!q9SNR_#bZiU&g9cd z3}2OU@m$(rwdvZ^C9U!0`n#rZ`=(`^8$G@E zoB!7va#&mg_K?Nr_uDN&-=Hhxcl*NOkmvGpqMDwr4tl2Jv6Yko2AAbnv4BqmpHCMP z3)2<#QU=69u24EIXA^0qpxx6b8s}^OuWlvZjqiROcSG{AR5qS2CzQrf#Kwe>;)^YXxfA_clPvy>ZDqF6`^5D(sIgL4|)hy$b9o*z?_V#U) zyL8%2d~!4Nm`!Q)>sxKLU}4^v7DOnk4{u*~zp0{>pqEOCtpC~T^dU=K-<3TG zU;TRM_qDF>Z)vp4yS?kZ=iBbK)`RD-r}lk#%z4oN(bd0w!}>PosD4jNOEHf;ydM7B Y%rR(JQLl8A4!!knb=x;C-7o9^e=%iR + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {4CD1BCED-7D97-4F75-9AAA-3027B620E030} + Win32Proj + clear_multi_turn + 8.1 + + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + Application + true + v140 + Unicode + + + Application + false + v140 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + true + + + false + + + false + $(SolutionDir)$(Configuration)\ + $(Configuration)\ + $(VC_LibraryPath_x64);$(WindowsSDK_LibraryPath_x64);$(NETFXKitsDir)Lib\um\x64;..\..\..\..\..\build\win64\output + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + ..\..\..\..\..\include\dynamixel_sdk + CompileAsC + + + Console + true + true + true + dxl_x64_c.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + + + + + + + + + \ No newline at end of file diff --git a/c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters b/c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters new file mode 100644 index 00000000..30c571fe --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + + + Source Files + + + \ No newline at end of file diff --git a/c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user b/c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user new file mode 100644 index 00000000..0f71dd30 --- /dev/null +++ b/c/example/protocol2.0/clear_multi_turn/win64/clear_multi_turn/clear_multi_turn.vcxproj.user @@ -0,0 +1,7 @@ + + + + PATH=%PATH%;..\..\..\..\..\build\win64\output; + WindowsLocalDebugger + + \ No newline at end of file diff --git a/c/include/dynamixel_sdk/packet_handler.h b/c/include/dynamixel_sdk/packet_handler.h index 416d69f9..66bb29e2 100644 --- a/c/include/dynamixel_sdk/packet_handler.h +++ b/c/include/dynamixel_sdk/packet_handler.h @@ -25,6 +25,11 @@ #include "robotis_def.h" #include "port_handler.h" +#if defined(__APPLE__) +#undef reboot +#define reboot rebootDXL +#endif + #define BROADCAST_ID 0xFE // 254 #define MAX_ID 0xFC // 252 @@ -47,6 +52,7 @@ #define INST_BULK_READ 146 // 0x92 // --- Only for 2.0 --- // #define INST_REBOOT 8 +#define INST_CLEAR 16 // 0x10 #define INST_STATUS 85 // 0x55 #define INST_SYNC_READ 130 // 0x82 #define INST_BULK_WRITE 147 // 0x93 @@ -100,7 +106,13 @@ WINDECLSPEC uint16_t pingGetModelNum (int port_num, int protocol_version, WINDECLSPEC void broadcastPing (int port_num, int protocol_version); WINDECLSPEC uint8_t getBroadcastPingResult (int port_num, int protocol_version, int id); +#if defined(__APPLE__) +WINDECLSPEC void rebootDXL (int port_num, int protocol_version, uint8_t id); +#else WINDECLSPEC void reboot (int port_num, int protocol_version, uint8_t id); +#endif + +WINDECLSPEC void clearMultiTurn (int port_num, int protocol_version, uint8_t id); WINDECLSPEC void factoryReset (int port_num, int protocol_version, uint8_t id, uint8_t option); diff --git a/c/include/dynamixel_sdk/protocol1_packet_handler.h b/c/include/dynamixel_sdk/protocol1_packet_handler.h index b9de05bc..bd0499fd 100644 --- a/c/include/dynamixel_sdk/protocol1_packet_handler.h +++ b/c/include/dynamixel_sdk/protocol1_packet_handler.h @@ -44,6 +44,7 @@ WINDECLSPEC uint8_t getBroadcastPingResult1 (int port_num, int id); WINDECLSPEC void action1 (int port_num, uint8_t id); WINDECLSPEC void reboot1 (int port_num, uint8_t id); +WINDECLSPEC void clearMultiTurn1 (int port_num, uint8_t id); WINDECLSPEC void factoryReset1 (int port_num, uint8_t id, uint8_t option); WINDECLSPEC void readTx1 (int port_num, uint8_t id, uint16_t address, uint16_t length); diff --git a/c/include/dynamixel_sdk/protocol2_packet_handler.h b/c/include/dynamixel_sdk/protocol2_packet_handler.h index 6cacd8f0..1c188995 100644 --- a/c/include/dynamixel_sdk/protocol2_packet_handler.h +++ b/c/include/dynamixel_sdk/protocol2_packet_handler.h @@ -48,6 +48,7 @@ WINDECLSPEC uint8_t getBroadcastPingResult2 (int port_num, int id); WINDECLSPEC void action2 (int port_num, uint8_t id); WINDECLSPEC void reboot2 (int port_num, uint8_t id); +WINDECLSPEC void clearMultiTurn2 (int port_num, uint8_t id); WINDECLSPEC void factoryReset2 (int port_num, uint8_t id, uint8_t option); WINDECLSPEC void readTx2 (int port_num, uint8_t id, uint16_t address, uint16_t length); diff --git a/c/src/dynamixel_sdk/group_bulk_read.c b/c/src/dynamixel_sdk/group_bulk_read.c index e5a0fcfd..900e0b94 100644 --- a/c/src/dynamixel_sdk/group_bulk_read.c +++ b/c/src/dynamixel_sdk/group_bulk_read.c @@ -183,6 +183,7 @@ void groupBulkReadRemoveParam(int group_num, uint8_t id) if (groupData[group_num].data_list[data_num].id == NOT_USED_ID) // NOT exist return; + free(groupData[group_num].data_list[data_num].data); groupData[group_num].data_list[data_num].data = 0; groupData[group_num].data_list[data_num].id = NOT_USED_ID; @@ -194,13 +195,22 @@ void groupBulkReadRemoveParam(int group_num, uint8_t id) void groupBulkReadClearParam(int group_num) { + int data_num = 0; int port_num = groupData[group_num].port_num; if (size(group_num) == 0) return; + for (data_num = 0; data_num < groupData[group_num].data_list_length; data_num++) + { + free(groupData[group_num].data_list[data_num].data); + groupData[group_num].data_list[data_num].data = 0; + } + + free(groupData[group_num].data_list); groupData[group_num].data_list = 0; + free(packetData[port_num].data_write); packetData[port_num].data_write = 0; groupData[group_num].data_list_length = 0; diff --git a/c/src/dynamixel_sdk/group_bulk_write.c b/c/src/dynamixel_sdk/group_bulk_write.c index 668128a3..d602cc85 100644 --- a/c/src/dynamixel_sdk/group_bulk_write.c +++ b/c/src/dynamixel_sdk/group_bulk_write.c @@ -219,6 +219,7 @@ void groupBulkWriteRemoveParam(int group_num, uint8_t id) groupData[group_num].data_list[data_num].data_end = 0; + free(groupData[group_num].data_list[data_num].data); groupData[group_num].data_list[data_num].data = 0; groupData[group_num].data_list[data_num].data_length = 0; @@ -274,6 +275,7 @@ uint8_t groupBulkWriteChangeParam(int group_num, uint8_t id, uint16_t start_addr } void groupBulkWriteClearParam(int group_num) { + int data_num = 0; int port_num = groupData[group_num].port_num; if (groupData[group_num].protocol_version == 1) @@ -282,8 +284,16 @@ void groupBulkWriteClearParam(int group_num) if (size(group_num) == 0) return; + for (data_num = 0; data_num < groupData[group_num].data_list_length; data_num++) + { + free(groupData[group_num].data_list[data_num].data); + groupData[group_num].data_list[data_num].data = 0; + } + + free(groupData[group_num].data_list); groupData[group_num].data_list = 0; + free(packetData[port_num].data_write); packetData[port_num].data_write = 0; groupData[group_num].data_list_length = 0; diff --git a/c/src/dynamixel_sdk/group_sync_read.c b/c/src/dynamixel_sdk/group_sync_read.c index 59932780..9b0dbc3c 100644 --- a/c/src/dynamixel_sdk/group_sync_read.c +++ b/c/src/dynamixel_sdk/group_sync_read.c @@ -173,6 +173,7 @@ void groupSyncReadRemoveParam(int group_num, uint8_t id) if (groupData[group_num].data_list[data_num].id == NOT_USED_ID) // NOT exist return; + free(groupData[group_num].data_list[data_num].data); groupData[group_num].data_list[data_num].data = 0; groupData[group_num].data_list[data_num].id = NOT_USED_ID; @@ -181,6 +182,7 @@ void groupSyncReadRemoveParam(int group_num, uint8_t id) } void groupSyncReadClearParam(int group_num) { + int data_num = 0; int port_num = groupData[group_num].port_num; if (groupData[group_num].protocol_version == 1) @@ -189,8 +191,16 @@ void groupSyncReadClearParam(int group_num) if (size(group_num) == 0) return; + for (data_num = 0; data_num < groupData[group_num].data_list_length; data_num++) + { + free(groupData[group_num].data_list[data_num].data); + groupData[group_num].data_list[data_num].data = 0; + } + + free(groupData[group_num].data_list); groupData[group_num].data_list = 0; + free(packetData[port_num].data_write); packetData[port_num].data_write = 0; groupData[group_num].data_list_length = 0; diff --git a/c/src/dynamixel_sdk/group_sync_write.c b/c/src/dynamixel_sdk/group_sync_write.c index 8469eb2a..df7cfa62 100644 --- a/c/src/dynamixel_sdk/group_sync_write.c +++ b/c/src/dynamixel_sdk/group_sync_write.c @@ -202,6 +202,7 @@ void groupSyncWriteRemoveParam(int group_num, uint8_t id) groupData[group_num].data_list[data_num].data_end = 0; + free(groupData[group_num].data_list[data_num].data); groupData[group_num].data_list[data_num].data = 0; groupData[group_num].data_list[data_num].id = NOT_USED_ID; @@ -251,13 +252,22 @@ uint8_t groupSyncWriteChangeParam(int group_num, uint8_t id, uint32_t data, uint void groupSyncWriteClearParam(int group_num) { + int data_num = 0; int port_num = groupData[group_num].port_num; if (size(group_num) == 0) return; + for (data_num = 0; data_num < groupData[group_num].data_list_length; data_num++) + { + free(groupData[group_num].data_list[data_num].data); + groupData[group_num].data_list[data_num].data = 0; + } + + free(groupData[group_num].data_list); groupData[group_num].data_list = 0; + free(packetData[port_num].data_write); packetData[port_num].data_write = 0; groupData[group_num].data_list_length = 0; diff --git a/c/src/dynamixel_sdk/packet_handler.c b/c/src/dynamixel_sdk/packet_handler.c index ae0cf3bb..fe4c0083 100644 --- a/c/src/dynamixel_sdk/packet_handler.c +++ b/c/src/dynamixel_sdk/packet_handler.c @@ -211,7 +211,11 @@ uint8_t getBroadcastPingResult(int port_num, int protocol_version, int id) } } +#if defined(__APPLE__) +void rebootDXL(int port_num, int protocol_version, uint8_t id) +#else void reboot(int port_num, int protocol_version, uint8_t id) +#endif { if (protocol_version == 1) { @@ -223,6 +227,18 @@ void reboot(int port_num, int protocol_version, uint8_t id) } } +void clearMultiTurn(int port_num, int protocol_version, uint8_t id) +{ + if (protocol_version == 1) + { + clearMultiTurn1(port_num, id); + } + else + { + clearMultiTurn2(port_num, id); + } +} + void factoryReset(int port_num, int protocol_version, uint8_t id, uint8_t option) { if (protocol_version == 1) diff --git a/c/src/dynamixel_sdk/port_handler_linux.c b/c/src/dynamixel_sdk/port_handler_linux.c index d506a4fa..965e64d1 100644 --- a/c/src/dynamixel_sdk/port_handler_linux.c +++ b/c/src/dynamixel_sdk/port_handler_linux.c @@ -56,6 +56,27 @@ // or if you have another good idea that can be an alternatives, // please give us advice via github issue https://github.com/ROBOTIS-GIT/DynamixelSDK/issues +struct termios2 { + tcflag_t c_iflag; /* input mode flags */ + tcflag_t c_oflag; /* output mode flags */ + tcflag_t c_cflag; /* control mode flags */ + tcflag_t c_lflag; /* local mode flags */ + cc_t c_line; /* line discipline */ + cc_t c_cc[19]; /* control characters */ + speed_t c_ispeed; /* input speed */ + speed_t c_ospeed; /* output speed */ +}; + +#ifndef TCGETS2 +#define TCGETS2 _IOR('T', 0x2A, struct termios2) +#endif +#ifndef TCSETS2 +#define TCSETS2 _IOW('T', 0x2B, struct termios2) +#endif +#ifndef BOTHER +#define BOTHER 0010000 +#endif + typedef struct { int socket_fd; @@ -263,6 +284,19 @@ uint8_t setupPortLinux(int port_num, int cflag_baud) uint8_t setCustomBaudrateLinux(int port_num, int speed) { + struct termios2 options; + + if (ioctl(portData[port_num].socket_fd, TCGETS2, &options) != 01) + { + options.c_cflag &= ~CBAUD; + options.c_cflag |= BOTHER; + options.c_ispeed = speed; + options.c_ospeed = speed; + + if (ioctl(portData[port_num].socket_fd, TCSETS2, &options) != -1) + return True; + } + // try to set a custom divisor struct serial_struct ss; if (ioctl(portData[port_num].socket_fd, TIOCGSERIAL, &ss) != 0) diff --git a/c/src/dynamixel_sdk/protocol1_packet_handler.c b/c/src/dynamixel_sdk/protocol1_packet_handler.c index 1e492a9c..5e1eee76 100644 --- a/c/src/dynamixel_sdk/protocol1_packet_handler.c +++ b/c/src/dynamixel_sdk/protocol1_packet_handler.c @@ -418,6 +418,11 @@ void reboot1(int port_num, uint8_t id) packetData[port_num].communication_result = COMM_NOT_AVAILABLE; } +void clearMultiTurn1(int port_num, uint8_t id) +{ + packetData[port_num].communication_result = COMM_NOT_AVAILABLE; +} + void factoryReset1(int port_num, uint8_t id, uint8_t option) { packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 6); diff --git a/c/src/dynamixel_sdk/protocol2_packet_handler.c b/c/src/dynamixel_sdk/protocol2_packet_handler.c index c0f475da..3f403482 100644 --- a/c/src/dynamixel_sdk/protocol2_packet_handler.c +++ b/c/src/dynamixel_sdk/protocol2_packet_handler.c @@ -17,11 +17,14 @@ /* Author: Ryu Woon Jung (Leon) */ #if defined(__linux__) +#include #include "protocol2_packet_handler.h" #elif defined(__APPLE__) +#include #include "protocol2_packet_handler.h" #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT +#include #include "protocol2_packet_handler.h" #endif @@ -29,8 +32,8 @@ #include #include -#define TXPACKET_MAX_LEN (4*1024) -#define RXPACKET_MAX_LEN (4*1024) +#define TXPACKET_MAX_LEN (1*1024) +#define RXPACKET_MAX_LEN (1*1024) ///////////////// for Protocol 2.0 Packet ///////////////// #define PKT_HEADER0 0 @@ -142,6 +145,11 @@ uint8_t getLastRxPacketError2(int port_num) void setDataWrite2(int port_num, uint16_t data_length, uint16_t data_pos, uint32_t data) { packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, (data_pos + data_length) * sizeof(uint8_t)); + if (packetData[port_num].data_write == NULL) + { + printf("[Set Data Write] memory allocation failed... \n"); + return; + } switch (data_length) { @@ -162,7 +170,7 @@ void setDataWrite2(int port_num, uint16_t data_length, uint16_t data_pos, uint32 break; default: - printf("[Set Data Write] failed... "); + printf("[Set Data Write] failed... \n"); break; } } @@ -181,7 +189,7 @@ uint32_t getDataRead2(int port_num, uint16_t data_length, uint16_t data_pos) , DXL_MAKEWORD(packetData[port_num].data_read[data_pos + 2], packetData[port_num].data_read[data_pos + 3])); default: - printf("[Set Data Read] failed... "); + printf("[Set Data Read] failed... \n"); return 0; } } @@ -189,7 +197,7 @@ uint32_t getDataRead2(int port_num, uint16_t data_length, uint16_t data_pos) unsigned short updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size) { uint16_t i, j; - uint16_t crc_table[256] = { 0x0000, + static const uint16_t crc_table[256] = { 0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011, 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D, @@ -239,42 +247,52 @@ unsigned short updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t dat void addStuffing(uint8_t *packet) { - uint16_t s; - - uint16_t i = 0; - int index = 0; + uint8_t *packet_ptr; + uint16_t i; + uint16_t packet_length_before_crc; + uint16_t out_index, in_index; + int packet_length_in = DXL_MAKEWORD(packet[PKT_LENGTH_L], packet[PKT_LENGTH_H]); int packet_length_out = packet_length_in; - uint8_t temp[TXPACKET_MAX_LEN] = { 0 }; - - for (s = PKT_HEADER0; s <= PKT_LENGTH_H; s++) - { - temp[s] = packet[s]; // FF FF FD XX ID LEN_L LEN_H - } - - index = PKT_INSTRUCTION; - for (i = 0; i < packet_length_in - 2; i++) // except CRC + + if (packet_length_in < 8) // INSTRUCTION, ADDR_L, ADDR_H, CRC16_L, CRC16_H + FF FF FD + return; + + packet_length_before_crc = packet_length_in - 2; + for (i = 3; i < packet_length_before_crc; i++) { - temp[index++] = packet[i + PKT_INSTRUCTION]; - if (packet[i + PKT_INSTRUCTION] == 0xFD && packet[i + PKT_INSTRUCTION - 1] == 0xFF && packet[i + PKT_INSTRUCTION - 2] == 0xFF) - { // FF FF FD - temp[index++] = 0xFD; + packet_ptr = &packet[i+PKT_INSTRUCTION-2]; + if (packet_ptr[0] == 0xFF && packet_ptr[1] == 0xFF && packet_ptr[2] == 0xFD) packet_length_out++; - } } - temp[index++] = packet[PKT_INSTRUCTION + packet_length_in - 2]; - temp[index++] = packet[PKT_INSTRUCTION + packet_length_in - 1]; - - if (packet_length_in != packet_length_out) - packet = (uint8_t *)realloc(packet, index * sizeof(uint8_t)); - - for (s = 0; s < index; s++) + + if (packet_length_in == packet_length_out) // no stuffing required + return; + + out_index = packet_length_out + 6 - 2; // last index before crc + in_index = packet_length_in + 6 - 2; // last index before crc + while (out_index != in_index) { - packet[s] = temp[s]; + if (packet[in_index] == 0xFD && packet[in_index-1] == 0xFF && packet[in_index-2] == 0xFF) + { + packet[out_index--] = 0xFD; // byte stuffing + if (out_index != in_index) + { + packet[out_index--] = packet[in_index--]; // FD + packet[out_index--] = packet[in_index--]; // FF + packet[out_index--] = packet[in_index--]; // FF + } + } + else + { + packet[out_index--] = packet[in_index--]; + } } packet[PKT_LENGTH_L] = DXL_LOBYTE(packet_length_out); packet[PKT_LENGTH_H] = DXL_HIBYTE(packet_length_out); + + return; } void removeStuffing(uint8_t *packet) @@ -460,6 +478,11 @@ void rxPacket2(int port_num) break; } } +#if defined(__linux__) || defined(__APPLE__) + usleep(0); +#elif defined(_WIN32) || defined(_WIN64) + Sleep(0); +#endif } g_is_using[port_num] = False; @@ -520,7 +543,12 @@ uint16_t pingGetModelNum2(int port_num, uint8_t id) packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 10); packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, 14); - + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[PingGetModeNum] memory allocation failed.. \n"); + return COMM_TX_FAIL; + } + if (id >= BROADCAST_ID) { packetData[port_num].communication_result = COMM_NOT_AVAILABLE; @@ -549,8 +577,14 @@ void broadcastPing2(int port_num) uint16_t rx_length = 0; uint16_t wait_length = STATUS_LENGTH * MAX_ID; - packetData[port_num].broadcast_ping_id_list = (uint8_t *)calloc(255, sizeof(uint8_t)); + double tx_time_per_byte = (1000.0 / (double)getBaudRate(port_num)) * 10.0; + packetData[port_num].broadcast_ping_id_list = (uint8_t *)calloc(255, sizeof(uint8_t)); + if (packetData[port_num].broadcast_ping_id_list == NULL) + { + printf("[BroadcastPing] memory allocation failed.. \n"); + return; + } for (id = 0; id < 255; id++) { @@ -559,6 +593,11 @@ void broadcastPing2(int port_num) packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 10 * sizeof(uint8_t)); packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, STATUS_LENGTH * MAX_ID * sizeof(uint8_t)); + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[BroadcastPing] memory allocation failed.. \n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = BROADCAST_ID; packetData[port_num].tx_packet[PKT_LENGTH_L] = 3; @@ -573,7 +612,8 @@ void broadcastPing2(int port_num) } // set rx timeout - setPacketTimeout(port_num, (uint16_t)(wait_length * 30)); + //setPacketTimeout(port_num, (uint16_t)(wait_length * 30)); + setPacketTimeoutMSec(port_num, ((double)wait_length * tx_time_per_byte) + (3.0 * (double)MAX_ID) + 16.0); while (1) { @@ -668,6 +708,11 @@ uint8_t getBroadcastPingResult2(int port_num, int id) void action2(int port_num, uint8_t id) { packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 10); + if (packetData[port_num].tx_packet == NULL) + { + printf("[Action] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = id; packetData[port_num].tx_packet[PKT_LENGTH_L] = 3; @@ -681,6 +726,11 @@ void reboot2(int port_num, uint8_t id) { packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 10); packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, 11); + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[Reboot] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = id; packetData[port_num].tx_packet[PKT_LENGTH_L] = 3; @@ -690,11 +740,39 @@ void reboot2(int port_num, uint8_t id) txRxPacket2(port_num); } +void clearMultiTurn2(int port_num, uint8_t id) +{ + packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 15); + packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, 11); + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[ClearMultiTurn] memory allocation failed..\n"); + return; + } + + packetData[port_num].tx_packet[PKT_ID] = id; + packetData[port_num].tx_packet[PKT_LENGTH_L] = 8; + packetData[port_num].tx_packet[PKT_LENGTH_H] = 0; + packetData[port_num].tx_packet[PKT_INSTRUCTION] = INST_CLEAR; + packetData[port_num].tx_packet[PKT_PARAMETER0] = 0x01; + packetData[port_num].tx_packet[PKT_PARAMETER0+1] = 0x44; + packetData[port_num].tx_packet[PKT_PARAMETER0+2] = 0x58; + packetData[port_num].tx_packet[PKT_PARAMETER0+3] = 0x4C; + packetData[port_num].tx_packet[PKT_PARAMETER0+4] = 0x22; + + txRxPacket2(port_num); +} + void factoryReset2(int port_num, uint8_t id, uint8_t option) { packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 11); packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, 11); - + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[FactoryReset] memory allocation failed..\n"); + return; + } + packetData[port_num].tx_packet[PKT_ID] = id; packetData[port_num].tx_packet[PKT_LENGTH_L] = 4; packetData[port_num].tx_packet[PKT_LENGTH_H] = 0; @@ -709,7 +787,12 @@ void readTx2(int port_num, uint8_t id, uint16_t address, uint16_t length) packetData[port_num].communication_result = COMM_TX_FAIL; packetData[port_num].tx_packet = (uint8_t *)malloc(14); - + if (packetData[port_num].tx_packet == NULL) + { + printf("[ReadTx] memory allocation failed..\n"); + return; + } + if (id >= BROADCAST_ID) { packetData[port_num].communication_result = COMM_NOT_AVAILABLE; @@ -727,6 +810,8 @@ void readTx2(int port_num, uint8_t id, uint16_t address, uint16_t length) txPacket2(port_num); + free(packetData[port_num].tx_packet); + // set packet timeout if (packetData[port_num].communication_result == COMM_SUCCESS) setPacketTimeout(port_num, (uint16_t)(length + 11)); @@ -738,7 +823,12 @@ void readRx2(int port_num, uint16_t length) packetData[port_num].communication_result = COMM_TX_FAIL; packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, RXPACKET_MAX_LEN); //(length + 11 + (length/3)); // (length/3): consider stuffing - + if (packetData[port_num].rx_packet == NULL) + { + printf("[ReadRx] memory allocation failed..\n"); + return; + } + rxPacket2(port_num); if (packetData[port_num].communication_result == COMM_SUCCESS) { @@ -759,7 +849,12 @@ void readTxRx2(int port_num, uint8_t id, uint16_t address, uint16_t length) packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, 14); packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, RXPACKET_MAX_LEN); //(length + 11 + (length/3)); // (length/3): consider stuffing - + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[ReadTxRx] memory allocation failed..\n"); + return; + } + if (id >= BROADCAST_ID) { packetData[port_num].communication_result = COMM_NOT_AVAILABLE; @@ -794,6 +889,11 @@ void read1ByteTx2(int port_num, uint8_t id, uint16_t address) uint8_t read1ByteRx2(int port_num) { packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 1 * sizeof(uint8_t)); + if (packetData[port_num].data_read == NULL) + { + printf("[Read1ByteRx] memory allocation failed..\n"); + return 0; + } packetData[port_num].data_read[0] = 0; readRx2(port_num, 1); if (packetData[port_num].communication_result == COMM_SUCCESS) @@ -803,6 +903,11 @@ uint8_t read1ByteRx2(int port_num) uint8_t read1ByteTxRx2(int port_num, uint8_t id, uint16_t address) { packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 1 * sizeof(uint8_t)); + if (packetData[port_num].data_read == NULL) + { + printf("[Read1ByteTxRx] memory allocation failed..\n"); + return 0; + } packetData[port_num].data_read[0] = 0; readTxRx2(port_num, id, address, 1); if (packetData[port_num].communication_result == COMM_SUCCESS) @@ -817,6 +922,11 @@ void read2ByteTx2(int port_num, uint8_t id, uint16_t address) uint16_t read2ByteRx2(int port_num) { packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 2 * sizeof(uint8_t)); + if (packetData[port_num].data_read == NULL) + { + printf("[Read2ByteRx] memory allocation failed..\n"); + return 0; + } packetData[port_num].data_read[0] = 0; packetData[port_num].data_read[1] = 0; readRx2(port_num, 2); @@ -827,6 +937,11 @@ uint16_t read2ByteRx2(int port_num) uint16_t read2ByteTxRx2(int port_num, uint8_t id, uint16_t address) { packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 2 * sizeof(uint8_t)); + if (packetData[port_num].data_read == NULL) + { + printf("[Read2ByteTxRx] memory allocation failed..\n"); + return 0; + } packetData[port_num].data_read[0] = 0; packetData[port_num].data_read[1] = 0; readTxRx2(port_num, id, address, 2); @@ -842,6 +957,11 @@ void read4ByteTx2(int port_num, uint8_t id, uint16_t address) uint32_t read4ByteRx2(int port_num) { packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 4 * sizeof(uint8_t)); + if (packetData[port_num].data_read == NULL) + { + printf("[Read4ByteRx] memory allocation failed..\n"); + return 0; + } packetData[port_num].data_read[0] = 0; packetData[port_num].data_read[1] = 0; packetData[port_num].data_read[2] = 0; @@ -854,6 +974,11 @@ uint32_t read4ByteRx2(int port_num) uint32_t read4ByteTxRx2(int port_num, uint8_t id, uint16_t address) { packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 4 * sizeof(uint8_t)); + if (packetData[port_num].data_read == NULL) + { + printf("[Read2ByteTxRx] memory allocation failed..\n"); + return 0; + } packetData[port_num].data_read[0] = 0; packetData[port_num].data_read[1] = 0; packetData[port_num].data_read[2] = 0; @@ -872,6 +997,11 @@ void writeTxOnly2(int port_num, uint8_t id, uint16_t address, uint16_t length) packetData[port_num].communication_result = COMM_TX_FAIL; packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, length + 12); + if (packetData[port_num].tx_packet == NULL) + { + printf("[WriteTxOnly] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = id; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(length + 5); @@ -897,7 +1027,12 @@ void writeTxRx2(int port_num, uint8_t id, uint16_t address, uint16_t length) packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, length + 12); packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, 11); - + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[WriteTxRx] memory allocation failed..\n"); + return; + } + packetData[port_num].tx_packet[PKT_ID] = id; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(length + 5); packetData[port_num].tx_packet[PKT_LENGTH_H] = DXL_HIBYTE(length + 5); @@ -916,12 +1051,22 @@ void writeTxRx2(int port_num, uint8_t id, uint16_t address, uint16_t length) void write1ByteTxOnly2(int port_num, uint8_t id, uint16_t address, uint8_t data) { packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 1 * sizeof(uint8_t)); + if (packetData[port_num].data_write == NULL) + { + printf("[Write1ByteTxOnly] memory allocation failed..\n"); + return; + } packetData[port_num].data_write[0] = data; writeTxOnly2(port_num, id, address, 1); } void write1ByteTxRx2(int port_num, uint8_t id, uint16_t address, uint8_t data) { packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 1 * sizeof(uint8_t)); + if (packetData[port_num].data_write == NULL) + { + printf("[Write1ByteTxRx] memory allocation failed..\n"); + return; + } packetData[port_num].data_write[0] = data; writeTxRx2(port_num, id, address, 1); } @@ -929,6 +1074,11 @@ void write1ByteTxRx2(int port_num, uint8_t id, uint16_t address, uint8_t data) void write2ByteTxOnly2(int port_num, uint8_t id, uint16_t address, uint16_t data) { packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 2 * sizeof(uint8_t)); + if (packetData[port_num].data_write == NULL) + { + printf("[Write2ByteTxOnly] memory allocation failed..\n"); + return; + } packetData[port_num].data_write[0] = DXL_LOBYTE(data); packetData[port_num].data_write[1] = DXL_HIBYTE(data); writeTxOnly2(port_num, id, address, 2); @@ -936,6 +1086,11 @@ void write2ByteTxOnly2(int port_num, uint8_t id, uint16_t address, uint16_t data void write2ByteTxRx2(int port_num, uint8_t id, uint16_t address, uint16_t data) { packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 2 * sizeof(uint8_t)); + if (packetData[port_num].data_write == NULL) + { + printf("[Write2ByteTxRx] memory allocation failed..\n"); + return; + } packetData[port_num].data_write[0] = DXL_LOBYTE(data); packetData[port_num].data_write[1] = DXL_HIBYTE(data); writeTxRx2(port_num, id, address, 2); @@ -944,6 +1099,11 @@ void write2ByteTxRx2(int port_num, uint8_t id, uint16_t address, uint16_t data) void write4ByteTxOnly2(int port_num, uint8_t id, uint16_t address, uint32_t data) { packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 4 * sizeof(uint8_t)); + if (packetData[port_num].data_write == NULL) + { + printf("[Write4ByteTxOnly] memory allocation failed..\n"); + return; + } packetData[port_num].data_write[0] = DXL_LOBYTE(DXL_LOWORD(data)); packetData[port_num].data_write[1] = DXL_HIBYTE(DXL_LOWORD(data)); packetData[port_num].data_write[2] = DXL_LOBYTE(DXL_HIWORD(data)); @@ -953,6 +1113,11 @@ void write4ByteTxOnly2(int port_num, uint8_t id, uint16_t address, uint32_t data void write4ByteTxRx2(int port_num, uint8_t id, uint16_t address, uint32_t data) { packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 4 * sizeof(uint8_t)); + if (packetData[port_num].data_write == NULL) + { + printf("[Write4ByteTxRx] memory allocation failed..\n"); + return; + } packetData[port_num].data_write[0] = DXL_LOBYTE(DXL_LOWORD(data)); packetData[port_num].data_write[1] = DXL_HIBYTE(DXL_LOWORD(data)); packetData[port_num].data_write[2] = DXL_LOBYTE(DXL_HIWORD(data)); @@ -967,6 +1132,11 @@ void regWriteTxOnly2(int port_num, uint8_t id, uint16_t address, uint16_t length packetData[port_num].communication_result = COMM_TX_FAIL; packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, length + 12); + if (packetData[port_num].tx_packet == NULL) + { + printf("[RegWriteTxOnly] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = id; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(length + 5); @@ -992,6 +1162,11 @@ void regWriteTxRx2(int port_num, uint8_t id, uint16_t address, uint16_t length) packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, length + 12); packetData[port_num].rx_packet = (uint8_t *)realloc(packetData[port_num].rx_packet, 11); + if (packetData[port_num].tx_packet == NULL || packetData[port_num].rx_packet == NULL) + { + printf("[RegWriteTxRx] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = id; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(length + 5); @@ -1016,6 +1191,11 @@ void syncReadTx2(int port_num, uint16_t start_address, uint16_t data_length, uin packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, param_length + 14); // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + if (packetData[port_num].tx_packet == NULL) + { + printf("[SyncReadTx] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = BROADCAST_ID; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H @@ -1045,6 +1225,11 @@ void syncWriteTxOnly2(int port_num, uint16_t start_address, uint16_t data_length packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, param_length + 14); // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + if (packetData[port_num].tx_packet == NULL) + { + printf("[SyncWriteTxOnly] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = BROADCAST_ID; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H @@ -1072,6 +1257,11 @@ void bulkReadTx2(int port_num, uint16_t param_length) packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, param_length + 10); // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H + if (packetData[port_num].tx_packet == NULL) + { + printf("[BulkReadTx] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = BROADCAST_ID; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H @@ -1103,6 +1293,11 @@ void bulkWriteTxOnly2(int port_num, uint16_t param_length) packetData[port_num].tx_packet = (uint8_t *)realloc(packetData[port_num].tx_packet, param_length + 10); // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H + if (packetData[port_num].tx_packet == NULL) + { + printf("[BulkWriteTxOnly] memory allocation failed..\n"); + return; + } packetData[port_num].tx_packet[PKT_ID] = BROADCAST_ID; packetData[port_num].tx_packet[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H diff --git a/java/dynamixel_functions_java/x64/Dynamixel.java b/java/dynamixel_functions_java/x64/Dynamixel.java index c8e20f83..445fc7db 100644 --- a/java/dynamixel_functions_java/x64/Dynamixel.java +++ b/java/dynamixel_functions_java/x64/Dynamixel.java @@ -69,6 +69,8 @@ interface LibFunction extends Library public void reboot (int port_num, int protocol_version, byte id); + public void clearMultiTurn (int port_num, int protocol_version, byte id); + public void factoryReset (int port_num, int protocol_version, byte id, byte option); public void readTx (int port_num, int protocol_version, byte id, short address, short length); @@ -290,6 +292,11 @@ public void reboot(int port_num, int protocol_version, byte id) libFunction.reboot(port_num, protocol_version, id); } + public void clearMultiTurn(int port_num, int protocol_version, byte id) + { + libFunction.clearMultiTurn(port_num, protocol_version, id); + } + public void factoryReset(int port_num, int protocol_version, byte id, byte option) { libFunction.factoryReset(port_num, protocol_version, id, option); diff --git a/java/dynamixel_functions_java/x86/Dynamixel.java b/java/dynamixel_functions_java/x86/Dynamixel.java index bc5afbe6..494191a7 100644 --- a/java/dynamixel_functions_java/x86/Dynamixel.java +++ b/java/dynamixel_functions_java/x86/Dynamixel.java @@ -69,6 +69,8 @@ interface LibFunction extends Library public void reboot (int port_num, int protocol_version, byte id); + public void clearMultiTurn (int port_num, int protocol_version, byte id); + public void factoryReset (int port_num, int protocol_version, byte id, byte option); public void readTx (int port_num, int protocol_version, byte id, short address, short length); @@ -290,6 +292,11 @@ public void reboot(int port_num, int protocol_version, byte id) libFunction.reboot(port_num, protocol_version, id); } + public void clearMultiTurn(int port_num, int protocol_version, byte id) + { + libFunction.clearMultiTurn(port_num, protocol_version, id); + } + public void factoryReset(int port_num, int protocol_version, byte id, byte option) { libFunction.factoryReset(port_num, protocol_version, id, option); diff --git a/java/protocol2.0/clear_multi_turn/ClearMultiTurn.java b/java/protocol2.0/clear_multi_turn/ClearMultiTurn.java new file mode 100644 index 00000000..bb5548b3 --- /dev/null +++ b/java/protocol2.0/clear_multi_turn/ClearMultiTurn.java @@ -0,0 +1,261 @@ +/******************************************************************************* +* Copyright 2018 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/* Author: Ki Jong Gil (Gilbert) */ + +// +// ********* Clear Multi-Turn Example ********* +// +// +// Available Dynamixel model on this example : MX with Protocol 2.0 (firmware v42 or above), Dynamixel X-series (firmware v42 or above) +// This example is designed for using a Dynamixel XM430-W350-R, and an U2D2. +// To use another Dynamixel model, such as MX series, see their details in E-Manual(emanual.robotis.com) and edit below "#define"d variables yourself. +// Be sure that Dynamixel properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +// + +import java.io.IOException; +import java.util.Scanner; + +public class ClearMultiTurn +{ + public static void main(String[] args) throws InterruptedException, IOException + { + // Control table address + short ADDR_OPERATING_MODE = 11; // Control table address is different in Dynamixel model + short ADDR_TORQUE_ENABLE = 64; + short ADDR_GOAL_POSITION = 116; + short ADDR_PRESENT_POSITION = 132; + + // Protocol version + int PROTOCOL_VERSION = 2; // See which protocol version is used in the Dynamixel + + // Default setting + byte DXL_ID = 1; // Dynamixel ID: 1 + int BAUDRATE = 57600; + String DEVICENAME = "COM1"; // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + + byte TORQUE_ENABLE = 1; // Value for enabling the torque + byte TORQUE_DISABLE = 0; // Value for disabling the torque + int MAX_POSITION_VALUE = 1048575; + int DXL_MOVING_STATUS_THRESHOLD = 20; // Dynamixel moving status threshold + byte EXT_POSITION_CONTROL_MODE = 4; // Value for extended position control mode (operating mode) + + + String KEY_FOR_ESCAPE = "e"; // Key for escape + String KEY_FOR_CONTINUE = " "; // key for continue + + int COMM_SUCCESS = 0; // Communication Success result value + int COMM_TX_FAIL = -1001; // Communication Tx Failed + + // Instead of getch + Scanner scanner = new Scanner(System.in); + + // Initialize Dynamixel class for java + Dynamixel dynamixel = new Dynamixel(); + + // Initialize PortHandler Structs + // Set the port path + // Get methods and members of PortHandlerLinux or PortHandlerWindows + int port_num = dynamixel.portHandler(DEVICENAME); + + // Initialize PacketHandler Structs + dynamixel.packetHandler(); + + int dxl_comm_result = COMM_TX_FAIL; // Communication result + + byte dxl_error = 0; // Dynamixel error + int dxl_present_position = 0; // Present position + + // Open port + if (dynamixel.openPort(port_num)) + { + System.out.println("Succeeded to open the port!"); + } + else + { + System.out.println("Failed to open the port!"); + System.out.println("Press any key to terminate..."); + scanner.nextLine(); + return; + } + + // Set port baudrate + if (dynamixel.setBaudRate(port_num, BAUDRATE)) + { + System.out.println("Succeeded to change the baudrate!"); + } + else + { + System.out.println("Failed to change the baudrate!"); + System.out.println("Press any key to terminate..."); + scanner.nextLine(); + return; + } + + // Set operating mode to extended position control mode + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_OPERATING_MODE, EXT_POSITION_CONTROL_MODE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + else + { + System.out.println("Operating mode changed to extended position control mode. \n"); + } + + // Enable Dynamixel Torque + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + else + { + System.out.println("Dynamixel has been successfully connected"); + } + + while (true) + { + System.out.println("\nPress enter to continue! (or press e then enter to quit!)"); + + String ch = scanner.nextLine(); + if (ch.equals("e")) + break; + + System.out.println("\nPress SPACE key to clear multi-turn information! (or press ESC to stop!)\n"); + + // Write goal position + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, MAX_POSITION_VALUE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + do + { + // Read present position + dxl_present_position = dynamixel.read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + System.out.printf(" [ID: %d] GoalPos:%d PresPos:%d\n", DXL_ID, MAX_POSITION_VALUE, dxl_present_position); + + if (System.in.available() > 0) + { + + String c = scanner.nextLine(); + if(c.equals(KEY_FOR_CONTINUE)) + { + System.out.printf(" Stop & Clear Multi-Turn Information! \n"); + + // Write the present position to the goal position to stop moving + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + Thread.sleep(300); + + // Clear Multi-Turn Information + dynamixel.clearMultiTurn(port_num, PROTOCOL_VERSION, DXL_ID); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + // Read present position + dxl_present_position = dynamixel.read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + System.out.printf(" Present Position has been reset. : %03d \n", dxl_present_position); + + break; + } + + else if (c.equals(KEY_FOR_ESCAPE)) + { + System.out.printf("\n Stopped!! "); + + // Write the present position to the goal position to stop moving + dynamixel.write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + break; + } + } + + } while ((Math.abs(MAX_POSITION_VALUE - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD)); + } + + // Disable Dynamixel Torque + dynamixel.write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE); + if ((dxl_comm_result = dynamixel.getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS) + { + System.out.println(dynamixel.getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + } + else if ((dxl_error = dynamixel.getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0) + { + System.out.println(dynamixel.getRxPacketError(PROTOCOL_VERSION, dxl_error)); + } + + // Close port + dynamixel.closePort(port_num); + + return; + } +} \ No newline at end of file diff --git a/labview/protocol2.0/clear_multi_turn.vi b/labview/protocol2.0/clear_multi_turn.vi new file mode 100644 index 0000000000000000000000000000000000000000..17d95fc25ee9d302f34ecbd476bb18d9c40c5c67 GIT binary patch literal 54652 zcmeFZ1yCJL(=d8)m*5EmCqWWi0>Ldf1b4UK?oO}}T!U)_55e6%xFxu|1-Eeb5b`|H z_x--ATes@g|2H+eZPVS;GrK#pI|o@gSpgJ85R`7Ge;HyaqUv00k0L&&)u_M$6pZ%9FQ0IOpF171fM}5C=e%bBm&szz!?JggS-L&Ecy=hloisl zxO75kHE2B%+D`TW9~mgJKC=jHgsG=xX1c7F2uPgt|+(6L4Ovf3>$Bph& zus$58!!xsIy4-LEPF6Mswzju#&cp^z272~(&nzv7^(-yyY%I+%{xQLCW~paNYi6eV zt6{J=5Cs4A35WmyAi`@(5I9;nCFzChXXKn8zp?`q1_PgwSMNE&ROG<{@-+>ce1I3R5H;kHg9)AzChfHkY#U2Th zDD+YrdAPj6USdqy z7+;k#kBFA(9gAk|V%dhcKO!}y57AL0U4}=Z4@G8nxleP*N3?w+Dar@>B6kC^lUMfZ zj_)})e)OiRarW5RpXA!vIdv2)6f!;w+OEarbAfrD5FXkVCM_XF_K3{UeMcZB#$N-i z?_rb0J~1;zauIi`WxR-_4z8ZDg@2Zm)CM!eMst~&ol<(Tu#-^aDZ3KkA z#ACZ-Js1FYc}wrZb_;D@?|8bVZd>UnVJo4`Tk&wx^sScHFI-6olOlF)BQqBRpY}16 zv6~`6bAeXHdCNHHyx+ZTP?iX^T<>IJPhkE5aiQ;L_vDmlvLLO$C$)D(MJ( z%_B6kcBYy%g0QE_2}Ex_tS4w+Q|-oHoP?Z|5&Pn@q5cd**Pex3)4PrR>7A+&hn!)( z5vZpLX&wWz?Rn`qruwjtme5-AF26pHhz!3d`&{#u+fGbDapbO#o+e4$sLD!6OxuY# zT_|leLbagV+ouE=*5n4sqv>2PhdIT>*$l2aQyZM*EYPj=yExqa6AWcsh)AM&obSGj zRi;8kfoig7gfq;u+Nnnjz_ZurgN|T@&wfXSb2yHJ?#u%FDo4M0{D3_1pvPg>vFG7} zd)CX$tgx|{l6<{f2+}c-xj8-aFROU zcS^TI+lR13)!Faytf#WNRX#(atC&anb;26&edJiS!!Z))B#gOZMME>KaVBp6fHp~D zeWT@c4Q~;LS+1P@a2cOJEHh>*rbTOrT4<&bq0ncG4l7@^kh2Lzfqnc$%`HaJI?9#a zCf9x@mmD;Tus9;n_KRFN5z38P-+v#^=7%Y3p)D-?RI z<;Xi>Ek&IWE;wV;W*_4#AR+8Tnud7G>=2Mmy}6*bH?^PQESp3KuH{ zK~COT^jG&zVPf=A&LNMy3TqL1o1Agps#)F1Id>-{L1pg1Ft0V4Sx|jEEb`8OG6hAl zl62{X3Tba7(Jqdb@Y136T031wi>r)17wS3bCTgHm8Y@J8a6vw9QHPxxjM9@`-xTVv zEo!YqqZKDy>FXQP4t=P-SC3o^VuteRHJIMG2JAVd?mLFBK_A!&9Y0(cg&Xg-v$Q6t zpWoG+Hks61f5IE^^wS%!Wz(D!dw)@nJMr6)tB4uFg`m;fUr~3>LV`VE*NpmbAw0Vd z>gBEMZ#}RXZ`TQG_CRH`dDJjR9H90n&#EG3&IlD1*@k)bD&9tG63Nxg;X<&T=5lLj z;7Fjb>6A#5jNa|~HkSjwQ930tX=`hDFqhG*fwErRzKz#{cLy(WUrzRRcmp=M!#=*Z z1uk}k6fSm(1rc_T6cKhPtv{-88lH3^99cLL#_}qP{wDI%xm5@4O}pn^?;92q(0t-~ z+0k1EJ2Sq__W@61HMHGo0%LAct9S_PJa>0X+Lrz z3p`&qRATXQzL)Wm)>c*uR+K#%U=aWXEczQjf+(&4F-rT@%^8^z4wW^P2QXKW70FoA*wo)l?) zn^+m!nVW&Fc=23aU3gwyeFf*)3+S7F%GDKwm*-aqFP;ksFM8x}P`7gG;}7sJbM1&p%-Jg}TS>6?sg^ILte4X`b+%^M%QK)hhz;Az({9SuS={0VlC zej*Jmzs)2--vRA^LWA1}2B6ZlKH4`DT=iT1Z#3BEH~JE}0l8u32O5n2NcaCtUrqJ& zOkEGooBEfNA7_5lN1K}3{gDP;&irH#)OYbSjrI%ui#}RE%1`z#f$)B?f7SnS66MEu zKvPpc*+-e0>iEEc?6s=;{h+ z;@{;!K4|`v{J+=-mR(@uf3pu3gBAWFzd8c}$)N!hen`p>D3IPW0RBUKXJ_7Eg}>Mb zR|d}Ke_sM2z~GAAI8VOLNNAS;UDa0G5G#_4gbi$SNP@pU*({GT>Vn>n|a{) zi|3!nYb8X4e;%XPG$iQW^%)riAuJ;zbB%)^?4PeOEMR?&ca3#{?gHl)z@X|c5`YB) z1<6P~K|#C&erTeIiU`UAXYk4#3m&}MhunApu4FDM$S3cVR6DqV&_IkVJkXN@!6+O{ z=_fT{f5xxo$NUjD9rw~X@C7r9V7sO)gKZ;Ie4w2Z%9|Wdot(xK!HH6tiw+WX1FS?n zp505kIt{K_{>0LLIvAt}KE zer=!HYXEaVv)9Le+t+{HzAm6K^1n#_$L+KI*1pogMieh%WZr?^ZBS?UfhOJnLiHcnqC=$d8aLnIZ>EqMT z&`=97{%;?CAHDy-?L&Crio$PjN@`VcHIq}oyRw-0IKj2(U{T~BG95D^+aM`uU>M}% zB|CWSdbfY;2+G<&g(ls$MaGky^s3< zQ*qjZO^>7Y3O;^KS+f1j_~~S!KgsI{kf{{{Qb!KfTuD(6;o^BJzBwg3N!>_--~Mhx|@M5&IPH$ zqExK7K1ATH$RPhU13iUTqX}X?axLHk-s5GA{%oYr6BF2(eH3K(?;vdKkh2=CIiC-W zyLq$HAn6Gl#IO%4Wn_~*7XQH=h({(#?)4*YxN8A?OihVLGPQn>g zTKs16zNBB66Ne7x%VUCI!homVZx&{iO%ND|GvFbt1Mr|0-s)61SJ2ZzvTXM=g$rcV zHPBo6Is5WQk_i+?@Y>X)r_gLNo07bfLPM~Ge9zAev$;Gy+M9gQIFt-$H=B06*5djQ zMt#NIH%#ZHl2_=ZCPHEA+PnGTTK?gYt+M} zJc_hv4Hr~EM<5{$g_(T|WxYFK0F7UOTEF+C!Gx-{g%M(-mYL*hS*?bK+G(BlY*^#M z-6xNw!9C}jae5JUfZB|$roo_pgSJL7d9{OSRkrv4` z1UaExUZ0o0llLv+X_Cce>brZh_R0wOgW+$b8D(!-QmE$pjSY=M4;YrlI?*untFp^* z%-@wFpB7_R29T$L?erp?uz2LtxdKYzP6Oou8H@R((`4}Q!Wmp27;yxk8rrFzv9gkp zI&E@Yo*&)A$fKobOuCKnp!|JZrA`px%muue@QY#ixu=mvu})=r<_dg-uQyvdXXp(+ zK1@|HbCSd~ioxKpiXU%Z<{PPzX5nd3{m8n6h{VtFpMOxyx#R zQb+=8IlH*c6tp|~`neaW zaRg_D->D-HFJQUIiXV_hlUc7fZfx<=JsPxO2$!Y*0+DF<3X*bn*G?SfHoGfw4n>|u z&YjCq$;7f*MS@bb1tGsTw<(g_M5LSLG-DT@-81w|XnmDx_$zDkJQKt4&wI=}qGtQe zvz?)x-HnUT8azzEVPRogSH~6BE_)npszLJnNv^tWpaKk*iJ(x%hPs_O2K3_&DK3RH zavalQ=v!16O%#Zv!d6Xq&_o|{4xVP$y-3H~2!_rfR?9lWF!OH_lXyQAzt@|4aGQ=f zFD|pnrIT-9@Cz10yL)L)*8BP+mUac2$9;Ryn6^H}r3oF1R>O;3#ifBAikLC^^f(0# zZ$5Xquo*O)_q=6*-E5WjIQ7`%oXz-f>09THi79R_(S=$=+04r(ig@%1yT(+AOPXhO zfmlQQ!&q_Vhmqnfs?tpfm2N44kDtG;Y%@(OdT7y~oNvz-4AtzU0+e*cV~h*U!J@C0 zHGI*9Tw5BR&lWdOR8PBx2Bg}>gz7BtHR~*hAWo~u@K4X|alY8EuyiO{#(uF^vN^rO zCA4IEfb49#WJ)0ndHZ=5#*y!>$RfEXQcZQ2M55ypj4?&yPxQ7l4>S1;9u&OG-9Iuj zFtbb=3LQh16)L{E7k%2>2MRe58-0akFh6E5Ddxa0OQGhYs{fU~ zGA{bT$7;n+smT6eN|l$Yp(Zli z8R(pDnNCE~+*==(Avr?|u;bEeY0ihT%vyuqh#I&0-LYPf`=Sv^Y*C;_V`!g0?!&^2uzg!I*3EAi z18!wGmxyt>3+;CIaq7<5Yj^ya()RK=o)hyi#V>Gsm>Sg=aaQZ~iRtk@n`l{=I**3JI{1ZkEYzU6FsX+oS7=S+PQR<52JuNVd`)HFkp+} zc}_h(@@2R{$DXjbsxUO!Lm$)GTxtxu;(S*smrNUL=OITI*Yjg)Vs?F6tcg|6PGiz| zq&V+vq>(OuLJfL7T|(WRg|b;vkBjiBCQalEtSdHEZPwtB4VqKEVV+EEn|j zVst7yfUv{YvCpD_vuQx%k>B1Y`GTqIt{C>cZF z(&UprT&roS!f8n5IM~A?QxU?d>?+W}QB$SQ*d-3MIqjZSB1uImp&__ptWwjBsv1pF zTHQ5N<|k;E@~cX-!U!`cbD!_{vYw2OB+jCumSmY!K=)iT<2_AH_6~0d?JU*QfvqCF z0m*^}*MoX}+)pgK_O8O4#=70;(v*2!#&?!)-5%n2&EnmbLYQw-nXF#%oXsf^&3*Np zk9m1BAVo6WfUlPDHR=mveyOfaP}EeNlIg5H!=6iFZ5f>AT%+c`fTp8pd6TTHFbpfHDRYN}vGm0Kh{5BnUnL01ZJ2Q45I!CGd^BKEeV= zFEIAaBpCY!$9TBl_v)apkYbPu3NU;i3zR;91ix4KUqSOBC3j8rPtYMbTHQj~#WCnkp5lT5ZNlN(UlP~s5*pZE2ROr^~& z>c!=;Q&(tpY(BeZRl=GRTyu?Zz+6sro;ihnogP%r~ z8$Qaj8QglU5rcYG6wfOeVd8J*C_gS5V|GWGII(i(lQCi9;#{-vS`s?}t(bl}5;QIC z1>!gjBx^`D9=%khDjwtPs!Y^@8}#jtvlaN=h&bq21moO(NL3*>_Y+THb{p+7$LXdJ zf5Wq!RG7$;kKF6qJ(({O*aIinU%?a~XQX4_-!kOuZ;e4%UrcF^_v5gzUb%{T7l6~9 zprh03{`lCe^Ih;!rQtNJC3eW$MaPF{tbN@?bNZ`Cb+=|=FsUY6Uy$z>QA0EC+nhgU z6xt3lKudtP?Th`8pxe;HZ5O2;tA_6B6>u;e73lqBrNwbq=RhSyTKI`_im)jL7boFe zzj^md=L+c<1*+QFi7;Pj6VHn!y+>cCJN%9p(dP24^EL)cce`*mEJ$mDxKktaZ-1zG z-rZ9hn445M#}V6NA+lrng=pH4Y(suBxn>wP^LWXf%4b856Z^KBY`j1>rxGEP2gELi z;fHU7!37wIkieD|@W53Dp@D}d2o1D&J*IVkq0N4w9lU^{?Dem{(~mSlMNLB$anV-k z-k&fCdI&}k=zp-c2^%>-m5t!{8Heqla|8$9}n zfXq$IP;dDKWx#h|0HA8*3)i3i$BP)<}5U;^_N=;y#2QQd155cIIHjGWL7 zzN#oAcoPHkg@mZC{x?1hIxrKv(T5@D7yPad^GH!tUhYOmLQwwZEh`8{TT(&vCMPg< zBBI~>1tw5NR-X7qKS@zQ{>B$fk+3`;{|&zde7?Dve`EcA1mAnF;Rn5*Kk#P%z+3&D z2NC@TUeXQk`-24_Ar}9j_x&CC4>3a){jLY3{TuvX4{r8`2mNn5;KOfta6jp@Q6cmQKa!R`Ng#hM zs)vIM{?Y^P_v<~XJy8Y`iz(egp=+i?k~1KbU-xHx-=m7v_x=Uj`xc?ZRa*=;V%SvR zhJPLR@A@G0#Pt&R$BW*!b!-7V{B}ijfGRXl0DxKjXOAlCKO0dY(e$0nw45HXYU$CM zIRKkZ(X1?O?1)8lEcDF`Z2sMsN)5CQcn<%n4W%e*`)iGBXWuuRe&6u=o1a@&I(nuC zfAI9+@1B0IbL|WA=7#)NU&xkL1{TCJK*N9reP8a}|GS@`^}#-%esKZ%tv%?rKx6oI z?DdIdb?gj&@I&)=Kfl)j`-1+jzVLzd1u=MSKrHJ-Eb}doLN+#*KlB&t-@X2)+F<`6 zm|p_;t*tm<|G&Hbo>_*!`~F)^uv^$)-2R?pynos)?*#TQYhVj(DgPnYOn>+M_qt%; zaR1deCfN5cZf_ROw14;dr&?ftAoyP#{+44*N1JDM1`PbpcEDO1+}eMy#sB2*54EoS zA^bOg7&Znv`piGM``(`q|K7eo)dKrN{KXvz@}K?wz|Hg~Z@@)$L8OM-v1KrH|5Hw*s*e}AZT?GNR@`9sk&v$Qq%ev`WK zMEUp3|Ez!Q1NFuScmnr*kAFLGIh!~o<;$^S_|hXs-$s;9a1-T0Fi2^{bVj707$3jw ztb!$dueG;}L$MfUj-pQmhaG*HVLzOm1gFfwAW>1OhxYY8D;@1t0VbRiThqGmdCthwvw*Lbs?+jPsqKx;VnvP49PX(XD7~1Vg&oL) zm>T_VYU;Ln$aP>R$j)|Xw?p#4s z^_;yfs@}ZPKx^C{zl`*$6fc_j=&`F+@an2UT1U%~BUEUt4Z~h7 z#p-JL(w(#z83x6r5ur9p)^K}Y29LEn8KtW1R2v4<5?_){68VV^_UWKGJ;W&YCnjdt zKOcq6*Q7HIKwUjZP+>dZrOQe~8{~c9zdSgB)2O?zn@TQ8jN~>0>!tnx4F>NyMiT6s zW*f>T^d#gr4UCVld%c)+VDg?TSdk>b7&Wt7(I&yIK%GtqSuq$(WtE#`AS*SQ;Q8my znpD6R__0{sRYzlM2%(2GeVFr54b9kst(h{datd{lX znU8e^ZoF;vjN9EEuXAlCGlUV@vIEva+wPKs1ou9>t=-ddNhg%$@pY&A0}m(~cdd4@ z{qmxO`ndNA7`3j}S_)^8k?xdQoDRjZPpJgviD6gHMDlQCb)qinK9dw>H z9eZ_=nYsxC1Z#HGY}4JLFp1qndFK+bPKBQ6j}{zc9j@ zQBocmh*KV!^&WS}L%Ryt={Zg@Iouz=++11SOFU`FD4obU(+i2Ma2z(A@z_pnmC_w} zE$zY;5>sa!Kg?l>a{pLyr*5gcw~Lr>PFajgT^G^V^*R zL0i;smIs3Nl5+}==HSX-?mRG?sZzKSW?Pb}q{`Lmozo3xBha!@#hyu=akf$;{mhr4 z-m{rCcD`~s%DiIJs5Iy3Q55_rzo5PuzRuzFBgGTEwfDQBri(PU+?G`Cq6#G`9`kV1 z-q&i0YL_mMooHPN&V3h~Ij^h0(Yb4MP#8S_d5i7QL!YYXk9g)F$CIA5O$AISL9#RYM1ZE#^wdu5k7beJrt5F0$E(#+1~U{R=Z}vS=P{ zi9E^E)XICV+sc+{d@R_KWoo{d%XLCc`9#x7Pjg>YvOfsPfTbkosArqAj>DvmIn0jx zNx79IgO(PP|2EVTjJrK-?Tf)+sny|1j}n)uox_iEl5C$Y|>GxR;!4{z?!{WubqE1JU_@eSeaDyrBE@oU9^pQ zF|huiZ8mq#WfSEyE=yPvF+uVt`?iu5X5|N%N*d>k9RX>( zcNhQXE4TwhvbO76J#_v*zf%I{@;ARz`rkY=udRGL_}t)-z&?0jp@aKvN&DR>ApDEn zKh915U>A5C;R0-2N}zaM%m0(@-{-_P&%!@g2G&71<3C&cE!IEHQ2uTaoP$R|QU2NL zA9C>Ps^{-E!BIB+S9`y&ZT_>xj-M_5*6yFzF#p+B|9`Rdr&;XZEdu?Ga{}ZLSQ6tJ z|7`gWdHmao;6K}61#A-o#p%D=|NFfEKYQ2(tiuCE`)3co<@rCYrv9^sS-?6TP^^CT z@P{1zJlFfXRbZsy2L5dAw|Kw(7Wa?y+UuI%4&UzyV2d(8TLj|!!(9G*U7*5`b$PG( z;0Y-RbRT%hWMc-*-`pYGuIM>;LXI^t@Z(w8M8J31)&7J4DjXX!*`WoYNdMCJp`X?>Db=6Ehm<_(J1=KWXV`6*CvBH|dy=b%^O#?r7ZfBq!-j?;H&e3swAG^7 z6`ZAG_M)5?Zt)3RnFiQF4qCm_k+^MySI&C|>UEc4McY*rnS*SOM_d_;xh?#VpdM;P z%S$hLjJ^)C9hc-1N7ngXbijeRh^MbS6n4S$68u3r;#1xL=Wtd&7o5QzVvRM()9`6; zJE2&e2Q-W?L94QGCph6VDD8cXd+-EgRy8wpazbS~oG|Tbb9lZ7t|DUE8k9_AaQOOoXw7@1kG_7S8^X8pun*GFU*Vr1w&y!fT9Vl&ZH8}h#u`kWy}-9} zgO$Z!ygz#)6dsXigcnT7g-C_CW*UBViP(IC*095O#+0=mUd-js-~l;|(yn&TCwcC~ zw&IBIQHr-7WT>-WnpTiR%243{<2czS6y z30f2Gm_ckWCtgyw#LEv)d3`{V#S~ufjQ(Yxz!?qsm3p%>&_pUv!V{b<^eln!UcM^A zb=N|K?M}CM-Bcnpme9`O)BcN=5o-=2T7Gu$gF7UWTFB-;K#wt5M7~2BEGMQQIgM+m zeRD95v5~K1rT7wctswxcWWoN{QEf zIpP#ujmrE5ltR*UBfjd^h;dJP9)AyptYF+l*l-376Fogu1tU zBq>N*&oyK$1mej#Cx|X{(0`@V@2&no%LaA6P0oFlY@8itsTO-uNPgx`e2-afk2Z=o zgi7krvxIu6%7EHPTjk2x7(2Qmlzrrl+NDW1n)_$8BS&pm+th6jiBa`1?&ic=v!Sy^ zd}fQnu#s$0z;HyN8Izc#Xc=L!AORAY*jgdfB6-h(b-{w1mUpuBr76j_Y$wddZMZN= zy?37uP#0m{BTY+f8rczJkk|_z48252>MpTqD#uzOwm@8CkF%DVrzNu>Tu^UOxW$%g z{i#Kgq9DTBV*a&g0mjZsW@}_O#kLK#BNR>C6M{DQ>0`q-=fHEU7&SqJO1F8Fx04}x z>JZlU@)igSH7y@W3u3If=M6E-qpkf~G{h%AzN8^7(6nh(!-I2=$?d6ma<>CJTC8BW z3uXf7nDdmS=rG5psFe>rI@$BotzMbvRXR~yx9Cjj1oSr@)Wlb?N9NXGha!oS zvoW;xS@_z~#N?7&z;>$l=xg$;Ls@s9=X;al~ky z*cQ+o6HFXtozvxPj?v3SVskgW^vVTnjxij`MjX+iD!ZteDr6yUqkU4b5usTZpk0kj z@~yzhLEEr0673b5)Xgc3x*o3ur1ZoawvU&rl!gN)i_Nan!tx1kqNuIt40>hzgH4t0 zB6n1idxG^brXyx4+6Er6nkQ@aq`N#$WnZ?HMKi%-$e|WZ)W9p7uj4|a`<6qMcZMbd z(e@eVnlnDbV2^GXg-gHP>!*=oH+;Gfv-3EAtbU~^CADQhw6a38?ai3WSDB#03s+3q zo*6Zpxig0)wLV+*FY2emO$2L7U2o>umk&+UotGL+bLVF4c3Lc~>mGdBepo(rwi`4T z5fRb9Ho6L_WqZ)Q-M_oSs*Yn0{BoGM4Sir!#9jL>12HFRs1yN2SV@6sD4eMfuB$Ml zT8n{gH>oYxK;?Fay65VXhsOH_qpO22`UR5P&R(ZG-;F1eG7KQhVH_QE!IUf=>&=~Z zbGF*I)4R-0{}|GC7Bo=V`w&XQ0L}8?Wh+k$Z7ml&TPC3hYjv?MILk-MnQRwi)5^7|$db?rK^ zt>j9`FQGm{GFLZss#e<{!t3BuNTL~uBs~=yyiX`6J2u?kCMi6&_!Og9q)9w`G%|$IH!!T5igib4L@(= zE&GVL(aM+_QYuT~x1NdNN?c-^w4IOT8C9ptCgTPwIX{q2RF`z<=FdyvWABSB`eT?b zh#7QJrGGUN>I{Aob0E{{^7IQl>%d+2MM{^6^oKlKHiEb;f@SrPaqVRb#lrfc6EZ`0 zlFTT0_Htc0xx=Pd`)yJ~Vo&AAZq+M@*IUe3Bu2u>7t>|yzp|L=X5HGSzQUyldu=(B zL10Ei`@Z97&PUM3$6{tv-SiyRyyW1ihS7`sv7OS&y6^%b%CfSqcU+aE8t+M|adcYO zyY%DOhCe(d!(!1)JSqyoXeHnJJU=j9LFY&$IAXH9I}#C>^CG4{xFopVd|}=L<4kh^ zMuRg=NO2Y4xo258HoU_VM(6$OQ4zfc%#C*t5MGmCR8y;PP~KK`ZA)i5(yHLUQsWVO zy$)44W^&In_RaR$Fl07CuiwY%T>>n$qxvw$nyEKa&p29aWDoVzBM)=kC~^l$H;AJV z4pZZbJ>sQCogz!sx?Kdjt6E4m7)ZoRIwxvblJkN^6mw%oB0h4ljMr0;)kaCYj?DH` zl(v5+jgm!!lcsyMB-dJI;fZJns-3`ZN!}T&<1pL%++8wuW{y=AO>Vgt;!spDX|G08 zuyNU@zNMk?S%-#k@bM;ABpX=>=WZ1Hsk@w33RM*=<7x{7QX8U*qM`7$`s2ijK zA+Dv((-FBAubVTYt0(92>RaZVuaMX9DhzqVHkoA)?-WKJ%BDmrm`5Di;c%$bMwdQL z&g&K(eFsUg;qh<-F*q-TU$Hvc-jhRRgnR>Eb@Vt%F~EJQjmPBOVh&_(v*ELVd?_U} zSnR|U*-aCH9L{u*f+mdu?E{g_FA|Yfs$pr7^^|x^a-xOKQ0*ZOm5U#_M`jDx)8h3) z9FoEg>%|AQ#WFh&vpU7@1lxa%wQ1-UEE~0Z%#0KtZ9JV73(o8Idk_}QLXw=D&ri7*EYn6whDdnR03Q$%PmaeVj~&cP}3195uum*%pyytycdc9^bLo*+f0uj42d^Fpnbhd{Xj` zZ16)S@&_s7FGb|Z5h-L|x>{x-b}(-JaE%DhQ8&n^nDK7;qF3UQEW*pI&(e3sdT zoz(>!Ad@{uq>!zd>mwAUlt#_NuW)Z7XTIEd*CSM(J%&nN5RF)-E(9$=X^jCr#!U;QA;@@?+pA&q2FCF%PLt~kN> zX?hcvqFA(s*}Z6j!iQe*?nN-YS1?kVbYIaZgz>b)i8H9WC*~H={+a5+bDwWmmqy>y1t8cxo5lRII7o=6RW9@cKKUt8=|vcWI;5m~nGe z<672!27GH<5%tF}CSoV%vnu5aV|BP2rN=ueLiMA)kyq)M3_Mi|&c)ZB(0#qm6PN218cL%1pd}*{3-Y`7&f?<1=;UYmPV&R}5&PFp zNxSL0x7dGz-z4|W<(75$$SQBCkyy|`O)Y~213VU09t?7;1eTX;Ibt@)qGoEGPpjZl zC`R=x5ZNdxc7Je1ipi=j$=YX)*c4PK+d=m%52~-7w=B0)6?)BSXMjILBpq8-fsZxvGy&c|r*;89D4iO)F5a{A4S(I9WG<$ z3O`ib8f(~{K^?<wK=CTN zVzzxno=cf-^9_HBJ>jhccfMCRumpd%>$y}e=^!lXr{JZzo`?BzqUN-jnODgY>{?2! z{k}o{+OsSLeVW;Q&)=_pP+I-KmduSw`?l|PoB~m5GPiUjw+3c=MqdiwZr-zB;< zG>goIGb~$o3zTGGbGLMF*aLVkkHf4$g7GhGmdB#%F{lgusH7S6CW2G%)zs28-O^q@ zI23G#+j>WKH2lf9INcm#~@BCe5**wDTJ%E*CYe$6+T@DY(A`n zj;l&`I@I_j2KF7hLiCBup0Ar_YHFGNYq0fo?eGAA0mrp5F- zeJWojZUwTtA^LmLW(BLncicuyC4Dte5!fY=CL(2*{uqOYg8Is|EN9i%tn!Qt>no+2 z0yE^QlpEdcUfb>$q;ouTf^@X8bqmEW0;Y2EpX8Yf=~7_=oxgG~ry2Z~#1o{^_+DW4s*Q#UIi!A2BOEs;JT<$=L|k-=6?<_?pw zD#@P3PqfYZ;=o;D(f^$cd5uC+d#PA9yIA%fyUlrzj1zyT>@y7Fu%hV$f^6Aa1!u=W zwG8gE*?ifN>$TAe;eoBV3wJyT-Yg5~+&7;I_G=}zsE}G5-I(<1Fh{QpsTAvMR_!EX zw>fT=IWf;)e9B9t{@nR~bfi0+UnG=7XQHSoGs)S&EtxN8tA>u`-hvNEGzH1$Gv*5i zvLj9)tiNJrYZ8nlk?pYwZA+KBoV01=l#?o1tl}XS_9(39!!oBs?h^vo)C>EgpfR$n zY1uHFX(q)LAyOQk<;E9!gmVmb&mNG(He(hBPYMv)2hX6dSUN|$l)FZ|I65z~;R?*T za*EX|c%|Tsp4U8iSB|`~*-V!h?Q%cbB}gatFg%bVVQ)~7q7Dxg?n}&JZ1Db(n*rB* zf1(}q%H&hA+9B0iCc@KC?J_5Mik5i&x6%n|v&0Xj5Tgi=Ay*lEdns!;j>k$MA zMzH$l_L>r4sN+!)FLx7Z4W3D-Al`F1$kFB}#cA(zCEGI`kSkq$S9B})VlJ&?YqTw1hie^<20FR`YH9cCS8C3wFHGJARfNZ0)@ zOYJ`W8Y?u1DbNQMGCMF^`C+=r?k7~QWa-jsSmr*cq6H~u;L=Ij1-^J3L%OFi@8;-T zoZ|EfbB4_3*yJ#$6mAr&!*ZY@7(gJXan@O=(Kd6NI2K}H4C&4HaUe)P-Xd*YVEXL-K3eRmZTz}i9Xl-nOgQ}1{Y;HbWc zYqzr`q*JUFNG^5cCB-Q?2u^?c9#0vY##Op`vhG-Dn?1Q&ZW1O=>!ez1X&b%rl(bxC zMG*;sg0y_H@XoCpob!KQPem_kY+ z43zjpCxyj2smh2G66>%2ie@T7vYSU3rz*PMl;hI-eJmWsM)L)yl(19*hn9s{!<=ldk`M`bgK#C=!<(*Gq^Bp&!lL;q9 zZ)vS#vD#7}ww!4^BDK-ua185k7hL3CmlxCA1j>B$d9Qy{97jx~97HYfe<1zks8m8( zj)PE$v-ArER9r$v21QyhbgQ4}$|$d-m5n-E7jQrFr$rwLe(dLBkw1+ZAZz(Xz`_6@ zamR-8a5q5V2>vhyz{+%z-E}b$-;Hg_HkS3?F$02mY|V{Jgg(`lCeH4oj39{|Jh@N1 z1n(b@%kd%FWkOx7_Ac#dK0f8T?D`g@Jjt@2tA<#uX5I(1di|kHI+jYENe0uZr=S#v0A-9bBNzW7_Uz zbnTuP!78US-g+1jcsO_FmbJr9vJ6v&_4&Sy7FOlC{kCSrc~u8jmTk4rHa_WbzL~*V zYVf|}LDD55SBxf%acM`jv~)HP(kiW+!ria3W$X4k{FhA?dm>y3a0>LTuKA(#ls*XM zM?&)`^RaAI@~r{(UIf-%lAgQtBM?6LLYCO>9SGRObH0=hAC#R3y~t!+jpI{7eGZ#U zv+eOweWzimA=ZoTGv4lVR+x*nGw~hIT+%B0yDocUyOvoGGtJ&I2sj}S>_%h!0(v+geCUfYm)fDCbrA6@x>=pC%(+=NNWn z{q7s?TaN`Y5+S`K8gSeK?pzEoPX^6yeMP;a?sll--io!^SMKcRQ~lZs`>GPzE&1U+ zS1zgdmFamBH3NNtN3-e&!?jhBl~s|Qv10s}A*?YHX<`XN6zy`<)-S~TmlF30c@_ih zXY{EoZ+pBUr9sJ(|Ew#wCYWG? z#HYZ%K?8|Q{BcxYCbnxUR%!VyOAV{agRmZBy56!(_K0a#`wb~~Zo4j(BfWYtrnn=5$%A5e zfs91w>fes$;mOEF;i34+>64xKMc}E1bh*`*#vpg7F`5()gGb8To^OmBb!$xdC;2Z_ zfP%`M+!iY8Mp5#%zTW5)XTX4>YLx7nRHB&agFVdQJ+gbR^+HppSofmL+oU}cPCl7q z@+c+jVO|im_np?`gB{E3>t0-V1D<2-48$%tbpQpG`6oSMu5dyZ1TkOdULGkvy{P%P zu!2VI;Xl;UmnM0kZr;|{z=O?0^#0_%2T?6&RRivwlrj=&o*5~3jLTwt(s!(K2V+Z3 zvTT8cp;mMQ_LDO?zL!_#`{upsU&>q0FmJ06?!eSJU8)zHl<;}jSW86e^;WJDsB7}3bC@^DO`!RM}#OoE&}(g^(AL(o>~2h z4<`kJC!fy|a)@)eu>+yIehFfEUdHpqPwJzyZ*20oPhAXMQq_e&PNte3cDDMT(PnkO zUd)%b`9K?#$am+0>bwndpo~|${xh;qTX-U$#}_DHR^RA%HO`hogw5}&hG$s?EHge- z3YAB|5(V!twJ_JT+xZ|=Fy+FH!9|`VMtx?qW-FI?dsQTP9{c}r_ZCo9b?f3c-O?Z> z(jXlo-7QFWN|$sBNJ%5zAl;yJBPAu>f+F1|-Sy4w8~5Dvo_p?h-|vp`|Br7C=X!oK z*E63PdvBR*&bSl1RZS+RxVk}_wAgy$buKzf#tF1UOZ@8}voHz9^>X22miEnG7j1|i z{3Ltey+MkXIA+u6lH$QPIN%|+`sn+Q-dBTfXptpgdpx@Qp*hY?3~hB!rOWI&oD>Gt z-wdND$us)RobyODjihYV33fNzOg4p2UI{yk+!_h#Ml2AVrpRFZg!-YclyPUtBs69a z=OyB1(ua6To7DGYbb@-GnDCOd@zDjWz%|X*U0z>B$v2B!GmheK^d1sFhRC0_qZced zmDbyRd5&M8I&P-YCt9)^znOwKg`ioxG&Or0(z?L(gkt)8$fp?bpPwzgM?4+ zT7Js4j-G&5?KCP<#fdMCun_!*){aZKtvuVIZJO(x_+F~v&haV=6Y{&4wTT@zw zHr>k`u1&1B)~9HPHSX_e5kL7zwI*|DDlL46MB0O1aODqEmbr5jZKIDya{2C>#9UwK*;HnvqGANz3?`LT zBQ9@#drPm`Z54?yjga0o?pe>}|gZX*#BjE*rw z`zAsW)b$d-zA-e?g6xe{9{3TM_LL=G0`Hl}aN%=xGor-Ispu%u$`sGkvoDw5%VD1_ z6UmUYPOh{_)h3P=nX1ly(G+ICGYG0Z-+a``g2QjDyZJ3f*6q!ko=pO$?-ouNmK;ge z$8KgGuP%a@sD$vb7m_mH3WXXh9&afG?RI;pw3U3{IpZJCKQno5MfN$l*ZRj;u) z={iODmZO3ZdADj`i0}F~yK8bb#FBz7sn?_Hn&Vm57c8-NyxIr{V)Ff5bch~SufM!* z_PK$U+q_cvV&RS@FR3;yKh-jL{x&~_Wd%v+BUk9Sil#)msEstSj~&YqQ?7C3Sm=qqrBoziedEFGJ&n_Jn~RMn}xsMH^O z(&_chG&wE$K8Em^N5ELVdOje0#i~WdnQHA-E!>D>nzd&R>P? zW6m!2$#^JW#m&MRWjTt4-QmtFQ9)y1BD`c8sotMjj zsMM|K72!wv1m;KgrGs6F1f)h+wa;Yvk?j%I)`sI>t1;R=zC}6^Pjvf6mBJM~<xV_mcaced%F3(2O-Li*OrH#{_V zBReTK#Bw(Sfi$hH-CYc}?1xEPf`Y@l>~XI&5obhR)28Tg=^Ghw%^io6)2m*tm<0Qn zpC2HPI}j~0_FuP7$4?9zN$quGyPDTEB-P%VpLBj92tT?f_%hlS{O%$(g(jo(fF`J| z{~!(RzH+z=zWN1!%Y4_sMzVW%1kK&^@X$7S*Phm8g0&Wyv$96jWs&w)8SHz5_5=>< zyC;h-0Sj6=cM7l-42v62?lF9$CS|hrmXNf0fGB91{Zr%;a}XE%r_d#`&N;Mm_D>N@kI?o_+#hx} z6V7)Y=m%vQU1$Ymn!7*lyhUppJb>zai}u*$g0)kMz&mXz7wxg}1$QScfneW(WzYz# zSK^Xk5cnI4zwm`nr)`h`+BLx$hi;EOd}jh0B0-r^L+TPykTqeMaYM!uLJ%>btyx3h zl6ufAf&Q>PU*{t^N&>Wg4!5Q1GdBeLUlpqE|bXMJNd(KYI0EfHco*+I{yi7y>?t>)? zoX6(wYwkF9FS(y}bS;=%ED*`v=mnh*aUO~U%|1+af7BU=pW;rlbSX=;g>tEIdmnTE zcnl2|7qT$!|C&9ip=}}RK!H7}A#Xtbs|ykhn+k4bzq@3x;13*r0R}xT zT@ZK;pbY|`9B4%dKrEIH00AsPhN^%7SU(F@1p!I`-VlJO3XZCPLV#4~2>`?j05}l% z0w4qekPRoPA@CEx90ZO41Oou8S)rhoApjf{Is_o53xxn305S+b-ro;{z!CsX0LYN` z!U8o#)&dX-34ti@0f9&Wl#nP$3kE?#z`9>3Cjh9BTDSs0a|9K90RiwP60{tE2gxAH z8RSBT81oAVL7xZE2LJ;RKq~~;0JK8@Qk_u%SZ@G)0)Qs~010HrQvr|x2{8sR015E} z&<_a#ia|p<30@8W1qj@NC=>wr*Z>eAKnwt~)d;>OfEfUgMe0yP0EnLhD1rdw&EYHv zKx$eFfp`EV5P%GVj}XWLkPm?Z0EG~!1)vK7NZ-hT0OW0GbqGK@Nj3lype~d!1i%Vl zs9Xrp1CW3Kq|@d>0MZXNKtd8(0FnSmLjVkeC{l>&#vlOMhh-c9Z6<&O0HDGjz|9Im z-~twf_5|(m4GIby4{!&lG>{1Hz>Nbxs3CM2aC^YDf-nmpFF<;*(-rCx7$%?(BZ20@ zum$fT>jCKs8X3HTfN2Vf2JbOrKLV8s2M+WA;w0eGfy)K%9H>qDo9e{Hz(4w1eTW7@ z`CxQIgXhD&1LbpqXA%OP7J*X&VJ$$W00*868Eml5fWb46*MS2a85T&m1>k_ba0bAE z{sFfMh7T8zpsp}iKre`HKwm6t;M_p>DhF;F=nl+*0jvzK3d(5%&uswx!UH&<2VNG~ zDEA@g3`~H5O>rLs+kOEKO&r1_+da9t0!`h!+78*!tI~ ze*kpH2Y#&IhbZXI&_Gux(5BFdK!Q5JNc|>%by^}|`*`37z5Q301$q!?0Y9+muMP`o zBS>EaW&G-aWFWj2_$h#d^jb=wrx=hl;Q25>(gF#YnCO5W!azO&eh>x)?D}hJW&jeR zKO>NpKr#af!k}0{IgtMR6!^D(lfUK&U`xo%0QC$=M<9V+e@&^}pj_~5C?4QH0g@Nk z6=DZIV4BxJ@&o@JkRa^WJR%C@Jn#cuf6XG|K(YZpc;>HJR}%DRIN+BCrc(J``T+^r z1~OYfJqPiSddLEQ&TkSM^bIIE(8ni!lQ^Kx5I-s^kT0O1$RLw1kmT^cNmNh=D23n0 zq#}@Yz^?>k2$0IZ&oAKFI2^#Q4$2MuT|)E*epJwxz&;uWQS_VTmU)M z0y4g#fbAjU77ElAGH#(jJ441Tq@5vS7jixnWQ;-y|29UUq(FN&06(NX-T?{P11}3m z`QOGOlp1&xC<96ZgoAMhu>*oHkf5(Y#uAhza6reuTz@(9Vl8eycE>^X@C#knkk@qW zou+S&^y{iir}mtO7|4lsMWBRV`#<=Cia=cE{S9<9lqz)6y()C#wJLOi3mkA%&~as| zzg*G+6^MfaX-I&>hmOZQ^vmGGHjJlw_$c%K$S^?W(9fS8AKEW~0NU66w=(}I`(H`O zw=Q6#|MDBypWn)${_XYO?qd!f@@G;10e_YW$$x+O57+r6<0a$bKgIt?#`|CKAk**H zZ~5;xS2sZ#$o>3=;fC=q@vHZ%ARcl*X9U;cAK8I!kmqlLm`#u!+|L`_3|B>Ri{QHpnAPN!-i3hqu%AlnD z&3^X>Ab|4MKS(Y9IX@H>WF%4k`ggFufAG)G2ayMm1Rw<@A=E$X4+-1<6$42I;{U82 zq;LHS0=I+xgI{U>@c$|i`{>=pp0RwIK%N+lFE&v*oFE~=r7FrFs zSdij3zdf`vbP2S`FF%-8p^KnppmU+YdL*pAtwZAe&QSrRmK%0_4TNOi2-ov(v~41)yq-4%xgMot~o zlyD6jbt#biqqG?DkvcK0YPAgoGmTjZvS#;0Cu$1q(*+jJMHE&K-O(nVR?hAnSPgG* zyqXO%)mk|6Xpts$S+lS#8`k+y{-40W}@D#pNpHGlcS zw>zg-aZ@f#0(#RT3WuN3I-?KV`B8#9MY<3rl%$7^on{IPm$`c^p2kK?QM7gU@*Oh{ z!Rw^hs^!Axh9Jw~XLG|37P&c-mcAYM20lDW0@+jT3;4`*I@fhm`CU3}SI z2M@7GegT)Zg-T6Eas7|#E#y)e86Nzk6*ku+v{#p2B%%renF?AiE&AtWH@t~EOxpqu2dYfsMi1R_0}bh5NjW)!In1h4 zO#C*Ed8!!W9`dKlbCaOY?4QrCxKNXkaP zsJZl8@9Kef1VMgY3$!E0?ziGfxLDk5FL3&*hYAVay;q82#QB5UtmEZfwE65O&+kpfzrJxTqRy-AQx5Et# zCE}bd*ID|A`SrWSPqM$%Z&$McQWeXvdugtutwV8EuI)kj>aW zXWw)FhISG09DcVMpKFjU9{E2v5pDta2`A$IeooiNo_H$Vr&*iUy1U0QB$fdChEYAz z2Dh6H6CJj@DxZqJ%7lu?K{Pbxqf5?9>o-?1n8}vod|cFPz6T6R%5kal3&G#0h_=&BWIvCz6SzMc6D>O}O|k51NaMEs{PkgII1bEf?Uq!# zEH!oWnC|rA7f33lS&|l4OxpQd#IK-I)l0<{O;J5gr!B)K(OPgC6)cohP?C zkfwB##o-o^sP@R2W~F=9xc-QkP{5oERjk}h5JjL8*%hqq6<5U>a8;^QDU|mk&{eB^ zq*WuHyuD6*5jU2}QR^mugTxk+;x6S4FCfJ8#XK`Zu(MUCwqhRROpOY^(*lXGXTDEU z^x$y#L#@FV)j0gN=+1X)cfJ0V74s53pA~v@zQ1V~&7#iC?o<-!eA&R$5fmnAr1bR) z&#fR^CAmapdqt*GE#z$nr`Wmo+3|U{=hp4WG?zd2`+SkDn?gIB*Qa-xF6X_@=TetJ z+dW=sQyvG4<&4B*phg7^}!Sr>JMnjslOGMuhH3 zzVkaQ2N-3A($rua&_~nq=4m5lx0-%dEn`2L@Xg`55I;U3FBn>C_rO?eZ-xI>PjTLO zpyZF_Njv*#p(_}!{?+4`7e6i*Ecc&|bzqo$oVN(dhkm;@`tcQNYF6inWlQs0G#_8| zHZ|hAC{wLrio2W6sE1kOm_Dd&ePxmaYChkK4=S@u9K`{Zgc&@2H=OVRTCiQuq2Q`p$w+;Jo&}6?F~D@?4Ye|` zr{X)%{zOHvA82u~ESloaz>G8E5A4l1VZ@7DZs^4P{Bc^?q$N~R-J&7#*{26{k*#3} zPHeH+tymF~hOAMKg)$yrN)lWW2Nau<$*%T{4Q=A#`c{3BfQdwVCirEv(%h*a$tNn& zmlCn#Bu^FRNdiZUO#26iEL#cLfrMvx@6-&whUKO(5X53h8Q*kr5TGRa1kLwhv} zsH37td$Ok-8ZjxB2Kd>$tRzpy#mmB$0wjkmjPj|r7?U*ql$<)^&x6bk5ipZRZ_gLXvl6zI^Ivdmd_PthZsct8Ed1$RYpZ?5 zrI)tIRQiMP&co2E{s6j^*y6~O(?d>dSc`Xf)YY%e*EyUf{h=OGn?`Ogss!HJQtCsS zABgfy&;xV2Bt#N68n64jZHyhM-f>+*udHk;)iU*SK=wi7w_R%bf2_`3c6 zi|(lqnz)|_CyH*=HW>t4FCA`-=O6G0JDXr(rgmkK3qW`FuWkq!A9?afG_1vIv$t~W-@vW{KbB?wVx!0-~Q$1}C zhukfTBMR0qbH0!4i`U4@hkWy9$VJ>!7K!%INo99Ng>Ua#Kl(oYL=4(OS}%(3$g)CQY1 zR_k6T`3Br%9O31k#cK#Km^AICyEva*SKSz3*_q2Q?Ds#;VGNr%G$?Y7@~K?CdWrRJ zT8zV;ue1yU|GWtS;TneAZie^(!`AWgN&ta$piR}kSDRd&%bIUU!Ysf#h7dU_un-cC z)}yQO#h7XI3Psg81WMvZB|=#I!PJ&vZaKZggVqwWB2xvioZZ z>6fc+&LecyE1RYk-#K-gUbZp7xCvwxKWH?AWAuUzlAl6 z&E*eUJmf1?ZeL47%&XuIX~s`*2Hi#-B$xjn9O;tWS5)hM}^A$~iVWedeayFVX{teWAT0WtY)hdXLzZPL0cxsRKK@f#Ly-xkF@Ljhb-d>i*u`FFUd2bgsQGygb2i>76Gu|5 zgG;tdF&qZkwkayjB=AqcT3nJxgbz%bVx8BE29a7UubwOM zIhDQC>S|F9qMFPNMX4Y9I3{rTMRQls!P#Duh?rO|r0>L{ze0am|5;g5;@c<`r%!;{ z%91{e$`6o~CpGLdIP13QYfFANOd26so9n5?){vtuhr8yP!Q<$`kyoJY?8W6~8Yxe1 z;AhP!Xtx;kbr6Q{ae;a_)ZNaliBABF2b0T;fyNdSjV&q7|4bp;-7ACau#1sggiex2 zlb=UNlY|~Ry!2fKtGSlrqVZ#Lc`Yq(DZvge#f~Fk{e$(?y2e|!`Xy3JF9nLaH&Q6| zX!XmHXSF*d+ytBG0WIV|aO`<2Saw}Sd8Rk%3f5wisW!2jyXg3X9*VFL$rfN&WHZG=G@gKaE>IR8j?uU*;yE@Avhk%?SbkEBs2mU1Ah z6gCCvLmcBu)#vY)4+Cl#@B`B(Bc)N8DO5Rl>GvYL>sJh)kmhTBrotn_QAt-VHmZ%) zBpN#*Ow3VaPnQ#sQpOsMQzayfb&b(TWm{IJf5ynWsKOPD=2P$7?z_T>F1Qib0#xtBulFe+;T7B{Mlg2 z;h+_D{gl~LR0Ka^IitaU4d!b0Cq+Ad)6q^-KD*L0r?Z%kXunWTy*XFG_Kpj|%T|Fk zK+l`2V8_AE&4(Kb<5d}^^!E_sc7`M$)HAdbc!6w8bhyg;`jL&m?X0`3fyZYaqUgJ) z=NDIV6#)(}i(sx{4R?>vJUSH_N$jJ|vYB(q&_DFHWV{@ayx816yZW@mRMUMrUy)f; zN1E!iB&flwsxZvI5g?~3#Y#DB2t;K!B_kO`i?7v2g1R+9Zcx8U!ymM zz3JdsLT$_Rrx7*{2ha-q#_%~+(di=uT# zJ%bmWw7Mmag8h!vY_Xz?{NC>=0I>`#p5Yb_-n5 zFD!#Ql>HX*m6K8T**L`wtFq)a3xBS^)3R4#7)g|(j5R{Hn3DyjZ}H*|{* zV1*4AbsND57oA-XmdNg4XDpGU_+0T;UJG|lWaI&3Qz3462^p3j1-#UcJ&X#J813u< zX_DFJJ+V8;CuKu+Q+J6pwCYx#DurL>Ct;e@!XvX*21`DF{BDpWBmdIbAkf6KxQa_6 zM=+q^N6$xx(lejFpOa0?AHVZD8|NdVxHZBBZW$Z<=U{2K{fwoele;gpP^r+9J!fE% z@c(?0raW8Qwf&Gq#E{o`rc4iRE|W*Z@G7s%b&r$UwMcHKzN(XFu)3FSomg$K`aY}k z)5AwnLUir?*B)AfcIBAI8uZBvnD&?buo<_9ub_SOE2@PW-?tC9I`H_Vzj34z_Q70<@PD`hnbgTT=Z}>dgIq z(^<)6>P<3AJg5vpW?A?B63hd9P5Z(;LrZ7-q-1HL5q+O%Q_1I9>5Aj)DeN}zx&^A+ zDc{Q8S#%hpUNUMs$W+-3q8o2t5{(w@#hT0}YZiCnLrgQD}(dE%Ek zWFO(}*W@w+)=`eC8#OHxWi+drL|1*|Q86ikb%B=+WDLC-R9cOEDAkVUCMl|1;kie( zT4(WWlp1f#q!^T51-&CFHCruFF~OiGl_?IF3D@HbMaBLoZEFq7@lB>|_&rPN2GQfh zFC(=%=4SmPF%)=aU!Rhw?$oSU1romh%N+eAFCoHd(?>VHv1)d_67w{ z2##IJ@itkA3GGT)*^gF~DL4rfq6jzcUzk$nc&@+Y{#j*^J@bk`#Az#soXeg^LdCeWRd5HM^^~DjD>Y%PS3r#T$gBWy=r&i;_DvO}+H-(-rxB0ImZLGC!whU}-Qm3*z zF37r_V5g_v=O%4-YLT{xKThZrx^jcRk9$zN<<4Fwz$|%q5GgI{5LkzO;%<2S^@hZ^ zRqA$;cL*b+{~DSR5d%i)$-!Im{wonT_}Pvru^4A()|j-mQ}lyZT8K!xA+TN>RgS(J z%nXR`ci7zRsML?ho>s$p)qjBHw@HQ~F{OoaWG76YEP)p;pN_=*LOVlL6K7q<`hH*+ zwoET(#=^uxwab>NCJv2XH@_iP8*e}ST|`u@-FoaNp*KlgTU33F=f&3IKbBr`1)l~Q zQz@159)-j!4oEpipe;rxhlI)?4rxj)HwaD6EzK{xoq8bh3l{P)j#b0PG{nX+j}QCB zQ4GcOVvj1KTnQg-* zO;;{Y_>qSz8G9-w<(R;zB#Kn*jBT$z*NG34{@dn`OTX(e1*TP4WVnN^p0uyE_4TPk z*6G~IksG_LHHa8dJwf|wDwnI*63_VK<@4K{n8cQgYKUj~$29wcdb`}4rYwKjFO$;0 z%nd$%l^5mkN$U9oN#l3R^q*bs&yH*?iGw;q^4bU2chcRfX=?ef6=LGASa0{ai=8Qc zwy#=G$-K(FXO)`hv25)K?O3N`dMwNE5jXy;0US#k`z~9du z1be{#e(vC3_Ivy<_Z9u0pR@3fhYX_X{Jsq(4fx|9Q0$)%hWKYc(Dx4&|3~}D{++$< z|I`x}ERJyoM$-dpS_l6Z_5CmRsQn+G_3)>v&|p0b+TU04uQvTJ_NV=yp5yV43L;qi zeFgv0FaPEKwEv?sIsQ>K{H~4R# zHS(WyPXW500+Sd2Z|eU4Vo&1#FXzMjrwS~BwSpv|0_T6f0)Oq}|Kik+-;4iuef(eK zg7onJ=;JV;k6(e$s_OqmUH{Gg;(z1Zls`=iRE4Z7hFAUjs{XZ4|C_y^|D9d`t20gh zR2F=A;dA|cMgP@)(*Jli%s)N{G2{2={MNGI1O6AVGJqBPc<%38^pL%9CBBw#|4jLr zBE#Nj#!W+olN^NP7%=f@RUQfpTI8_(t?=h;B!bUx#Dp()ibE=#rkqCaI+)C%hc|8bLY<=j`I3#lrHcNMTV~wYJ6-V%v*t90 zkQ*t+_6gN`MIyZDhUO^$PhXhUm&4wnqfL?D@~T+T1(`oobD5@pZmvw*dr+5C67M69 zFRS|A-&W+?X4y%8gJeS$-F{SZRZSJt)Fi3$w&`?dC5^S^6G3s=`;Rs8>eWZ^+BsOe z22m5rGb3g9pZl{VGf6qGsR-V9gq_KZUUf0&2s7FkDyex)pWLn9KaI#ABIh#PTPUun zdHq3m)3QJ^ZJ$R$WJQrY)j#LCPkx4X+h}tQ%A6q*W>bas3usX;^|JyPZAIwxKC&}W zQu=lhRfKg&X)om%Y`_mfZX-4m(KY zZoIsaujUf1SVM3dH6I;%Q^dLb>IY_X@SLKKCtWU2nMecs;~}P4S1vh1p|Ve(XPZr4 zZ6#M7^&`Q%ry|->N3F=}IT{WMgw;l%i-!p+|4jQLP5DgG#^`6LRSor{=%&>+LtF&P z?XrLdc&i$`?tJSn(wsq~5|~Zm5%|hY8$*s`;DgT^(JXf3BjbcE*$ zYh!bjZz2(_>@gd4Rwg#<2b_xTys-oy&4WEq94+GdWzbn29&&XvksGV-))f@l1ZN01T92OJ#c zNDb(p>EiHk_J?dDPqZ0o#u`_#@K!^rQv#vtje0J!!lftF+NKUhYPZ#5and_?@iZ}{Arn-V;&INr z2{baq2JAOIRRK-n+UDEX3z)&ohYw&^PabIGKBW0d-O3(9oGr=c;1X(w8xX0Uo8H*e zxUOpGi7S1KLC3pNt-ZU*yJRDK!mti5aSgODsh=(FQ9N~Ps(i8?y`J>+NO;ha zmMbvc#M&4Mh|-+lpR57mkFx3tj#Xhyeyg* z8`~tW?1Fu2N0Xq3f-Ps7K$TUd%8(-^9S-+SR1|0Og%7<2jwSO?^o;)VU1(SCZWZKQ zo+7$7>8cF>VHD*xjjVp-ntpOR#z6^z2>Ld8-8G5A502#J&-v#|u%oCc`tBP7B`>^M zo_lc=vv+E(MRV-uKaE%C308ZeCsj%kNVI5L6s(`G8r#s{##%AXqRx`PZ<&xb=6GXQ zGgWjXe$!4$&hY_X&u1N$VYj{n_iWsJOKKp{)hyw&UzeJ`)4Ez%???LXOp64rY`%cz zQT&$Yhe=&(^UmvPIat1x`Oe?H-yYc`&_5&KV`nq=ybm>v*-- zod#JWV!ndbmI*qQ7(V`}r}S&V*kGr#^^vMR?b3c4j8VV2pgL5ku?>%e7o_jXk95@6 zs)W=`n@V_mS2Gp!pm0j_tUkUx`{4S)4da&0lZNOFO{lxyZe?yxbRcvJfBjWAal2<^ zBehXGD$&fF`OuevEs8p|#De7kIz88)GT;Qu_YIJ}^!b$-F`117%ds-rC%SdBr9?BQ z&qKG4o18PJYbWtDiiE#epigfIU>-*~1`ymBi!@jK{JPk~D(*`>BL>GEl@MVWvPi+y zvq;_QsqPiBi2ap~3k~bU=uzkH9fHH$aT1^Im2=1X_y$f=>uc;J!AG$HX zwrsRvddNkfuYxS)WGB{~ydgVdo>pWv>Jj=qr<*MVk_eyt@d+FFLv{9x!`yb-jMp1B zYkpke_P4T{W_IT8%U|%J)tZvF$O&9^phwLM^$FS?4?;oNzC?if@nAD*OXAyTct%T; zWLHyIC+sq9!$V?v^xXABdgf^1?tFtZGVRdERmHJ7E2@1c>Vo2GeR!$#hgd@~4>}Xx z*evxgH`tr9sGsG-lug3Hh5GUrg?q%Ima5jnI4cR|g#WDjoRBPG9k|RL5wE{IDt$+k zCTS)0RJoptsPA6qz2tLpqT-z=oe4Po^q=NrX%Z8YRO3bRSIgNFV&5+-K6k`_+4%mW zWcl+C@vCHAQ%boSP6@HP7@|9+W8}K|R2#w;urHqIb*epgBn=3j+N=d(Tmhq!Rwuk= z%CTxlHXkI*H|VJwp+rYia>W{-%h)1hZTFSHn|DlI#4sU`G9_<{z89}= zrUB2uxaVBT+2*MwGGL@)-YA$SR8Wm8X5RPYQ2$4?y9C)oZQjz#f@-weI&%G;FE&iC z!rgDxX_W>ki4DRs{GVggMm`DNa;mU2TvLgIr8Mq0kD+JBk|caujX$?8X$Hez}_B{PvsG}~sGL117&-4ZzpX#Cc z7lgZLPDuF|%zkGw%ba!9$VIymXi|4+Hf-)Qsu?X%)yeHCLe%b4DUmSbV#l?{NA2VY z*I}=FDu*QKz&}}DmQNF`#~b`66DF#~HK#fHj(}wjfu);Kn?CrPXIo{BT-&qAV)x8$ zK{kt2Mkb5M=9!e#jtUB#tKxO5H1*gr#c`9omk;qBCa&~gGlcnFCUBD12ZjBof)%Oo zrLl?ijZeu>u$;P614^R?Jqp<5CL#=Pr)^53tV7z^!>rMCdckp;2TX;T`4f^oj#s5) zO8B$3l2mNCRkpopSQZE`~hL3Flc z>`+&OqEH~fRWX;#36$$2Y@r&F2q9GRnmD5Lb{A^LCgEwa!qRmjReKQpGhZz>a6fyA z7C(WGE|f1OF6m2p^ytk*&MSK=2U-MqWQqCWf7s1J!FoZ zx^Kfmw}`981f<$5^|5~jdA}H(t1axF!(6jnh($IRU*s$buYlDnZ)$nhF3~dP72dJW zO^CK4oQ)yfM$dyAq?9#E4x`(?W{(u)EBY8`SClzaj1>VlhfPZEpx$1K#NRJ#RLNhj zE8hW0(qA+aXV-{1N{kg3_sajJ-5NH}33ZpZM1^dF9QqsB%6qAbdWT|?D|Dka+L?S^ z`e1M04`{bV)sBQoJ=vM$=VHC5#I{0#MCdJP$^9z|BTiYWt*=n1kJ_t{yL`AGp+r&e zx?@dsqzpQd;kI_>9MI4PE@h;T#^ost@ZfqA!DN!R^IhV4qZ?(?&NN@(&ZAZ8IHN2K z6&{3R-eY&ncNQKDU|yqilr5^bBX+euuQ)$?@(I<*fO6&_Leyhc zfveF@^e90S8x>+gRDtK}op}beY(k>+}20Q8Uw|FKJH%D69SW!|o2VSZJ>PMs% zM92b*udd%#>|t2i7+BZd^1gA^vN2eB<(XV_tGchFP`{Uy_0^qjidW?EcvIJH^;dg-v<$ z*`4S*1tC5gDOyGHvz!#hI~(h3Z1dS9!o5~K>vP`HxipHYCugn;>#y9{EYAz7Cx6}+ zag<2*s=8s;HM6SUzX)zAz9(07IK7u4y0bU(RC!#6zTJytFR(B#Y#_KwGb43zRzTfV zM>F%lOUDVi%av+I>awnYxC-n_8$Hdeg##1EW2f+si4s>Y6sXyRP8T9Mgrp_uEr%^j z!u!^88TwJ06+Y5Uphb)61=vd+Es&Qq+gd(_ZwyI!{T)sJ>w+b!zU1heqDNO-&i+Z3 zD?LdGNviKi`PjWC8kA=}v#-k290pVcY*W6qym>3gEhuQ>sva?@Qf29?E^!a83~E-9Q%poi1NIR0`rH6VNzI2`mz^_qqO)P zLt8Lc0ebjH+N{cHT9>fm{s;ySqKP%X1#`aZj?Ao@_JMC_HePeKb~-cjchQ*;Yku>+F>5fh#~y# zYfuwNW7*u9D8py?RQSqoa(SdRFLQW?v>t|QHnjD6Ynq+6*VTBvzLo+biIMm%x z>kQP#BnqWbMKjvC)bWdJ3tltUdLcBaG(6%mwiXg{Omo%b-md6`(G5ghhz=4;nn6ch z5M6YGyWpQjN4{856#@--Q9PE9x{pDlPdLhW}iDZ8yvh zJBmr{-EdtTMk8N5c>gz{)^8+`jr8D}BLEN@3BX;mPalK{TDW)P&IPr`P9B7L19rYG z*popkKUnBu$y2DsIB?FjM=;M6*$Z?VeOcf;uKC3#xO+B1e!lE&l(oQCS1HN7t$#b{ z=CqmhtVk665*5uCpWfgbWlp@lCd#a55xz0=f0I5kn?!bI>OVKM!Ss#+>1kO-@PJM> ziqQhqOpES3ik;XlAKW!UQvGL7Oxcyp>xNHw=pyqd_mfW=gr3+1Dv;R)c3!(F)&9pWV%s9q&^L8YazZdM9~zW~+3C2Kt4{@Ew-7m2uEr(-AR$ z@>{RgAWqG=EtL4iNNc*3!9p%~b-;pdx@2vd%?9l~SjhOJm-@X_#r?VpzU?aZ@bnX% zArLl1T|+gaa1n3wpwb5Ej5V`rkE~9hgLFv+zXvtI2Xj|R(3DSfHxTanNoG|#c^yNC zcTeFf3}Vx8X9Vxz!d;1H{byr#7bC@VX>rL_rap&LK^@at7ReO|L&k>&FS_rhPrBw# zNirH{zgMxcuiJj;?rN>@I^?`ksYOQ)e$?u|=P-U(I;!UnN_cK!-e;A)oSBM z-xQGBIkmT%u>>VEeT|V>#s(gVMn$isyTKwa#yiwm=DBr}bLUalE&Y#s1~j4B&(Gga z)a5>wnbq4g!@m!-=~a1e^H6wJujK1ld2H8Qexv;GWNaOVknGBQR8333_U5aZv(L$z zOQR#p&J8BXB1CsCMz@Tg>9VAAeHZLctC5DPrH7919sZzt-8n|lV@BoUn@1X4;iLTF zll(p-Q$x$jv)UFZWleWUPb2B)4RuhNrtPl$+G3kg>o#ruZ)4hGbqsO5%b9Oz?;LIO zKcbeN5PQqFzSprSU4ynNO+!l>cI(VAoR2Z52tX=;HGM8yN)Od{CEufUTPxV3pYZAV~BqPg+(Jk+gk<;%p*Nmt&ygj&Y47)mo1%q=PW zBjT2ejI+-rI&F5Ua!quOdCeYp%H@(0ZT*kwPvaH(D6eY|MMVf}?9mc(l+x0vocHsE z@R<}i-7eKDUNoo>+}j#!e6J)S*foH!L)2`DPhik`9Zz0g;pnORUN-~5wT#O+I%yC# zuq!5L%#Khz4Bk~;X*q8llS?z(rjntvx}tT{*ypj)n#6AZbA}qGj?rg7UH9{*$9GIk zT>EzU=kc}iGi&`1emc`^*jB+FS+C~X&=s@?~M166Me~Z_>n6!yuySc@ ztVoYDSaG!3l=Nx(bvk2JkmM%!RaG%4N?7D%6QaTb9{qgwVKzm(J}pb|bNJ8ouPG|~ z$O^$fZU}it8`h2hy^!6#IsjXW;`p*VFg;^lk<;SXQ_FdphR1LAMg`2 zzq%+fl5cF&N$dF8+JgvL=lS)0o&sr;ch>oc=C~jC=23=!oOvV!;Af^zd@gN^j}@p( zQl?aTmKwdAAHS-{??OX%JLb;0LQn+iY@7#6eQ6 z&aGs3gh5i?7vB=LspkDc802A`*g z#l(vxV=q#7*n?%99zZvJb$Rf*{jQ5<=>O^KETF3BzQ0dgy1Prdkw&_uk?t$qAdNIA zf|NAU4Jw_|T)HkuN~d&}bi9|}gO9HN<9ZJZX3uB7XU?2G!yQ;>?Y-T|07fbSTLy9K zOo3CzfYde~>r%B))-j_OONynsE|G69UI0?Ncx+2aD9>bq2G>(~2*AGE#0urmrP3~u zA?qNwDhKo+gYfkfs9L9P z8`Bez<1TGA&xu?b1uiJ2=b7$ANATuy@@C8RDAMlA4(<1r3x<79hnI`UTuiWXtb41K z*0?_>(NKk~WKm1%PQMqOD`*`e?lBr=HQ%RXqCWZs$DSbR?wI$MW}fKHoE0x|FSxNp zP(`q@3eMfK=zF?Qk)X<^7ifD3WoZBO$^7f(Ikyl8I#Oi0YV?v8EcR6I~O#DKi z3|ruO>5xb2g^)s1IAgfi%pqP@sb^T-xcny0OY33Z*F&#VUdG_4 zTuxi`(sPUv$I5e2VtuqUG=zs051f@FctVMZtK$F&BF>`ygy%JgkBB_ig$AfmAx5mc z;gjWHcy+#rgNi&C$3Zy0tkISQ3hQj6EZ%O*(%9ZR%Zd{ca_B_t&6in)emf0&xJIOF z>K9s*C5n&rMa9zHK#HM!G^H@mocQ(6P|U%rkgk}cqbv~%A%^mqH2PGbRcgZexxczy$VLVzIU7YkYIA@m17Hixx7v1rP>BB0Y=&z`+iJV`HY&x%BtAgA3 zpW21^tzRoD;@C6Yzh!cLIw7X0C7#zG9Xrv>Myp_M4jrc^md`@3re&>GiM)IvYcF4J zpN4Jst)C&zg*?H9{dF`(H**`}Rr=scbUt7wH*=cBLXX?!2{T5ejP-W5eVQH^9Z!>I zJa@7|o4w4*qC3d@=~|&%VFRPR4ip;Qm=nWhN>hC$@?gahJGK=UazZFcd{9cadGCy| z?7@@G6MHND*kZojO<2JE+`HPfUazqzzwj*mso`2~-GkW?3M^Lzl9@!tqM0ZW2}l^B zm40RM{mcju+cg`_ejo`>MQK2EvxWQGRs5sSIm~LLLW)~E+pR~CgJ~T4U}zB2doi4n z&<39~tT$0oen9T={W)gxR3F;ltl8<+p0&XlRXscrM;OmCL$NF}mE^G`e%hFMG~rpG z|N8P_DbUDwCBC%R%LKtsadEcZ&kbp+_ zdX?>Fc2Z>Ec?h`#PO^vnPSjZAQ1F6V>AvATb>9p+kvG?r?xJn(%Mj~TVe7q8&|W_p$t6ZRf7rdf zA)m*O?x>rC83#|5)@(sO_tkr-+I7jGy|zfQON{BaI~%aCupTHOM0Nk&kwKYQ@OTy- z_u?lkT%Bd?RLp%>XGL!6{mN`KjUu^nHQ1**yyTfnOvqG<(Ygq|F7V!LW14KTZ(ZAh zlU~nnQ}Fx5n?(K3DcV)Ux(+7ZT=ltSCCddLK9kA%gOw~@!f1!QGZO2sbuPJ?H%2*o z7w!jaU9}hT8;|cyj}{8S{$P_fdTVOH=4nbmXxo_QE@>7TpW%?bKj)L8V1I z!kMu3Y)QMH@jY59+Jb7B2(!sp!s=^`1^LINHQZBi>l24R5+$&~MVGy!C@6|Wi2{oa zUQ-Qv_DZ+B>l4Ki9WeX%k~yLl&?l%Ugu7X@{4e;RFPH}aR!kCOfo%hUNYU@1`}$|I ze2lq7mu*Y*d3f@-j+YXg))B(_nX8_SG24N7PvSh#Fv~%sD{WMiNUS-tLYeLSD|B%EZJbF063{9H|U`4hd)mhD8c`2GKVO&~%}+tUx(H$ru1DR;QoXKZM!@Uw?|I zpZGpvC;YRbuC2IZA_{*~&%FsumyISX5|Q75^q4;8mgJWz9Iw#o z960(P#fpE=z&fQ$Ei*1pM7~)n=L^gXlt(3{_pKMHXhup400EI+F-$H1UY=!w7f0r6NU;D!c=6;2>xZ-nlZ{k?4f}O?r))htHc9$XcxR;lSa_!r5|Bnl`SQup z)1mOr)Kh}@W1NjqB4oJf+AWCz+|Vhy-YRlMKZ_sI#9UW~;U44N7w(ic$*t z(!m}ueHF1RPaD0dfG~eXG^8KI3t#xgxmmtaFykepf_uuk;b&lR9w7j)zO&1gZ4-w z4CLI&O%7bHZf1T#?1fju69GcB0bKF7#BT@)0{gl2p7vfD0hdPSclFgBxRHq{Bv1|9 z3rci6XG$n>lq!pHc)n@ zYY9$=E_bQ9<$*-(a=33HoUq8Bxf2I9@WZxJ31gs%!_QjAJ>_DXNqIV*7h;UgX%S1+ zwp(we$cMo6h7ifP)ZH!d5;Om2q9~QHRM8#&V27?%ZpHOQOx3Omz_gS&oUc@L6Mr>V ztzapUjiXlTdxrX%4XQwBOQC3YbOXF(r?z!+H%yQ9ZdNW3<+!plsC2;ft}fE*71@ql zqfNCX;L_CT$xl36s$Hi1{OXJ&Ry;`l43zK%xfQ&P=}$>sQ(tHzy8;Y3@WkszW5Eh=kCJ0k22>AOPU3~2HB$)ViV z&|*kBsEK|3JCp=*z6yA4k5gVCKxhIVihG}tC zIM3KvTr@lSlGREl3pQ)y7H7WQ+-4ktfdZ$)YF10HgoIA`+75@ek+pLz+EK5QTi;t= zf*12zx4?_5T##eIKhoz>o2$g}XxH!#hk=8P=(pyn6!6TZC&yk|e&Bv~qHlu3YQs_4 z{Z33`k$eLZ&P#=O{>_Er=w#O!$KxH0(v9=Sb4nEUptfQI-K@Grhdx zYo%h(1|*o=Rhp_}AUVp4NF-}3xaBEQWt;+K^5U!bV0jw+6V?k{JKVO%k#TG)L>Ino zzr4^L{m_s}+l76h+x{Y+O5VRUQ?tas?U;tyKXME&gF-2Hd-VP4EqI|8_J3^(own@mrX^IIYv{?r#rhUWEeKc8EFcHUkx8J8>L{CVec z5CLZjb79d8YS9&4^o=R+6CQd#c)Y`0;Su&{NbFc0b&C#!!mV9IG8lqHAGR#h-)hep2J_9s-sKtN5`Tn-6COFy znWVWgeUoDBxBC;N(8(^HQtTi@Z411X8q0>CS8Fy4A3+MoDE^f1XVY8Dk~uE$?ME3l z;A!37)Tvl}WT}F)-Aol2Qks^0nS4Q@ZNyyz8Wqg>^Mn zWmK{kn{(|Aw*J6%OrlD)-hS`ePW{E)`f)SfASO8o`iz4lsA^t5iW;U2WZ*0Rk=sXY z1+fXHb?6KC6HwnA#1#GZg_~}Q@xeT~Vr2b^c%$I}FbWj-iR&frMa&23_jO!eJ1Bi9 z62v@DRg2Izv?Q~XU=q3~SI$-6=8@0WX(Ux%RoCXR24RrMym}{(e2R!h=G&i`S7~`p z9&2iZ9@_BRe1l5Z9@@k=!u38LS#<5jSC6&cU8b$+1sQ@iSiu{`h|e4ej$fm=JY!}HY7YLU|8Y$B1)@7v=2xT8 zpIEylB97`*ypfRAt80dQY9VCzpZ9h9c5A+!5&?3h=KecTYVtm*DUMx3L&KW)k&@*pD5c#+!opb1JC3%6LD~`@T$8QJ19AxZMs+3%Xbe)&yF>{UmMK4XmSgsZ zs{rEc`WlS(-y>8kV(-dBWC!+(t9O}0t(pey{h|_y1EO1ebN*qSpPX+96o&lR76&&u zmnAjYoO5lw+-sz#5z^y*aid0MMne$z<9$(KDCj{vKK&v{6)IS}dLrhTfm4=l{UW`E zyC<0UFl{28g}eBn^YZ087xBTD6KnQ>YsivHnb@v-km0w&-6Bi{kN2YOkYyKIwlTvM zl8g9x)7)L7^uQ0tjE&!9rf;v%NK~Y!Wryt97H5Ykmyx&w_rQ}HyL4kXvZ4Y)PG-r6 zF;7oJYQ@)|4iI>(9!s}o&Kk5_zYzH%Q&u_8aY=a;I`BhLD-LdEzkht@&NJ49qV&`y z)suz*&WTE|*IjItq)2hny&1u?h>OHYe;8JLAS^udx%0TBm8%2S)g1<0d8qu`P_7Z17`z+csF`NO7sc;S!`3A9yvS3aK z8+C!tQ${AaP`}8jB>Rn7l(w9KR{JvQ0gb^$Wy0Zh?Ma*MU!4-D@reJSp6Rnv#s{F6fi`=F^8O&gbhpGcWXLtCm4=FUW4ViH#K?z`Dr_ zuFq%7r4{O@=$={2PaK*Pp6gtUY+f~4(^A8$>s-;)L2U|dKN+Cz-8I)$zn|I$k=bd2 zH(l>$IMA5L_dLqU8kf)g$M>j`X+?h)4x1DfA6DiXaEpF2*2yq-MP4=MHA4zGDs!O6 z`txe}D<*~P9bNpSu}Q%ZWcq{=QE7?gqjdf%_X1-HO%9japIv-dsOGay^!JRe;)tx* zHq1}?N;FrpE@jt=Nc#{|TCGr0Jfx;S5%5_V5#qoLiq^v5#3ONwPoH%b00XA`04eEq z2$QEM9D>QJGUa8?O07^_aY)=;)5@h=1TQT(11;!gyLfJ4z>0LkV6!qOrB)7d6GytK z$$ETXfE=WIydB@<6iOVWJ7?SeGO@QYQ>QXDWMx;79UL%~3|ZNoY(lBBr!Y^>O+ELO z12?`>TH(+ncnX3v!mO$W8FfDtWDRcCk2%RV{pjNlo{pX-jU^!S?wY3% zTv+MaFBG*X*67fY)62PRbCR={y1xUceW>5C_zr6J0>ru2xM<35df#=H1)o+%RpIP&E{nYVgcKi`P~?8D zX+t3zLqAWet=aMhzW$Y&W`^4NJ@nU{`Iv`@0Z7Oq!b7fS$o78?0NoG$>Ysi3EXbAt z@(qc>_}}4&{M!GY1}_cCeeLa;HmH5=hb@aMf@B7V9mzw$qczW+FDAjwQwtwAEL~Mm z@stwV){zRp%P2pEsPLuPy5@X`i6Y;RD?-B|kKuAj?L+CZ9si+fV&-4k}K zNJ4VrxzdCaa!3z;uhJNBGXlQPZQFs->y{^-P!I2dwyWqc?fVrXfhP@qrgMT(cIIc{c!Xtrv1IJIK4Ia+lk~? zTl6io?dUB00k1l{9Usg#CKy+B!Rxo33N`?JF0^&r;oTg-$E7DCxa3MgZ{S0(rW~qt<2zRwmYr z>1cVQ>#Q!UaZ0p~C1zT&wr{n&Ou?d3uIXy0@WHQ9a-@fYNJ9dR@(~zRcGJ$qF6&5N zb6_(RtCmR=;)XHh!B(v7Sa$IZ6qUV9Q&%5ia@EVmK^}y;3@xn6GXSj7aIQ~9c9P)* z?e2AMH^{xT;-<-QWlh$xf4j*aJDo3tk&TLqOTI#@=kqe5vX~N)naV+$ae!uwZ*s7> zKC!OSrk~Mtt`GMKD2LUmqyI=C%ZZST>ww#xiKH&YU?4B9Xqu#tw$2+F|6OpfS-&DZ zC$sG&je^xkyhx^mQScDoYs{E>P8o{l`=~#NKQzPH3Q9XKu$0J^LJLc@BSbC9;CUEX zXCTk7IrVYiJqF~ zJ*9R$*tb}ll?2afJTpaRWj2G6j*i5+u2&lzW#9Sis)n)1JgXlAB0tqJmtCwXlGdut z4~2_i3aP!@O!01XsDpy?3jr5fhsux53*EG5e#!DkbHt=JKI_WY);6 zOt`Tl%~?765*pjRs#faRbrLAZgG^>jxawAhR0`Q-!RvT>TJ`wxo23%|u<6nuWnMUz zrKyB#LY=iat-kh(!{Lu8jjF}YBJ#TIjn=#0JFs2j3U4{VJEy|80o%PZADTMf^HS*x z=C@tG=UZM!yk$wk32Y(C!UE8vr@jEpi}gw%_Q12q8c%kvn2O=IV`)NPC-}k6{E$9A z-(MVX%{nkwL4Cg>ZFsION|r6|g=R!v$Q9bo-+z;Oir#fx4iI?v}(Q(U(<{(RjtE@ZV{H3>rdRbh4&d#tpl)C?Xjv> zECjQ=%ye86w}@SvKD;3H;_(AWDzvx?FEyoiHp0 zVp>$OBnN#^%spJIjMyUWe&RQI)J$WwaWvE@R^<97_HctPe=BjDNYx?N|GCE|_34KZ zqFbC(74du2lq%2l;jhCdO9W!3o+P&}yC-bLiP`DG_7UfsBAOhfD_cvtu)Y)*C`$;= zcalr&BdxK{z#o@r&vN}yK2R*{{}A-k%GpjUCrjx`Uz^406ss=O5e~-{lxF!tXSECH z+9aSkr#Pk0?8HZZgb=frJw~kXHM?Hn27dUqWAuYZ!lo5cuPoJj8N0 z)!2|cySCN%OmkxSxH7DxtoB|xO&rZ@zV5=j^U`b%&8To{;%p#zY=>@uvtdya-d~7+ z&%yR3=bKQ4G|Ne6l(MZ!xP+W#70V)r24FQjp9Jqm&%os;51Rd$t<8|X!g`zm)U^vFf=}Miz;c>tBx<8z?K85>(GqVhsz3*Dj zmKjs7^Ow_eZc)^aMmqm_!+1f$>0uy2Z4X(nb)YaF5@thcF04XLLbfLVXW#Ds?7Ig* zJ$(JE_k@CE3xMonL7hTvBGom48Ys*6YL5P9L32QJK#EkTt4X3EL%}L)$tf#JXhCW% z4Bb4|S)hd2bC7HJ)hHnbZ7fyp~MfliiZYcCM6^FaLxzYQ&G;$<S4tsRh1sz@sI|qAt58K_-I=xYs&r7_^AK3 zqa~F8<$1D_s=v-zCn2Q@@y$bn1Rclru4VRNc=Q__NJ``RufF3-|IQ0;^SRuwdjWT&C8_bKfyb255SRGp{O~jn z+lTb@|Lp(!6Z$uUhSUi8zm56g7x}GYN&5>c{|kGl|M9=}yDw+nUs&;f8JFjO8UNe= zGU3Pj0|od!hS}r%p%DIHFCY6N{=r^7GNeCPz#~KcgGE2GKm2Ew^%wS+`I=4rMYr@{ zX8sHPF@{yvFZlafY<|t{51rlce|3=DF^}zcU;DrK*?#H2I)}$+^3UhR+3LSK=U@JV z`8|enz@rZK5BAG{fB4=x>rwZI@14sZ*&n`l20b#AKhF1SzNmk&rAHmwAMEgvq5o!& zA3KoG)IS*JqwbGq$c6HeJ(S>h{GD+HKQj2=%-!da{qd}MvOKas?$PUCeg9xlp8wTF z1^k7D{+A`i|CjZ2{)PQz+@A5j=>B~d{GMCS>VI{;zkC(&TQ_9zp!+8l9cb@n=V}df Lb#r!LbGQC~V>qmw literal 0 HcmV?d00001 diff --git a/matlab/m_basic_function/packet_handler/clearMultiTurn.m b/matlab/m_basic_function/packet_handler/clearMultiTurn.m new file mode 100644 index 00000000..f7b63a8d --- /dev/null +++ b/matlab/m_basic_function/packet_handler/clearMultiTurn.m @@ -0,0 +1,36 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% Copyright 2018 ROBOTIS CO., LTD. +% +% Licensed under the Apache License, Version 2.0 (the "License"); +% you may not use this file except in compliance with the License. +% You may obtain a copy of the License at +% +% http://www.apache.org/licenses/LICENSE-2.0 +% +% Unless required by applicable law or agreed to in writing, software +% distributed under the License is distributed on an "AS IS" BASIS, +% WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +% See the License for the specific language governing permissions and +% limitations under the License. +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% Author: Ki Jong Gil (Gilbert) + +function [] = clearMultiTurn( port_num, protocol_version, id ) + +lib_name = ''; + +if strcmp(computer, 'PCWIN') + lib_name = 'dxl_x86_c'; +elseif strcmp(computer, 'PCWIN64') + lib_name = 'dxl_x64_c'; +elseif strcmp(computer, 'GLNX86') + lib_name = 'libdxl_x86_c'; +elseif strcmp(computer, 'GLNXA64') + lib_name = 'libdxl_x64_c'; +elseif strcmp(computer, 'MACI64') + lib_name = 'libdxl_mac_c'; +end + +calllib(lib_name, 'clearMultiTurn', port_num, protocol_version, id); +end diff --git a/matlab/protocol2.0/clear_multi_turn.m b/matlab/protocol2.0/clear_multi_turn.m new file mode 100644 index 00000000..3390a679 --- /dev/null +++ b/matlab/protocol2.0/clear_multi_turn.m @@ -0,0 +1,305 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% Copyright 2017 ROBOTIS CO., LTD. +% +% Licensed under the Apache License, Version 2.0 (the "License"); +% you may not use this file except in compliance with the License. +% You may obtain a copy of the License at +% +% http://www.apache.org/licenses/LICENSE-2.0 +% +% Unless required by applicable law or agreed to in writing, software +% distributed under the License is distributed on an "AS IS" BASIS, +% WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +% See the License for the specific language governing permissions and +% limitations under the License. +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% Author: Ki Jong Gil (Gilbert) + +% +% ********* Clear Multi-Turn Example ********* +% +% +% Available Dynamixel model on this example : Dynamixel X-series (firmware v42 or above) +% This example is designed for using a Dynamixel XM430-W350-R, and an U2D2. +% To use another Dynamixel model, such as MX series, see their details in E-Manual(emanual.robotis.com) and edit below "#define"d variables yourself. +% Be sure that Dynamixel properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +% + +clc; +clear all; + +lib_name = ''; + +if strcmp(computer, 'PCWIN') + lib_name = 'dxl_x86_c'; +elseif strcmp(computer, 'PCWIN64') + lib_name = 'dxl_x64_c'; +elseif strcmp(computer, 'GLNX86') + lib_name = 'libdxl_x86_c'; +elseif strcmp(computer, 'GLNXA64') + lib_name = 'libdxl_x64_c'; +elseif strcmp(computer, 'MACI64') + lib_name = 'libdxl_mac_c'; +end + +% Load Libraries +if ~libisloaded(lib_name) + [notfound, warnings] = loadlibrary(lib_name, 'dynamixel_sdk.h', 'addheader', 'port_handler.h', 'addheader', 'packet_handler.h'); +end + +% Control table address +ADDR_OPERATING_MODE = 11; % Control table address is different in Dynamixel model +ADDR_TORQUE_ENABLE = 64; +ADDR_GOAL_POSITION = 116; +ADDR_PRESENT_POSITION = 132; + +% Protocol version +PROTOCOL_VERSION = 2.0; % See which protocol version is used in the Dynamixel + +% Default setting +DXL_ID = 1; % Dynamixel ID: 1 +BAUDRATE = 57600; +DEVICENAME = 'COM1'; % Check which port is being used on your controller + % ex) Windows: 'COM1' Linux: '/dev/ttyUSB0' Mac: '/dev/tty.usbserial-*' + +TORQUE_ENABLE = 1; % Value for enabling the torque +TORQUE_DISABLE = 0; % Value for disabling the torque +MAX_POSITION_VALUE = 1048575; +DXL_MOVING_STATUS_THRESHOLD = 20; % Dynamixel moving status threshold +EXT_POSITION_CONTROL_MODE = 4; % Value for extended position control mode (operating mode) + +ESC_CHARACTER = 'e'; % Key for escaping loop +SPACE_ASCII_VALUE = ' '; + +COMM_SUCCESS = 0; % Communication Success result value +COMM_TX_FAIL = -1001; % Communication Tx Failed + +% Initialize PortHandler Structs +% Set the port path +% Get methods and members of PortHandlerLinux or PortHandlerWindows +port_num = portHandler(DEVICENAME); + +% Initialize PacketHandler Structs +packetHandler(); + +dxl_comm_result = COMM_TX_FAIL; % Communication result + +dxl_error = 0; % Dynamixel error +dxl_present_position = 0; % Present position + +% Open port +if (openPort(port_num)) + fprintf('Succeeded to open the port!\n'); +else + unloadlibrary(lib_name); + fprintf('Failed to open the port!\n'); + input('Press any key to terminate...\n'); + return; +end + +% Set port baudrate +if (setBaudRate(port_num, BAUDRATE)) + fprintf('Succeeded to change the baudrate!\n'); +else + unloadlibrary(lib_name); + fprintf('Failed to change the baudrate!\n'); + input('Press any key to terminate...\n'); + return; +end + +% Set operating mode to extended position control mode +write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_OPERATING_MODE, EXT_POSITION_CONTROL_MODE); +dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); +dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); +if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); +elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); +else + fprintf('Operating mode changed to extended position control mode. \n'); +end + +% Enable Dynamixel Torque +write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE); +dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); +dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); +if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); +elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); +else + fprintf('Dynamixel has been successfully connected \n'); +end + +while 1 + if input('\nPress any key to continue! (or input e to quit!)', 's') == ESC_CHARACTER + break; + end + + fprintf(' Press SPACE key to clear multi-turn information! (or press e to stop!)'); + + % Write goal position + write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, MAX_POSITION_VALUE); + dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); + dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); + if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); + end + + while 1 + ch = -1; + % Read present position + dxl_present_position = read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); + dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); + if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); + end + + fprintf('\r [ID:%03d] GoalPos:%03d PresPos:%03d', DXL_ID, MAX_POSITION_VALUE, dxl_present_position); + ch = kbhit(0.2); + if ch == SPACE_ASCII_VALUE + fprintf('\n Stop & Clear Multi-Turn Information! \n'); + + % Write the present position to the goal position to stop moving + write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, typecast(uint32(dxl_present_position), 'int32')); + dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); + dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); + if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); + end + + pause(0.5); + + % Clear Multi-Turn Information + clearMultiTurn(port_num, PROTOCOL_VERSION, DXL_ID); + dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); + dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); + if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); + end + + % Read present position + dxl_present_position = read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); + dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); + dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); + if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); + end + + fprintf(' Present Position has been reset. : %03d \n', dxl_present_position); + break; + + elseif ch == ESC_CHARACTER + fprintf('\n Stopped!! \n'); + + % Write the present position to the goal position to stop moving + write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, typecast(uint32(dxl_present_position), 'int32')); + dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); + dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); + if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); + elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); + end + break; + end + + if ~(abs(MAX_POSITION_VALUE - typecast(uint32(dxl_present_position), 'int32')) > DXL_MOVING_STATUS_THRESHOLD) + break; + end + end +end + + +% Disable Dynamixel Torque +write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE); +dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); +dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); +if dxl_comm_result ~= COMM_SUCCESS + fprintf('%s\n', getTxRxResult(PROTOCOL_VERSION, dxl_comm_result)); +elseif dxl_error ~= 0 + fprintf('%s\n', getRxPacketError(PROTOCOL_VERSION, dxl_error)); +end + +% Close port +closePort(port_num); + +% Unload Library +unloadlibrary(lib_name); + +close all; + +function ch = kbhit(m) +% GETKEYWAIT - get a key within a time limit +% CH = GETKEYWAIT(P) waits for a keypress for a maximum of P seconds. P +% should be a positive number. CH is a double representing the key +% pressed key as an ascii number, including backspace (8), space (32), +% enter (13), etc. If a non-ascii key (Ctrl, Alt, etc.) is pressed, CH +% will be NaN. +% If no key is pressed within P seconds, -1 is returned, and if something +% went wrong during excution 0 is returned. +% +% See also INPUT, +% GETKEY (FileExchange) +% tested for Matlab 6.5 and higher +% version 2.1 (jan 2012) +% author : Jos van der Geest +% email : jos@jasen.nl +% History +% 1.0 (2005) creation +% 2.0 (apr 2009) - expanded error check on input argument, changed return +% values when a non-ascii was pressed (now NaN), or when something went +% wrong (now 0); added comments ; slight change in coding +% 2.1 (jan 2012) - modified a few properties, included check is figure +% still exists (after comment on GETKEY on FEX by Andrew). +% check input argument + narginchk(1,1) ; + if numel(m)~=1 || ~isnumeric(m) || ~isfinite(m) || m <= 0, + error('Argument should be a single positive number.') ; + end + % set up the timer + tt = timer ; + tt.timerfcn = 'uiresume' ; + tt.startdelay = m ; + % Set up the figure + % May be the position property should be individually tweaked to avoid visibility + callstr = 'set(gcbf,''Userdata'',double(get(gcbf,''Currentcharacter''))) ; uiresume ' ; + fh = figure(... + 'name','Press a key', ... + 'keypressfcn',callstr, ... + 'windowstyle','modal',... + 'numbertitle','off', ... + 'position',[0 0 1 1],... + 'userdata',-1) ; + try + % Wait for something to happen or the timer to run out + start(tt) ; + uiwait ; + ch = get(fh,'Userdata') ; + if isempty(ch), % a non-ascii key was pressed, return a NaN + ch = NaN ; + end + catch + % Something went wrong, return zero. + ch = 0 ; + end + % clean up the timer ... + stop(tt) ; + delete(tt) ; + % ... and figure + if ishandle(fh) + delete(fh) ; + end +end \ No newline at end of file diff --git a/ros/src/dynamixel_sdk/__init__.py b/python/CATKIN_IGNORE similarity index 100% rename from ros/src/dynamixel_sdk/__init__.py rename to python/CATKIN_IGNORE diff --git a/python/setup.py b/python/setup.py index c10954e7..54836fa5 100644 --- a/python/setup.py +++ b/python/setup.py @@ -4,7 +4,7 @@ setup( name='dynamixel_sdk', - version='3.6.0', + version='3.7.41', packages=['dynamixel_sdk'], package_dir={'': 'src'}, license='Apache 2.0', diff --git a/python/src/dynamixel_sdk/port_handler.py b/python/src/dynamixel_sdk/port_handler.py index de555d45..6bec0a93 100644 --- a/python/src/dynamixel_sdk/port_handler.py +++ b/python/src/dynamixel_sdk/port_handler.py @@ -129,14 +129,8 @@ def setupPort(self, cflag_baud): return True def getCFlagBaud(self, baudrate): - if platform.system() == 'Darwin': - if baudrate in [9600, 19200, 38400, 57600, 115200]: - return baudrate - else: - return -1 + if baudrate in [9600, 19200, 38400, 57600, 115200, 230400, 460800, 500000, 576000, 921600, 1000000, 1152000, + 2000000, 2500000, 3000000, 3500000, 4000000]: + return baudrate else: - if baudrate in [9600, 19200, 38400, 57600, 115200, 230400, 460800, 500000, 576000, 921600, 1000000, 1152000, - 2000000, 2500000, 3000000, 3500000, 4000000]: - return baudrate - else: - return -1 + return -1 diff --git a/python/src/dynamixel_sdk/protocol2_packet_handler.py b/python/src/dynamixel_sdk/protocol2_packet_handler.py index a3df5ea8..6b2fd690 100644 --- a/python/src/dynamixel_sdk/protocol2_packet_handler.py +++ b/python/src/dynamixel_sdk/protocol2_packet_handler.py @@ -21,8 +21,8 @@ from .robotis_def import * -TXPACKET_MAX_LEN = 4 * 1024 -RXPACKET_MAX_LEN = 4 * 1024 +TXPACKET_MAX_LEN = 1 * 1024 +RXPACKET_MAX_LEN = 1 * 1024 # for Protocol 2.0 Packet PKT_HEADER0 = 0 @@ -197,10 +197,9 @@ def removeStuffing(self, packet): packet[i + PKT_INSTRUCTION - 1] == 0xFF) and (packet[i + PKT_INSTRUCTION - 2] == 0xFF): # FF FF FD FD packet_length_out = packet_length_out - 1 - i += 1 - - packet[index] = packet[i + PKT_INSTRUCTION] - index += 1 + else: + packet[index] = packet[i + PKT_INSTRUCTION] + index += 1 packet[index] = packet[PKT_INSTRUCTION + packet_length_in - 2] packet[index + 1] = packet[PKT_INSTRUCTION + packet_length_in - 1] @@ -384,6 +383,8 @@ def broadcastPing(self, port): txpacket = [0] * 10 rxpacket = [] + tx_time_per_byte = (1000.0 / port.getBaudRate()) *10.0; + txpacket[PKT_ID] = BROADCAST_ID txpacket[PKT_LENGTH_L] = 3 txpacket[PKT_LENGTH_H] = 0 @@ -395,7 +396,8 @@ def broadcastPing(self, port): return data_list, result # set rx timeout - port.setPacketTimeout(wait_length * 1) + #port.setPacketTimeout(wait_length * 1) + port.setPacketTimeoutMillis((wait_length * tx_time_per_byte) + (3.0 * MAX_ID) + 16.0); while True: rxpacket += port.readPort(wait_length - rx_length) @@ -472,6 +474,22 @@ def reboot(self, port, dxl_id): _, result, error = self.txRxPacket(port, txpacket) return result, error + def clearMultiTurn(self, port, dxl_id): + txpacket = [0] * 15 + + txpacket[PKT_ID] = dxl_id + txpacket[PKT_LENGTH_L] = 8 + txpacket[PKT_LENGTH_H] = 0 + txpacket[PKT_INSTRUCTION] = INST_CLEAR + txpacket[PKT_PARAMETER0 + 0] = 0x01 + txpacket[PKT_PARAMETER0 + 1] = 0x44 + txpacket[PKT_PARAMETER0 + 2] = 0x58 + txpacket[PKT_PARAMETER0 + 3] = 0x4C + txpacket[PKT_PARAMETER0 + 4] = 0x22 + + _, result, error = self.txRxPacket(port, txpacket) + return result, error + def factoryReset(self, port, dxl_id, option): txpacket = [0] * 11 diff --git a/python/src/dynamixel_sdk/robotis_def.py b/python/src/dynamixel_sdk/robotis_def.py index aacadd76..b618b38b 100644 --- a/python/src/dynamixel_sdk/robotis_def.py +++ b/python/src/dynamixel_sdk/robotis_def.py @@ -29,6 +29,7 @@ INST_REG_WRITE = 4 INST_ACTION = 5 INST_FACTORY_RESET = 6 +INST_CLEAR = 16 INST_SYNC_WRITE = 131 # 0x83 INST_BULK_READ = 146 # 0x92 # --- Only for 2.0 --- diff --git a/python/tests/protocol1_0/read_write.py b/python/tests/protocol1_0/read_write.py index 2d8fa88e..099770d5 100644 --- a/python/tests/protocol1_0/read_write.py +++ b/python/tests/protocol1_0/read_write.py @@ -116,7 +116,7 @@ def getch(): break # Write goal position - dxl_comm_result, dxl_error = packetHandler.write4ByteTxRx(portHandler, DXL_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index]) + dxl_comm_result, dxl_error = packetHandler.write2ByteTxRx(portHandler, DXL_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index]) if dxl_comm_result != COMM_SUCCESS: print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) elif dxl_error != 0: @@ -124,7 +124,7 @@ def getch(): while 1: # Read present position - dxl_present_position, dxl_comm_result, dxl_error = packetHandler.read4ByteTxRx(portHandler, DXL_ID, ADDR_MX_PRESENT_POSITION) + dxl_present_position, dxl_comm_result, dxl_error = packetHandler.read2ByteTxRx(portHandler, DXL_ID, ADDR_MX_PRESENT_POSITION) if dxl_comm_result != COMM_SUCCESS: print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) elif dxl_error != 0: diff --git a/python/tests/protocol2_0/bulk_read_write.py b/python/tests/protocol2_0/bulk_read_write.py index 651f32fb..5443a1f0 100644 --- a/python/tests/protocol2_0/bulk_read_write.py +++ b/python/tests/protocol2_0/bulk_read_write.py @@ -124,7 +124,7 @@ def getch(): else: print("Dynamixel#%d has been successfully connected" % DXL1_ID) -# Enable Dynamixel#1 Torque +# Enable Dynamixel#2 Torque dxl_comm_result, dxl_error = packetHandler.write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE) if dxl_comm_result != COMM_SUCCESS: print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) diff --git a/python/tests/protocol2_0/clear_multi_turn.py b/python/tests/protocol2_0/clear_multi_turn.py new file mode 100644 index 00000000..df35d4fc --- /dev/null +++ b/python/tests/protocol2_0/clear_multi_turn.py @@ -0,0 +1,215 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +################################################################################ +# Copyright 2017 ROBOTIS CO., LTD. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +################################################################################ + +# Author: Ki Jong Gil (Gilbert) + +# +# ********* Clear Multi Turn Example ********* +# +# +# Available Dynamixel model on this example : All models using Protocol 2.0 +# This example is designed for using a Dynamixel PRO 54-200, and an USB2DYNAMIXEL. +# To use another Dynamixel model, such as X series, see their details in E-Manual(emanual.robotis.com) and edit below variables yourself. +# Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) +# + +from __future__ import print_function +import os + +if os.name == 'nt': + import msvcrt + def getch(): + return msvcrt.getch().decode() +else: + import termios, fcntl, sys, os + from select import select + fd = sys.stdin.fileno() + old_term = termios.tcgetattr(fd) + new_term = termios.tcgetattr(fd) + + def getch(): + new_term[3] = (new_term[3] & ~termios.ICANON & ~termios.ECHO) + termios.tcsetattr(fd, termios.TCSANOW, new_term) + try: + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_term) + return ch + + def kbhit(): + new_term[3] = (new_term[3] & ~(termios.ICANON | termios.ECHO)) + termios.tcsetattr(fd, termios.TCSANOW, new_term) + try: + dr,dw,de = select([sys.stdin], [], [], 0) + if dr != []: + return 1 + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_term) + sys.stdout.flush() + + return 0 + +from dynamixel_sdk import * # Uses Dynamixel SDK library + +# Control table address +ADDR_OPERATING_MODE = 11 # Control table address is different in Dynamixel model +ADDR_TORQUE_ENABLE = 64 +ADDR_GOAL_POSITION = 116 +ADDR_PRESENT_POSITION = 132 + +# Protocol version +PROTOCOL_VERSION = 2.0 # See which protocol version is used in the Dynamixel + +# Default setting +DXL_ID = 1 # Dynamixel ID : 1 +BAUDRATE = 57600 # Dynamixel default baudrate : 57600 +DEVICENAME = '/dev/ttyUSB0' # Check which port is being used on your controller + # ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*" + +TORQUE_ENABLE = 1 # Value for enabling the torque +TORQUE_DISABLE = 0 # Value for disabling the torque +MAX_POSITION_VALUE = 1048575 +DXL_MOVING_STATUS_THRESHOLD = 20 # Dynamixel will rotate between this value +EXT_POSITION_CONTROL_MODE = 4 # Value for extended position control mode (operating mode) + +ESC_ASCII_VALUE = 0x1b +SPACE_ASCII_VALUE = 0x20 + +# Initialize PortHandler instance +# Set the port path +# Get methods and members of PortHandlerLinux or PortHandlerWindows +portHandler = PortHandler(DEVICENAME) + +# Initialize PacketHandler instance +# Set the protocol version +# Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler +packetHandler = PacketHandler(PROTOCOL_VERSION) + +# Open port +if portHandler.openPort(): + print("Succeeded to open the port") +else: + print("Failed to open the port") + print("Press any key to terminate...") + getch() + quit() + + +# Set port baudrate +if portHandler.setBaudRate(BAUDRATE): + print("Succeeded to change the baudrate") +else: + print("Failed to change the baudrate") + print("Press any key to terminate...") + getch() + quit() + +# Set operating mode to extended position control mode +dxl_comm_result, dxl_error = packetHandler.write1ByteTxRx(portHandler, DXL_ID, ADDR_OPERATING_MODE, EXT_POSITION_CONTROL_MODE) +if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) +elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) +else: + print("Operating mode changed to extended position control mode.") + +# Enable Dynamixel Torque +dxl_comm_result, dxl_error = packetHandler.write1ByteTxRx(portHandler, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE) +if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) +elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) +else: + print("Dynamixel has been successfully connected") + +while 1: + print("\nPress any key to continue! (or press ESC to quit!)") + if getch() == chr(ESC_ASCII_VALUE): + break + print(" Press SPACE key to clear multi-turn information! (or press ESC to stop!)") + + # Write goal position + dxl_comm_result, dxl_error = packetHandler.write4ByteTxRx(portHandler, DXL_ID, ADDR_GOAL_POSITION, MAX_POSITION_VALUE) + if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) + elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) + + while 1: + # Read present position + dxl_present_position, dxl_comm_result, dxl_error = packetHandler.read4ByteTxRx(portHandler, DXL_ID, ADDR_PRESENT_POSITION) + if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) + elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) + + print(" [ID:%03d] GoalPos:%03d PresPos:%03d" %(DXL_ID, MAX_POSITION_VALUE, dxl_present_position), end = "\r") + if kbhit(): + c = getch() + if c == chr(SPACE_ASCII_VALUE): + print("\n Stop & Clear Multi-Turn Information! ") + # Write the present position to the goal position to stop moving + dxl_comm_result, dxl_error = packetHandler.write4ByteTxRx(portHandler, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position) + if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) + elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) + + time.sleep(0.3) + + # Clear Multi-Turn Information + dxl_comm_result, dxl_error = packetHandler.clearMultiTurn(portHandler, DXL_ID) + if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) + elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) + + # Read present position + dxl_present_position, dxl_comm_result, dxl_error = packetHandler.read4ByteTxRx(portHandler, DXL_ID, ADDR_PRESENT_POSITION) + if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) + elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) + + print(" Present Position has been reset. : %03d" % dxl_present_position) + + break + + elif c == chr(ESC_ASCII_VALUE): + print("\n Stopped!!") + # Write the present position to the goal position to stop moving + dxl_comm_result, dxl_error = packetHandler.write4ByteTxRx(portHandler, DXL_ID, ADDR_GOAL_POSITION, dxl_present_position) + if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) + elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) + break + + if not abs(MAX_POSITION_VALUE - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD: + break + +# Disable Dynamixel Torque +dxl_comm_result, dxl_error = packetHandler.write1ByteTxRx(portHandler, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE) +if dxl_comm_result != COMM_SUCCESS: + print("%s" % packetHandler.getTxRxResult(dxl_comm_result)) +elif dxl_error != 0: + print("%s" % packetHandler.getRxPacketError(dxl_error)) + +# Close port +portHandler.closePort() diff --git a/ros/CHANGELOG.rst b/ros/dynamixel_sdk/CHANGELOG.rst similarity index 81% rename from ros/CHANGELOG.rst rename to ros/dynamixel_sdk/CHANGELOG.rst index 829e486d..1cea7ea2 100644 --- a/ros/CHANGELOG.rst +++ b/ros/dynamixel_sdk/CHANGELOG.rst @@ -2,12 +2,52 @@ Changelog for package dynamixel_sdk ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.7.41(2020-08-12) +------------------- +* DYNAMIXEL SDK ROS example initial commit. +* Bug fix for 4.5Mbps support (#430) +* Contributors: Zerom, Will Son + +3.7.31 (2020-07-13) +------------------- +* ROS 1 Noetic Ninjemys support +* 3x faster getError member function of GroupSyncRead Class +* Contributors: developer0hye, Zerom, Will Son + +3.7.21 (2019-09-06) +------------------- +* Fixed buffer overflow bug (rxpacket size) +* Fixed typo in the package.xml and header files +* Contributors: Chris Lalancette, Zerom, Pyo + +3.7.11 (2019-08-19) +------------------- +- Updated C lib and DLL file +- Changed C# / win32 / protocol_combined output path +- Fixed "protocol_combined" example bug +- Fixed typo in bulk_read_write.py +* Contributors: Pyo, Zerom + +3.7.10 (2019-08-19) +------------------- +* Supported ROS 2 Dashing Diademata +* Contributors: Darby, Pyo + +3.7.0 (2019-01-03) +------------------ +* Added clear instruction `#269 `_ +* Removed busy waiting for rxPacket() +* Fixed addStuffing() function (reduced stack memory usage) +* Fixed memory issues `#268 `_ +* Fixed the broadcast ping bug in dxl_monitor +* Contributors: Gilbert, Pyo, Zerom + 3.6.2 (2018-07-17) ------------------ -* added python modules for ROS to ros folder -* moved cpp library files for ROS to ros folder -* created an ROS package separately `#187 `_ -* modified the e-Manual address to emanual.robotis.com +* Added python modules for ROS to ros folder +* Moved cpp library files for ROS to ros folder +* Created an ROS package separately `#187 `_ +* Modified the e-Manual address to emanual.robotis.com * Contributors: Pyo 3.6.1 (2018-06-14) diff --git a/ros/CMakeLists.txt b/ros/dynamixel_sdk/CMakeLists.txt similarity index 97% rename from ros/CMakeLists.txt rename to ros/dynamixel_sdk/CMakeLists.txt index f71e5443..768bbe31 100644 --- a/ros/CMakeLists.txt +++ b/ros/dynamixel_sdk/CMakeLists.txt @@ -4,6 +4,9 @@ cmake_minimum_required(VERSION 2.8.3) project(dynamixel_sdk) +## Compile as C++11, supported in ROS Kinetic and newer +add_compile_options(-std=c++11) + ################################################################################ # Find catkin packages and libraries for catkin and system dependencies ################################################################################ diff --git a/ros/include/dynamixel_sdk/dynamixel_sdk.h b/ros/dynamixel_sdk/include/dynamixel_sdk/dynamixel_sdk.h similarity index 100% rename from ros/include/dynamixel_sdk/dynamixel_sdk.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/dynamixel_sdk.h diff --git a/ros/include/dynamixel_sdk/group_bulk_read.h b/ros/dynamixel_sdk/include/dynamixel_sdk/group_bulk_read.h similarity index 100% rename from ros/include/dynamixel_sdk/group_bulk_read.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/group_bulk_read.h diff --git a/ros/include/dynamixel_sdk/group_bulk_write.h b/ros/dynamixel_sdk/include/dynamixel_sdk/group_bulk_write.h similarity index 100% rename from ros/include/dynamixel_sdk/group_bulk_write.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/group_bulk_write.h diff --git a/ros/include/dynamixel_sdk/group_sync_read.h b/ros/dynamixel_sdk/include/dynamixel_sdk/group_sync_read.h similarity index 100% rename from ros/include/dynamixel_sdk/group_sync_read.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/group_sync_read.h diff --git a/ros/include/dynamixel_sdk/group_sync_write.h b/ros/dynamixel_sdk/include/dynamixel_sdk/group_sync_write.h similarity index 100% rename from ros/include/dynamixel_sdk/group_sync_write.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/group_sync_write.h diff --git a/ros/include/dynamixel_sdk/packet_handler.h b/ros/dynamixel_sdk/include/dynamixel_sdk/packet_handler.h similarity index 96% rename from ros/include/dynamixel_sdk/packet_handler.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/packet_handler.h index 37ff2400..8b20e26f 100644 --- a/ros/include/dynamixel_sdk/packet_handler.h +++ b/ros/dynamixel_sdk/include/dynamixel_sdk/packet_handler.h @@ -24,6 +24,11 @@ #if defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) #include + +#define ERROR_PRINT SerialBT2.print +#else +#define ERROR_PRINT printf + #endif #include @@ -52,6 +57,7 @@ #define INST_BULK_READ 146 // 0x92 // --- Only for 2.0 --- // #define INST_REBOOT 8 +#define INST_CLEAR 16 // 0x10 #define INST_STATUS 85 // 0x55 #define INST_SYNC_READ 130 // 0x82 #define INST_BULK_WRITE 147 // 0x93 @@ -222,6 +228,19 @@ class WINDECLSPEC PacketHandler //////////////////////////////////////////////////////////////////////////////// virtual int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0; + //////////////////////////////////////////////////////////////////////////////// + /// @brief The function that reset multi-turn revolution information of Dynamixel + /// @description The function makes an instruction packet with INST_CLEAR, + /// @description transmits the packet with PacketHandler::txRxPacket(). + /// @description Applied Products : MX with Protocol 2.0 (Firmware v42 or above), + /// @description Dynamixel X-series (Firmware v42 or above). + /// @param port PortHandler instance + /// @param id Dynamixel ID + /// @param error Dynamixel hardware error + /// @return communication results which come from PacketHandler::txRxPacket() + //////////////////////////////////////////////////////////////////////////////// + virtual int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0) = 0; + //////////////////////////////////////////////////////////////////////////////// /// @brief The function that makes Dynamixel reset as it was produced in the factory /// @description The function makes an instruction packet with INST_FACTORY_RESET, @@ -491,7 +510,7 @@ class WINDECLSPEC PacketHandler /// @brief The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits the packet with PacketHandler::txPacket(). - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write @@ -506,7 +525,7 @@ class WINDECLSPEC PacketHandler /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits and receives the packet with PacketHandler::txRxPacket(), /// @description gets the error from the packet. - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write diff --git a/ros/include/dynamixel_sdk/port_handler.h b/ros/dynamixel_sdk/include/dynamixel_sdk/port_handler.h similarity index 100% rename from ros/include/dynamixel_sdk/port_handler.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/port_handler.h diff --git a/ros/include/dynamixel_sdk/port_handler_arduino.h b/ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_arduino.h similarity index 100% rename from ros/include/dynamixel_sdk/port_handler_arduino.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_arduino.h diff --git a/ros/include/dynamixel_sdk/port_handler_linux.h b/ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_linux.h similarity index 100% rename from ros/include/dynamixel_sdk/port_handler_linux.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_linux.h diff --git a/ros/include/dynamixel_sdk/port_handler_mac.h b/ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_mac.h similarity index 100% rename from ros/include/dynamixel_sdk/port_handler_mac.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_mac.h diff --git a/ros/include/dynamixel_sdk/port_handler_windows.h b/ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_windows.h similarity index 100% rename from ros/include/dynamixel_sdk/port_handler_windows.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/port_handler_windows.h diff --git a/ros/include/dynamixel_sdk/protocol1_packet_handler.h b/ros/dynamixel_sdk/include/dynamixel_sdk/protocol1_packet_handler.h similarity index 98% rename from ros/include/dynamixel_sdk/protocol1_packet_handler.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/protocol1_packet_handler.h index ebfa05c0..3dcbadd1 100644 --- a/ros/include/dynamixel_sdk/protocol1_packet_handler.h +++ b/ros/dynamixel_sdk/include/dynamixel_sdk/protocol1_packet_handler.h @@ -178,6 +178,15 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler //////////////////////////////////////////////////////////////////////////////// int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// + /// @brief (Available only in Protocol 2.0) The function that reset multi-turn revolution information of Dynamixel + /// @param port PortHandler instance + /// @param id Dynamixel ID + /// @param error Dynamixel hardware error + /// @return COMM_NOT_AVAILABLE + //////////////////////////////////////////////////////////////////////////////// + int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// /// @brief The function that makes Dynamixel reset as it was produced in the factory /// @description The function makes an instruction packet with INST_FACTORY_RESET, @@ -447,7 +456,7 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler /// @brief The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits the packet with Protocol1PacketHandler::txPacket(). - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write @@ -462,7 +471,7 @@ class WINDECLSPEC Protocol1PacketHandler : public PacketHandler /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits and receives the packet with Protocol1PacketHandler::txRxPacket(), /// @description gets the error from the packet. - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write diff --git a/ros/include/dynamixel_sdk/protocol2_packet_handler.h b/ros/dynamixel_sdk/include/dynamixel_sdk/protocol2_packet_handler.h similarity index 97% rename from ros/include/dynamixel_sdk/protocol2_packet_handler.h rename to ros/dynamixel_sdk/include/dynamixel_sdk/protocol2_packet_handler.h index 3c953f39..b8bd8856 100644 --- a/ros/include/dynamixel_sdk/protocol2_packet_handler.h +++ b/ros/dynamixel_sdk/include/dynamixel_sdk/protocol2_packet_handler.h @@ -186,6 +186,19 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler //////////////////////////////////////////////////////////////////////////////// int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// + /// @brief The function that reset multi-turn revolution information of Dynamixel + /// @description The function makes an instruction packet with INST_CLEAR, + /// @description transmits the packet with Protocol2PacketHandler::txRxPacket(). + /// @description Applied Products : MX with Protocol 2.0 (Firmware v42 or above), + /// @description Dynamixel X-series (Firmware v42 or above). + /// @param port PortHandler instance + /// @param id Dynamixel ID + /// @param error Dynamixel hardware error + /// @return communication results which come from Protocol2PacketHandler::txRxPacket() + //////////////////////////////////////////////////////////////////////////////// + int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0); + //////////////////////////////////////////////////////////////////////////////// /// @brief The function that makes Dynamixel reset as it was produced in the factory /// @description The function makes an instruction packet with INST_FACTORY_RESET, @@ -455,7 +468,7 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler /// @brief The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits the packet with Protocol2PacketHandler::txPacket(). - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write @@ -470,7 +483,7 @@ class WINDECLSPEC Protocol2PacketHandler : public PacketHandler /// @description The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, /// @description transmits and receives the packet with Protocol2PacketHandler::txRxPacket(), /// @description gets the error from the packet. - /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. + /// @description The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. /// @param port PortHandler instance /// @param id Dynamixel ID /// @param address Address of the data for write diff --git a/ros/package.xml b/ros/dynamixel_sdk/package.xml similarity index 57% rename from ros/package.xml rename to ros/dynamixel_sdk/package.xml index a24119b7..6d8c066c 100644 --- a/ros/package.xml +++ b/ros/dynamixel_sdk/package.xml @@ -1,15 +1,16 @@ dynamixel_sdk - 3.6.2 + 3.7.41 - This package is wrapping version of ROBOTIS Dynamxel SDK for ROS. The ROBOTIS Dynamixel SDK, or SDK, is a software development library that provides Dynamixel control functions for packet communication. The API is designed for Dynamixel actuators and Dynamixel-based platforms. + This package is wrapping version of ROBOTIS Dynamixel SDK for ROS. The ROBOTIS Dynamixel SDK, or SDK, is a software development library that provides Dynamixel control functions for packet communication. The API is designed for Dynamixel actuators and Dynamixel-based platforms. Apache 2.0 - Pyo + Gilbert Zerom + Darby Lim Leon - Pyo + Will Son http://wiki.ros.org/dynamixel_sdk http://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/overview/ https://github.com/ROBOTIS-GIT/DynamixelSDK diff --git a/ros/setup.py b/ros/dynamixel_sdk/setup.py similarity index 100% rename from ros/setup.py rename to ros/dynamixel_sdk/setup.py diff --git a/ros/src/DynamixelSDK.h b/ros/dynamixel_sdk/src/DynamixelSDK.h similarity index 100% rename from ros/src/DynamixelSDK.h rename to ros/dynamixel_sdk/src/DynamixelSDK.h diff --git a/ros/dynamixel_sdk/src/dynamixel_sdk/__init__.py b/ros/dynamixel_sdk/src/dynamixel_sdk/__init__.py new file mode 100644 index 00000000..bc227b66 --- /dev/null +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/__init__.py @@ -0,0 +1,27 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +################################################################################ +# Copyright 2017 ROBOTIS CO., LTD. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +################################################################################ + +# Author: Ryu Woon Jung (Leon) + +from .port_handler import * +from .packet_handler import * +from .group_sync_read import * +from .group_sync_write import * +from .group_bulk_read import * +from .group_bulk_write import * diff --git a/ros/src/dynamixel_sdk/group_bulk_read.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_read.cpp similarity index 98% rename from ros/src/dynamixel_sdk/group_bulk_read.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_read.cpp index bcea7551..edd1ad69 100644 --- a/ros/src/dynamixel_sdk/group_bulk_read.cpp +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_read.cpp @@ -232,14 +232,5 @@ bool GroupBulkRead::getError(uint8_t id, uint8_t* error) // TODO : check protocol version, last_result_, data_list // if (last_result_ == false || error_list_.find(id) == error_list_.end()) - error[0] = error_list_[id][0]; - - if (error[0] != 0) - { - return true; - } - else - { - return false; - } + return error[0] = error_list_[id][0]; } \ No newline at end of file diff --git a/ros/src/dynamixel_sdk/group_bulk_read.py b/ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_read.py similarity index 100% rename from ros/src/dynamixel_sdk/group_bulk_read.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_read.py diff --git a/ros/src/dynamixel_sdk/group_bulk_write.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_write.cpp similarity index 100% rename from ros/src/dynamixel_sdk/group_bulk_write.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_write.cpp diff --git a/ros/src/dynamixel_sdk/group_bulk_write.py b/ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_write.py similarity index 100% rename from ros/src/dynamixel_sdk/group_bulk_write.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_bulk_write.py diff --git a/ros/src/dynamixel_sdk/group_sync_read.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_read.cpp similarity index 97% rename from ros/src/dynamixel_sdk/group_sync_read.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_read.cpp index f392943b..79e5f3b8 100644 --- a/ros/src/dynamixel_sdk/group_sync_read.cpp +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_read.cpp @@ -201,14 +201,5 @@ bool GroupSyncRead::getError(uint8_t id, uint8_t* error) // TODO : check protocol version, last_result_, data_list // if (ph_->getProtocolVersion() == 1.0 || last_result_ == false || error_list_.find(id) == error_list_.end()) - error[0] = error_list_[id][0]; - - if (error[0] != 0) - { - return true; - } - else - { - return false; - } + return error[0] = error_list_[id][0]; } \ No newline at end of file diff --git a/ros/src/dynamixel_sdk/group_sync_read.py b/ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_read.py similarity index 100% rename from ros/src/dynamixel_sdk/group_sync_read.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_read.py diff --git a/ros/src/dynamixel_sdk/group_sync_write.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_write.cpp similarity index 100% rename from ros/src/dynamixel_sdk/group_sync_write.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_write.cpp diff --git a/ros/src/dynamixel_sdk/group_sync_write.py b/ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_write.py similarity index 100% rename from ros/src/dynamixel_sdk/group_sync_write.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/group_sync_write.py diff --git a/ros/src/dynamixel_sdk/packet_handler.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/packet_handler.cpp similarity index 100% rename from ros/src/dynamixel_sdk/packet_handler.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/packet_handler.cpp diff --git a/ros/src/dynamixel_sdk/packet_handler.py b/ros/dynamixel_sdk/src/dynamixel_sdk/packet_handler.py similarity index 100% rename from ros/src/dynamixel_sdk/packet_handler.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/packet_handler.py diff --git a/ros/src/dynamixel_sdk/port_handler.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler.cpp similarity index 100% rename from ros/src/dynamixel_sdk/port_handler.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/port_handler.cpp diff --git a/ros/src/dynamixel_sdk/port_handler.py b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler.py similarity index 100% rename from ros/src/dynamixel_sdk/port_handler.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/port_handler.py diff --git a/ros/src/dynamixel_sdk/port_handler_arduino.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_arduino.cpp similarity index 92% rename from ros/src/dynamixel_sdk/port_handler_arduino.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_arduino.cpp index 19ad599f..07add9ad 100644 --- a/ros/src/dynamixel_sdk/port_handler_arduino.cpp +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_arduino.cpp @@ -27,7 +27,7 @@ #define DYNAMIXEL_SERIAL Serial3 #endif -#define LATENCY_TIMER 16 // msec (USB latency timer) +#define LATENCY_TIMER 4 // msec (USB latency timer) using namespace dynamixel; @@ -91,10 +91,17 @@ void PortHandlerArduino::closePort() void PortHandlerArduino::clearPort() { + int temp __attribute__((unused)); #if defined(__OPENCR__) - DYNAMIXEL_SERIAL.flush(); + while (DYNAMIXEL_SERIAL.available()) + { + temp = DYNAMIXEL_SERIAL.read(); + } #elif defined(__OPENCM904__) - p_dxl_serial->flush(); + while (p_dxl_serial->available()) + { + temp = p_dxl_serial->read(); + } #endif } @@ -205,7 +212,7 @@ bool PortHandlerArduino::isPacketTimeout() double PortHandlerArduino::getCurrentTime() { - return (double)millis(); + return (double)millis(); } double PortHandlerArduino::getTimeSinceStart() @@ -285,8 +292,15 @@ void PortHandlerArduino::setTxEnable() void PortHandlerArduino::setTxDisable() { #if defined(__OPENCR__) +#ifdef SERIAL_WRITES_NON_BLOCKING + DYNAMIXEL_SERIAL.flush(); // make sure it completes before we disable... +#endif drv_dxl_tx_enable(FALSE); + #elif defined(__OPENCM904__) +#ifdef SERIAL_WRITES_NON_BLOCKING + p_dxl_serial->flush(); +#endif drv_dxl_tx_enable(socket_fd_, FALSE); #endif } diff --git a/ros/src/dynamixel_sdk/port_handler_linux.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_linux.cpp similarity index 89% rename from ros/src/dynamixel_sdk/port_handler_linux.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_linux.cpp index 57564a94..5ba4091d 100644 --- a/ros/src/dynamixel_sdk/port_handler_linux.cpp +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_linux.cpp @@ -55,6 +55,27 @@ // or if you have another good idea that can be an alternatives, // please give us advice via github issue https://github.com/ROBOTIS-GIT/DynamixelSDK/issues +struct termios2 { + tcflag_t c_iflag; /* input mode flags */ + tcflag_t c_oflag; /* output mode flags */ + tcflag_t c_cflag; /* control mode flags */ + tcflag_t c_lflag; /* local mode flags */ + cc_t c_line; /* line discipline */ + cc_t c_cc[19]; /* control characters */ + speed_t c_ispeed; /* input speed */ + speed_t c_ospeed; /* output speed */ +}; + +#ifndef TCGETS2 +#define TCGETS2 _IOR('T', 0x2A, struct termios2) +#endif +#ifndef TCSETS2 +#define TCSETS2 _IOW('T', 0x2B, struct termios2) +#endif +#ifndef BOTHER +#define BOTHER 0010000 +#endif + using namespace dynamixel; PortHandlerLinux::PortHandlerLinux(const char *port_name) @@ -207,6 +228,19 @@ bool PortHandlerLinux::setupPort(int cflag_baud) bool PortHandlerLinux::setCustomBaudrate(int speed) { + struct termios2 options; + + if (ioctl(socket_fd_, TCGETS2, &options) != 01) + { + options.c_cflag &= ~CBAUD; + options.c_cflag |= BOTHER; + options.c_ispeed = speed; + options.c_ospeed = speed; + + if (ioctl(socket_fd_, TCSETS2, &options) != -1) + return true; + } + // try to set a custom divisor struct serial_struct ss; if(ioctl(socket_fd_, TIOCGSERIAL, &ss) != 0) diff --git a/ros/src/dynamixel_sdk/port_handler_mac.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_mac.cpp similarity index 100% rename from ros/src/dynamixel_sdk/port_handler_mac.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_mac.cpp diff --git a/ros/src/dynamixel_sdk/port_handler_windows.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_windows.cpp similarity index 100% rename from ros/src/dynamixel_sdk/port_handler_windows.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/port_handler_windows.cpp diff --git a/ros/src/dynamixel_sdk/protocol1_packet_handler.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/protocol1_packet_handler.cpp similarity index 97% rename from ros/src/dynamixel_sdk/protocol1_packet_handler.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/protocol1_packet_handler.cpp index f8efe111..668adfa3 100644 --- a/ros/src/dynamixel_sdk/protocol1_packet_handler.cpp +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/protocol1_packet_handler.cpp @@ -365,6 +365,11 @@ int Protocol1PacketHandler::reboot(PortHandler *port, uint8_t id, uint8_t *error return COMM_NOT_AVAILABLE; } +int Protocol1PacketHandler::clearMultiTurn(PortHandler *port, uint8_t id, uint8_t *error) +{ + return COMM_NOT_AVAILABLE; +} + int Protocol1PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error) { uint8_t txpacket[6] = {0}; @@ -407,6 +412,9 @@ int Protocol1PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t lengt uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length+6); //uint8_t *rxpacket = new uint8_t[length+6]; + if (rxpacket == NULL) + return result; + do { result = rxPacket(port, rxpacket); } while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id); @@ -436,8 +444,14 @@ int Protocol1PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add uint8_t txpacket[8] = {0}; uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN);//(length+6); + if (rxpacket == NULL) + return result; + if (id >= BROADCAST_ID) + { + free(rxpacket); return COMM_NOT_AVAILABLE; + } txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = 4; @@ -534,6 +548,9 @@ int Protocol1PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t uint8_t *txpacket = (uint8_t *)malloc(length+7); //uint8_t *txpacket = new uint8_t[length+7]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_WRITE; @@ -559,6 +576,9 @@ int Protocol1PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t ad //uint8_t *txpacket = new uint8_t[length+7]; uint8_t rxpacket[6] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_WRITE; @@ -615,6 +635,9 @@ int Protocol1PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16 uint8_t *txpacket = (uint8_t *)malloc(length+6); //uint8_t *txpacket = new uint8_t[length+6]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_REG_WRITE; @@ -640,6 +663,9 @@ int Protocol1PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t //uint8_t *txpacket = new uint8_t[length+6]; uint8_t rxpacket[6] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH] = length+3; txpacket[PKT_INSTRUCTION] = INST_REG_WRITE; @@ -669,6 +695,9 @@ int Protocol1PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_ad // 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM //uint8_t *txpacket = new uint8_t[param_length + 8]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH] = param_length + 4; // 4: INST START_ADDR DATA_LEN ... CHKSUM txpacket[PKT_INSTRUCTION] = INST_SYNC_WRITE; @@ -694,6 +723,9 @@ int Protocol1PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16 // 7: HEADER0 HEADER1 ID LEN INST 0x00 ... CHKSUM //uint8_t *txpacket = new uint8_t[param_length + 7]; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH] = param_length + 3; // 3: INST 0x00 ... CHKSUM txpacket[PKT_INSTRUCTION] = INST_BULK_READ; diff --git a/ros/src/dynamixel_sdk/protocol1_packet_handler.py b/ros/dynamixel_sdk/src/dynamixel_sdk/protocol1_packet_handler.py similarity index 100% rename from ros/src/dynamixel_sdk/protocol1_packet_handler.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/protocol1_packet_handler.py diff --git a/ros/src/dynamixel_sdk/protocol2_packet_handler.cpp b/ros/dynamixel_sdk/src/dynamixel_sdk/protocol2_packet_handler.cpp similarity index 90% rename from ros/src/dynamixel_sdk/protocol2_packet_handler.cpp rename to ros/dynamixel_sdk/src/dynamixel_sdk/protocol2_packet_handler.cpp index c897e620..06dae1d2 100644 --- a/ros/src/dynamixel_sdk/protocol2_packet_handler.cpp +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/protocol2_packet_handler.cpp @@ -17,11 +17,14 @@ /* Author: zerom, Ryu Woon Jung (Leon) */ #if defined(__linux__) +#include #include "protocol2_packet_handler.h" #elif defined(__APPLE__) +#include #include "protocol2_packet_handler.h" #elif defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT +#include #include "protocol2_packet_handler.h" #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) #include "../../include/dynamixel_sdk/protocol2_packet_handler.h" @@ -31,8 +34,8 @@ #include #include -#define TXPACKET_MAX_LEN (4*1024) -#define RXPACKET_MAX_LEN (4*1024) +#define TXPACKET_MAX_LEN (1*1024) +#define RXPACKET_MAX_LEN (1*1024) ///////////////// for Protocol 2.0 Packet ///////////////// #define PKT_HEADER0 0 @@ -140,7 +143,7 @@ const char *Protocol2PacketHandler::getRxPacketError(uint8_t error) unsigned short Protocol2PacketHandler::updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size) { uint16_t i; - uint16_t crc_table[256] = {0x0000, + static const uint16_t crc_table[256] = {0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011, 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D, @@ -190,39 +193,48 @@ unsigned short Protocol2PacketHandler::updateCRC(uint16_t crc_accum, uint8_t *da void Protocol2PacketHandler::addStuffing(uint8_t *packet) { - int i = 0, index = 0; int packet_length_in = DXL_MAKEWORD(packet[PKT_LENGTH_L], packet[PKT_LENGTH_H]); int packet_length_out = packet_length_in; - uint8_t temp[TXPACKET_MAX_LEN] = {0}; + + if (packet_length_in < 8) // INSTRUCTION, ADDR_L, ADDR_H, CRC16_L, CRC16_H + FF FF FD + return; - for (uint16_t s = PKT_HEADER0; s <= PKT_LENGTH_H; s++) - temp[s] = packet[s]; // FF FF FD XX ID LEN_L LEN_H - //memcpy(temp, packet, PKT_LENGTH_H+1); - index = PKT_INSTRUCTION; - for (i = 0; i < packet_length_in - 2; i++) // except CRC + uint8_t *packet_ptr; + uint16_t packet_length_before_crc = packet_length_in - 2; + for (uint16_t i = 3; i < packet_length_before_crc; i++) { - temp[index++] = packet[i+PKT_INSTRUCTION]; - if (packet[i+PKT_INSTRUCTION] == 0xFD && packet[i+PKT_INSTRUCTION-1] == 0xFF && packet[i+PKT_INSTRUCTION-2] == 0xFF) - { // FF FF FD - temp[index++] = 0xFD; + packet_ptr = &packet[i+PKT_INSTRUCTION-2]; + if (packet_ptr[0] == 0xFF && packet_ptr[1] == 0xFF && packet_ptr[2] == 0xFD) packet_length_out++; + } + + if (packet_length_in == packet_length_out) // no stuffing required + return; + + uint16_t out_index = packet_length_out + 6 - 2; // last index before crc + uint16_t in_index = packet_length_in + 6 - 2; // last index before crc + while (out_index != in_index) + { + if (packet[in_index] == 0xFD && packet[in_index-1] == 0xFF && packet[in_index-2] == 0xFF) + { + packet[out_index--] = 0xFD; // byte stuffing + if (out_index != in_index) + { + packet[out_index--] = packet[in_index--]; // FD + packet[out_index--] = packet[in_index--]; // FF + packet[out_index--] = packet[in_index--]; // FF + } + } + else + { + packet[out_index--] = packet[in_index--]; } } - temp[index++] = packet[PKT_INSTRUCTION+packet_length_in-2]; - temp[index++] = packet[PKT_INSTRUCTION+packet_length_in-1]; - - - ////////////////////////// - if (packet_length_in != packet_length_out) - packet = (uint8_t *)realloc(packet, index * sizeof(uint8_t)); - /////////////////////////// - - for (uint16_t s = 0; s < index; s++) - packet[s] = temp[s]; - //memcpy(packet, temp, index); packet[PKT_LENGTH_L] = DXL_LOBYTE(packet_length_out); packet[PKT_LENGTH_H] = DXL_HIBYTE(packet_length_out); + + return; } void Protocol2PacketHandler::removeStuffing(uint8_t *packet) @@ -393,6 +405,11 @@ int Protocol2PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket) break; } } +#if defined(__linux__) || defined(__APPLE__) + usleep(0); +#elif defined(_WIN32) || defined(_WIN64) + Sleep(0); +#endif } port->is_using_ = false; @@ -489,6 +506,8 @@ int Protocol2PacketHandler::broadcastPing(PortHandler *port, std::vectorgetBaudRate()) * 10.0; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = 3; txpacket[PKT_LENGTH_H] = 0; @@ -502,7 +521,8 @@ int Protocol2PacketHandler::broadcastPing(PortHandler *port, std::vectorsetPacketTimeout((uint16_t)(wait_length * 30)); + //port->setPacketTimeout((uint16_t)(wait_length * 30)); + port->setPacketTimeout(((double)wait_length * tx_time_per_byte) + (3.0 * (double)MAX_ID) + 16.0); while(1) { @@ -595,6 +615,24 @@ int Protocol2PacketHandler::reboot(PortHandler *port, uint8_t id, uint8_t *error return txRxPacket(port, txpacket, rxpacket, error); } +int Protocol2PacketHandler::clearMultiTurn(PortHandler *port, uint8_t id, uint8_t *error) +{ + uint8_t txpacket[15] = {0}; + uint8_t rxpacket[11] = {0}; + + txpacket[PKT_ID] = id; + txpacket[PKT_LENGTH_L] = 8; + txpacket[PKT_LENGTH_H] = 0; + txpacket[PKT_INSTRUCTION] = INST_CLEAR; + txpacket[PKT_PARAMETER0] = 0x01; + txpacket[PKT_PARAMETER0+1] = 0x44; + txpacket[PKT_PARAMETER0+2] = 0x58; + txpacket[PKT_PARAMETER0+3] = 0x4C; + txpacket[PKT_PARAMETER0+4] = 0x22; + + return txRxPacket(port, txpacket, rxpacket, error); +} + int Protocol2PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error) { uint8_t txpacket[11] = {0}; @@ -641,8 +679,10 @@ int Protocol2PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t lengt int result = COMM_TX_FAIL; uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length + 11 + (length/3)); // (length/3): consider stuffing - //uint8_t *rxpacket = new uint8_t[length + 11 + (length/3)]; // (length/3): consider stuffing - + + if (rxpacket == NULL) + return result; + do { result = rxPacket(port, rxpacket); } while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id); @@ -672,8 +712,14 @@ int Protocol2PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t add uint8_t *rxpacket = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length + 11 + (length/3)); // (length/3): consider stuffing + if (rxpacket == NULL) + return result; + if (id >= BROADCAST_ID) + { + free(rxpacket); return COMM_NOT_AVAILABLE; + } txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = 7; @@ -770,8 +816,10 @@ int Protocol2PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t { int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length+12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); + + if (txpacket == NULL) + return result; txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); @@ -796,10 +844,12 @@ int Protocol2PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t ad { int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length + 12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); uint8_t rxpacket[11] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5); @@ -853,11 +903,13 @@ int Protocol2PacketHandler::write4ByteTxRx(PortHandler *port, uint8_t id, uint16 int Protocol2PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length + 12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5); @@ -879,12 +931,14 @@ int Protocol2PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16 int Protocol2PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(length + 12); - //uint8_t *txpacket = new uint8_t[length+12]; + uint8_t *txpacket = (uint8_t *)malloc(length + 12 + (length / 3)); uint8_t rxpacket[11] = {0}; + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = id; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(length+5); txpacket[PKT_LENGTH_H] = DXL_HIBYTE(length+5); @@ -905,11 +959,14 @@ int Protocol2PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t int Protocol2PacketHandler::syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 14); + uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3)); // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H @@ -933,12 +990,14 @@ int Protocol2PacketHandler::syncReadTx(PortHandler *port, uint16_t start_address int Protocol2PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 14); - //uint8_t *txpacket = new uint8_t[param_length + 14]; + uint8_t *txpacket = (uint8_t *)malloc(param_length + 14 + (param_length / 3)); // 14: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 7); // 7: INST START_ADDR_L START_ADDR_H DATA_LEN_L DATA_LEN_H CRC16_L CRC16_H @@ -961,12 +1020,14 @@ int Protocol2PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_ad int Protocol2PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 10); - //uint8_t *txpacket = new uint8_t[param_length + 10]; + uint8_t *txpacket = (uint8_t *)malloc(param_length + 10 + (param_length / 3)); // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H @@ -992,12 +1053,14 @@ int Protocol2PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16 int Protocol2PacketHandler::bulkWriteTxOnly(PortHandler *port, uint8_t *param, uint16_t param_length) { - int result = COMM_TX_FAIL; + int result = COMM_TX_FAIL; - uint8_t *txpacket = (uint8_t *)malloc(param_length + 10); - //uint8_t *txpacket = new uint8_t[param_length + 10]; + uint8_t *txpacket = (uint8_t *)malloc(param_length + 10 + (param_length / 3)); // 10: HEADER0 HEADER1 HEADER2 RESERVED ID LEN_L LEN_H INST CRC16_L CRC16_H + if (txpacket == NULL) + return result; + txpacket[PKT_ID] = BROADCAST_ID; txpacket[PKT_LENGTH_L] = DXL_LOBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H txpacket[PKT_LENGTH_H] = DXL_HIBYTE(param_length + 3); // 3: INST CRC16_L CRC16_H diff --git a/ros/src/dynamixel_sdk/protocol2_packet_handler.py b/ros/dynamixel_sdk/src/dynamixel_sdk/protocol2_packet_handler.py similarity index 97% rename from ros/src/dynamixel_sdk/protocol2_packet_handler.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/protocol2_packet_handler.py index a3df5ea8..6b2fd690 100644 --- a/ros/src/dynamixel_sdk/protocol2_packet_handler.py +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/protocol2_packet_handler.py @@ -21,8 +21,8 @@ from .robotis_def import * -TXPACKET_MAX_LEN = 4 * 1024 -RXPACKET_MAX_LEN = 4 * 1024 +TXPACKET_MAX_LEN = 1 * 1024 +RXPACKET_MAX_LEN = 1 * 1024 # for Protocol 2.0 Packet PKT_HEADER0 = 0 @@ -197,10 +197,9 @@ def removeStuffing(self, packet): packet[i + PKT_INSTRUCTION - 1] == 0xFF) and (packet[i + PKT_INSTRUCTION - 2] == 0xFF): # FF FF FD FD packet_length_out = packet_length_out - 1 - i += 1 - - packet[index] = packet[i + PKT_INSTRUCTION] - index += 1 + else: + packet[index] = packet[i + PKT_INSTRUCTION] + index += 1 packet[index] = packet[PKT_INSTRUCTION + packet_length_in - 2] packet[index + 1] = packet[PKT_INSTRUCTION + packet_length_in - 1] @@ -384,6 +383,8 @@ def broadcastPing(self, port): txpacket = [0] * 10 rxpacket = [] + tx_time_per_byte = (1000.0 / port.getBaudRate()) *10.0; + txpacket[PKT_ID] = BROADCAST_ID txpacket[PKT_LENGTH_L] = 3 txpacket[PKT_LENGTH_H] = 0 @@ -395,7 +396,8 @@ def broadcastPing(self, port): return data_list, result # set rx timeout - port.setPacketTimeout(wait_length * 1) + #port.setPacketTimeout(wait_length * 1) + port.setPacketTimeoutMillis((wait_length * tx_time_per_byte) + (3.0 * MAX_ID) + 16.0); while True: rxpacket += port.readPort(wait_length - rx_length) @@ -472,6 +474,22 @@ def reboot(self, port, dxl_id): _, result, error = self.txRxPacket(port, txpacket) return result, error + def clearMultiTurn(self, port, dxl_id): + txpacket = [0] * 15 + + txpacket[PKT_ID] = dxl_id + txpacket[PKT_LENGTH_L] = 8 + txpacket[PKT_LENGTH_H] = 0 + txpacket[PKT_INSTRUCTION] = INST_CLEAR + txpacket[PKT_PARAMETER0 + 0] = 0x01 + txpacket[PKT_PARAMETER0 + 1] = 0x44 + txpacket[PKT_PARAMETER0 + 2] = 0x58 + txpacket[PKT_PARAMETER0 + 3] = 0x4C + txpacket[PKT_PARAMETER0 + 4] = 0x22 + + _, result, error = self.txRxPacket(port, txpacket) + return result, error + def factoryReset(self, port, dxl_id, option): txpacket = [0] * 11 diff --git a/ros/src/dynamixel_sdk/robotis_def.py b/ros/dynamixel_sdk/src/dynamixel_sdk/robotis_def.py similarity index 97% rename from ros/src/dynamixel_sdk/robotis_def.py rename to ros/dynamixel_sdk/src/dynamixel_sdk/robotis_def.py index aacadd76..3986393b 100644 --- a/ros/src/dynamixel_sdk/robotis_def.py +++ b/ros/dynamixel_sdk/src/dynamixel_sdk/robotis_def.py @@ -32,7 +32,8 @@ INST_SYNC_WRITE = 131 # 0x83 INST_BULK_READ = 146 # 0x92 # --- Only for 2.0 --- -INST_REBOOT = 8 +INST_REBOOT = 8 +INST_CLEAR = 16 #0x10 INST_STATUS = 85 # 0x55 INST_SYNC_READ = 130 # 0x82 INST_BULK_WRITE = 147 # 0x93 diff --git a/ros/dynamixel_sdk_examples/CHANGELOG.rst b/ros/dynamixel_sdk_examples/CHANGELOG.rst new file mode 100644 index 00000000..bc7479c4 --- /dev/null +++ b/ros/dynamixel_sdk_examples/CHANGELOG.rst @@ -0,0 +1,9 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package dynamixel_sdk_examples +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +3.7.41(2020-08-12) +------------------- +* DYNAMIXEL SDK ROS example initial commit. +* Bug fix for 4.5Mbps support (#430) +* Contributors: Zerom, Will Son diff --git a/ros/dynamixel_sdk_examples/CMakeLists.txt b/ros/dynamixel_sdk_examples/CMakeLists.txt new file mode 100644 index 00000000..0e4d8405 --- /dev/null +++ b/ros/dynamixel_sdk_examples/CMakeLists.txt @@ -0,0 +1,73 @@ +################################################################################ +# Set minimum required version of cmake, project name and compile options +################################################################################ +cmake_minimum_required(VERSION 2.8.3) +project(dynamixel_sdk_examples) + +## Compile as C++11, supported in ROS Kinetic and newer +add_compile_options(-std=c++11) + +################################################################################ +# Find catkin packages and libraries for catkin and system dependencies +################################################################################ +find_package(catkin REQUIRED + COMPONENTS + roscpp + std_msgs + message_generation + dynamixel_sdk +) + +################################################################################ +# Declare ROS messages, services and actions +################################################################################ +## Generate messages in the 'msg' folder +add_message_files( + FILES + SetPosition.msg +) + +## Generate services in the 'srv' folder +add_service_files( + FILES + GetPosition.srv +) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs +) + +################################################################################ +# Declare catkin specific configuration to be passed to dependent projects +################################################################################ +catkin_package( + CATKIN_DEPENDS + roscpp + std_msgs + dynamixel_sdk +# DEPENDS system_lib +) + +################################################################################ +# Build +################################################################################ +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( + ${catkin_INCLUDE_DIRS} +) + +add_executable(read_write_node src/read_write_node.cpp) +add_dependencies(read_write_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(read_write_node ${catkin_LIBRARIES}) + +################################################################################ +# Install +################################################################################ +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +install(TARGETS read_write_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) diff --git a/ros/dynamixel_sdk_examples/msg/SetPosition.msg b/ros/dynamixel_sdk_examples/msg/SetPosition.msg new file mode 100644 index 00000000..10fc14b5 --- /dev/null +++ b/ros/dynamixel_sdk_examples/msg/SetPosition.msg @@ -0,0 +1,2 @@ +uint8 id +int32 position diff --git a/ros/dynamixel_sdk_examples/package.xml b/ros/dynamixel_sdk_examples/package.xml new file mode 100644 index 00000000..fa69ffeb --- /dev/null +++ b/ros/dynamixel_sdk_examples/package.xml @@ -0,0 +1,24 @@ + + + dynamixel_sdk_examples + 0.1.0 + The DYNAMIXEL SDK ROS example package + + zerom --> + zerom + + Apache 2.0 + + + + + + + catkin + roscpp + std_msgs + dynamixel_sdk + message_generation + message_runtime + + diff --git a/ros/dynamixel_sdk_examples/src/read_write_node.cpp b/ros/dynamixel_sdk_examples/src/read_write_node.cpp new file mode 100644 index 00000000..d0cc563f --- /dev/null +++ b/ros/dynamixel_sdk_examples/src/read_write_node.cpp @@ -0,0 +1,126 @@ +/******************************************************************************* +* Copyright 2020 ROBOTIS CO., LTD. +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*******************************************************************************/ + +/******************************************************************************* + * This example is written for DYNAMIXEL X(excluding XL-320) and MX(2.0) series with U2D2. + * For other series, please refer to the product eManual and modify the Control Table addresses and other definitions. + * To test this example, please follow the commands below. + * + * Open terminal #1 + * $ roscore + * + * Open terminal #2 + * $ rosrun dynamixel_sdk_examples read_write_node + * + * Open terminal #3 (run one of below commands at a time) + * $ rostopic pub -1 /set_position dynamixel_sdk_examples/SetPosition "{id: 1, position: 0}" + * $ rostopic pub -1 /set_position dynamixel_sdk_examples/SetPosition "{id: 1, position: 1000}" + * $ rosservice call /get_position "id: 1" + * + * Author: Zerom +*******************************************************************************/ + +#include + +#include "std_msgs/String.h" +#include "dynamixel_sdk_examples/GetPosition.h" +#include "dynamixel_sdk_examples/SetPosition.h" +#include "dynamixel_sdk/dynamixel_sdk.h" + +using namespace dynamixel; + +// Control table address +#define ADDR_TORQUE_ENABLE 64 +#define ADDR_GOAL_POSITION 116 +#define ADDR_PRESENT_POSITION 132 + +// Protocol version +#define PROTOCOL_VERSION 2.0 // Default Protocol version of DYNAMIXEL X series. + +// Default setting +#define DXL1_ID 1 // DXL1 ID +#define DXL2_ID 2 // DXL2 ID +#define BAUDRATE 57600 // Default Baudrate of DYNAMIXEL X series +#define DEVICE_NAME "/dev/ttyUSB0" // [Linux] To find assigned port, use "$ ls /dev/ttyUSB*" command + +PortHandler *portHandler; +PacketHandler *packetHandler; + +bool getPresentPosition(dynamixel_sdk_examples::GetPosition::Request &req, + dynamixel_sdk_examples::GetPosition::Response &res) +{ + uint8_t dxl_error = 0; + int dxl_comm_result = COMM_TX_FAIL; + + // Position Value of X series is 4 byte data. For AX & MX(1.0) use 2 byte data(int16_t) for the Position Value. + int32_t pos = 0; + + // Read Present Position (length : 4 bytes) and Convert uint32 -> int32 + // When reading 2 byte data from AX / MX(1.0), use read2ByteTxRx() instead. + dxl_comm_result = packetHandler->read4ByteTxRx(portHandler, (uint8_t)req.id, ADDR_PRESENT_POSITION, (uint32_t*)&pos, &dxl_error); + ROS_INFO("getPosition : [ID:%d] -> [POSITION:%d]", req.id, pos); + + res.position = pos; + return true; +} + +void setPositionCallback(const dynamixel_sdk_examples::SetPosition::ConstPtr &msg) +{ + uint8_t dxl_error = 0; + + // Position Value of X series is 4 byte data. For AX & MX(1.0) use 2 byte data(uint16_t) for the Position Value. + uint32_t pos = (unsigned int)msg->position; // Convert int32 -> uint32 + + // Write Goal Position (length : 4 bytes) + // When writing 2 byte data to AX / MX(1.0), use write2ByteTxRx() instead. + packetHandler->write4ByteTxRx(portHandler, (uint8_t)msg->id, ADDR_GOAL_POSITION, pos, &dxl_error); + ROS_INFO("setPosition : [ID:%d] [POSITION:%d]", msg->id, msg->position); +} + +int main(int argc, char **argv) +{ + uint8_t dxl_error = 0; + ros::init(argc, argv, "read_write_node"); + ros::NodeHandle nh; + + portHandler = dynamixel::PortHandler::getPortHandler(DEVICE_NAME); + packetHandler = dynamixel::PacketHandler::getPacketHandler(PROTOCOL_VERSION); + + if(portHandler->openPort() == false) + { + ROS_ERROR("Failed to open the port!"); + } + + if(portHandler->setBaudRate(BAUDRATE) == false) + { + ROS_ERROR("Failed to set the baudrate!"); + } + + ros::Subscriber set_position_sub = nh.subscribe("/set_position", 10, setPositionCallback); + ros::ServiceServer get_position_srv = nh.advertiseService("/get_position", getPresentPosition); + + packetHandler->write1ByteTxRx(portHandler, DXL1_ID, ADDR_TORQUE_ENABLE, 1, &dxl_error); + packetHandler->write1ByteTxRx(portHandler, DXL2_ID, ADDR_TORQUE_ENABLE, 1, &dxl_error); + + while (ros::ok()) + { + usleep(8 * 1000); + + ros::spin(); + } + + return 0; +} diff --git a/ros/dynamixel_sdk_examples/srv/GetPosition.srv b/ros/dynamixel_sdk_examples/srv/GetPosition.srv new file mode 100644 index 00000000..7441039c --- /dev/null +++ b/ros/dynamixel_sdk_examples/srv/GetPosition.srv @@ -0,0 +1,3 @@ +uint8 id +--- +int32 position