Skip to content

Commit

Permalink
Merge pull request ROBOTIS-GIT#96 from ROBOTIS-GIT/hotfix_feature_pro…
Browse files Browse the repository at this point in the history
…tocol1_0_func_dxl_x_series

hotfix - now DynamixelSDK for protocol1.0 supports read/write 4Byte (for XM series)
  • Loading branch information
LeonJung authored Jul 7, 2017
2 parents 6ab926a + 85c23b9 commit 6ef5d28
Show file tree
Hide file tree
Showing 20 changed files with 97 additions and 36 deletions.
17 changes: 9 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,9 @@
--------------------------------------------------------------------------
| Dynamixel SDK Version | 1.X | 2.X | 3.X ([Download](https://github.com/ROBOTIS-GIT/DynamixelSDK/releases)) |
| ------------- | ------------- | ------------- | ------------- |
| Release date| 2010.05.16 | 2015.02.10 | 2017.05.23 |
| Latest version released |||3.4.5|
| Release date | 2010.05.16 | 2015.02.10 | 2016.03.08 |
| Latest version released |||3.4.6|
| |||(2017.07.07)|
| OS | Linux | Windows | Linux + Windows |
||||+ MacOSX (coming soon)|
| Available Dynamixel models | All models | All models | All models |
Expand All @@ -31,19 +32,19 @@
| | | | ROS |
| | | | Arduino (coming soon) |

#####¹ C++ ver. Library is not optimized in binding other languages. Please use C ver. Library instead.
##### ¹ C++ ver. Library is not optimized in binding other languages. Please use C ver. Library instead.
---------------------------------------------------------------------------

* [Quick Start Video](https://github.com/ROBOTIS-GIT/DynamixelSDK/wiki/Quick-Start-Video) may make you run your Dynamixel in 20 minutes.

[![](https://github.com/ROBOTIS-GIT/ROBOTIS-Documents/blob/master/wiki-images/DynamixelSDK/Quick%20Start/Episode%201-Introduction%20to%20the%20Dynamixel%20SDK%2C%20the%20Dynamixel%20SDK%20Wiki%2C%20and%20the%20Issues%20Section.png)](https://github.com/ROBOTIS-GIT/DynamixelSDK/wiki/Quick-Start-Video)

* ####Here we opened [FAQ board](https://github.com/ROBOTIS-GIT/DynamixelSDK/wiki/FAQ). You may get your keys faster!
* #### Here we opened [FAQ board](https://github.com/ROBOTIS-GIT/DynamixelSDK/wiki/FAQ). You may get your keys faster!

* ####But any questions related with DynamixelSDK are always welcomed. Just let me know at: [ISSUES](https://github.com/ROBOTIS-GIT/DynamixelSDK/issues)
* #### But any questions related with DynamixelSDK are always welcomed. Just let me know at: [ISSUES](https://github.com/ROBOTIS-GIT/DynamixelSDK/issues)

* ####For the other questions, including Hardware-wise problems on your Dynamixels, please contact to [email protected]
* #### For the other questions, including Hardware-wise problems on your Dynamixels, please contact to [email protected]

* ####See 'How to use' in [Dynamixel SDK Manual](https://github.com/ROBOTIS-GIT/DynamixelSDK/wiki)
* #### See 'How to use' in [Dynamixel SDK Manual](https://github.com/ROBOTIS-GIT/DynamixelSDK/wiki)

* ####Visit [ROBOTIS E-Manual](http://support.robotis.com/) and have details of ROBOTIS products
* #### Visit [ROBOTIS E-Manual](http://support.robotis.com/) and have details of ROBOTIS products
42 changes: 29 additions & 13 deletions ReleaseNote.txt
Original file line number Diff line number Diff line change
@@ -1,26 +1,42 @@
==============================================
Dynamixel SDK v3.4.4 (Protocol 1.0/2.0)
Dynamixel SDK 3.4.6 (Protocol 1.0/2.0)
==============================================

- 07.07.2017

* hotfix - now DynamixelSDK for protocol1.0 supports read/write 4Byte (for XM series)

==============================================
Dynamixel SDK 3.4.5 (Protocol 1.0/2.0)
==============================================

- 05.23.2017

* Merge branch 'kinetic-devel' of github.com:ROBOTIS-GIT/DynamixelSDK into kinetic-devel

==============================================
Dynamixel SDK 3.4.4 (Protocol 1.0/2.0)
==============================================

- 04.26.2017

* hotfix - return delay time is changed from 4 into 8 due to the Ubuntu update 16.04.2

==============================================
Dynamixel SDK v3.4.3 (Protocol 1.0/2.0)
Dynamixel SDK 3.4.3 (Protocol 1.0/2.0)
==============================================

- 02.17.2017

* DynamixelSDK C++ ver. and ROS ver. in Windows platform now can use the port number of over then 10 #45

==============================================
Dynamixel SDK v3.4.2 (Protocol 1.0/2.0)
Dynamixel SDK 3.4.2 (Protocol 1.0/2.0)
==============================================

- 02.16.2017

* fprintf output in GrouBulkRead of C++ removed
* fprintf output in GroupBulkRead of C++ removed
* MATLAB library compiler error solving
* Makefile for build example sources in SBC added
* build files of windows c and c++ SDK rebuilt by using renewed SDK libraries
Expand All @@ -29,7 +45,7 @@
* Solved issue : #31, #34, #36, #50

==============================================
Dynamixel SDK v3.4.1 (Protocol 1.0/2.0)
Dynamixel SDK 3.4.1 (Protocol 1.0/2.0)
==============================================

- 08.22.2016
Expand All @@ -38,15 +54,15 @@
* Modified c++'s original header files for ROS package

==============================================
Dynamixel SDK v3.4.0 (Protocol 1.0/2.0)
Dynamixel SDK 3.4.0 (Protocol 1.0/2.0)
==============================================

- 08.12.2016

* Added a ROS package information for ROS users

==============================================
Dynamixel SDK v3.3.3 (Protocol 1.0/2.0)
Dynamixel SDK 3.3.3 (Protocol 1.0/2.0)
==============================================

- 08.03.2016
Expand All @@ -63,7 +79,7 @@


==============================================
Dynamixel SDK v3.3.2 (Protocol 1.0/2.0)
Dynamixel SDK 3.3.2 (Protocol 1.0/2.0)
==============================================

- 06.30.2016
Expand All @@ -73,7 +89,7 @@
* Solved issue : #3, #8

==============================================
Dynamixel SDK v3.3.1 (Protocol 1.0/2.0)
Dynamixel SDK 3.3.1 (Protocol 1.0/2.0)
==============================================

- 06.30.2016
Expand All @@ -83,7 +99,7 @@
* Solved issue : #3, #8

==============================================
Dynamixel SDK v3.3.0 (Protocol 1.0/2.0)
Dynamixel SDK 3.3.0 (Protocol 1.0/2.0)
==============================================

- 06.28.2016
Expand All @@ -98,7 +114,7 @@
* Solved issue : #3, #8

==============================================
Dynamixel SDK v3.2.0 (Protocol 1.0/2.0)
Dynamixel SDK 3.2.0 (Protocol 1.0/2.0)
==============================================

- 06.07.2016
Expand All @@ -109,7 +125,7 @@
* Solved issue : #3

==============================================
Dynamixel SDK v3.1.0 (Protocol 1.0/2.0)
Dynamixel SDK 3.1.0 (Protocol 1.0/2.0)
==============================================

- 05.31.2016
Expand All @@ -121,7 +137,7 @@
* Solved issue : #3

==============================================
Dynamixel SDK v3.0.0 (Protocol 1.0/2.0)
Dynamixel SDK 3.0.0 (Protocol 1.0/2.0)
==============================================

- 03.08.2016
Expand Down
Binary file modified c++/build/win32/.vs/dxl_x86_cpp/v14/.suo
Binary file not shown.
Binary file modified c++/build/win32/output/dxl_x86_cpp.dll
Binary file not shown.
Binary file modified c++/build/win32/output/dxl_x86_cpp.lib
Binary file not shown.
Binary file modified c++/build/win64/.vs/dxl_x64_cpp/v14/.suo
Binary file not shown.
Binary file modified c++/build/win64/output/dxl_x64_cpp.dll
Binary file not shown.
Binary file modified c++/build/win64/output/dxl_x64_cpp.lib
Binary file not shown.
20 changes: 15 additions & 5 deletions c++/src/dynamixel_sdk/protocol1_packet_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -517,15 +517,23 @@ int Protocol1PacketHandler::read2ByteTxRx(PortHandler *port, uint8_t id, uint16_

int Protocol1PacketHandler::read4ByteTx(PortHandler *port, uint8_t id, uint16_t address)
{
return COMM_NOT_AVAILABLE;
return readTx(port, id, address, 4);
}
int Protocol1PacketHandler::read4ByteRx(PortHandler *port, uint32_t *data, uint8_t *error)
{
return COMM_NOT_AVAILABLE;
uint8_t data_read[4] = {0};
int result = readRx(port, 4, data_read, error);
if (result == COMM_SUCCESS)
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
return result;
}
int Protocol1PacketHandler::read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error)
{
return COMM_NOT_AVAILABLE;
uint8_t data_read[4] = {0};
int result = readTxRx(port, id, address, 4, data_read, error);
if (result == COMM_SUCCESS)
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
return result;
}

int Protocol1PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
Expand Down Expand Up @@ -600,11 +608,13 @@ int Protocol1PacketHandler::write2ByteTxRx(PortHandler *port, uint8_t id, uint16

int Protocol1PacketHandler::write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data)
{
return COMM_NOT_AVAILABLE;
uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
return writeTxOnly(port, id, address, 4, data_write);
}
int Protocol1PacketHandler::write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error)
{
return COMM_NOT_AVAILABLE;
uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
return writeTxRx(port, id, address, 4, data_write, error);
}

int Protocol1PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
Expand Down
Binary file modified c/build/win32/.vs/dxl_x86_c/v14/.suo
Binary file not shown.
Binary file modified c/build/win32/output/dxl_x86_c.dll
Binary file not shown.
Binary file modified c/build/win32/output/dxl_x86_c.lib
Binary file not shown.
Binary file modified c/build/win64/.vs/dxl_x64_c/v14/.suo
Binary file not shown.
Binary file modified c/build/win64/output/dxl_x64_c.dll
Binary file not shown.
Binary file modified c/build/win64/output/dxl_x64_c.lib
Binary file not shown.
Binary file modified c/example/protocol1.0/read_write/win32/.vs/read_write/v14/.suo
Binary file not shown.
Binary file not shown.
Binary file modified c/example/protocol1.0/sync_write/win32/.vs/sync_write/v14/.suo
Binary file not shown.
34 changes: 29 additions & 5 deletions c/src/dynamixel_sdk/protocol1_packet_handler.c
Original file line number Diff line number Diff line change
Expand Up @@ -577,16 +577,30 @@ uint16_t read2ByteTxRx1(int port_num, uint8_t id, uint16_t address)

void read4ByteTx1(int port_num, uint8_t id, uint16_t address)
{
packetData[port_num].communication_result = COMM_NOT_AVAILABLE;
readTx1(port_num, id, address, 4);
}
uint32_t read4ByteRx1(int port_num)
{
packetData[port_num].communication_result = COMM_NOT_AVAILABLE;
packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 4 * sizeof(uint8_t));
packetData[port_num].data_read[0] = 0;
packetData[port_num].data_read[1] = 0;
packetData[port_num].data_read[2] = 0;
packetData[port_num].data_read[3] = 0;
readRx1(port_num, 4);
if (packetData[port_num].communication_result == COMM_SUCCESS)
return DXL_MAKEDWORD(DXL_MAKEWORD(packetData[port_num].data_read[0], packetData[port_num].data_read[1]), DXL_MAKEWORD(packetData[port_num].data_read[2], packetData[port_num].data_read[3]));
return 0;
}
uint32_t read4ByteTxRx1(int port_num, uint8_t id, uint16_t address)
{
packetData[port_num].communication_result = COMM_NOT_AVAILABLE;
packetData[port_num].data_read = (uint8_t *)realloc(packetData[port_num].data_read, 4 * sizeof(uint8_t));
packetData[port_num].data_read[0] = 0;
packetData[port_num].data_read[1] = 0;
packetData[port_num].data_read[2] = 0;
packetData[port_num].data_read[3] = 0;
readTxRx1(port_num, id, address, 4);
if (packetData[port_num].communication_result == COMM_SUCCESS)
return DXL_MAKEDWORD(DXL_MAKEWORD(packetData[port_num].data_read[0], packetData[port_num].data_read[1]), DXL_MAKEWORD(packetData[port_num].data_read[2], packetData[port_num].data_read[3]));
return 0;
}

Expand Down Expand Up @@ -664,11 +678,21 @@ void write2ByteTxRx1(int port_num, uint8_t id, uint16_t address, uint16_t data)

void write4ByteTxOnly1(int port_num, uint8_t id, uint16_t address, uint32_t data)
{
packetData[port_num].communication_result = COMM_NOT_AVAILABLE;
packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 4 * sizeof(uint8_t));
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));
packetData[port_num].data_write[3] = DXL_HIBYTE(DXL_HIWORD(data));
writeTxOnly1(port_num, id, address, 4);
}
void write4ByteTxRx1(int port_num, uint8_t id, uint16_t address, uint32_t data)
{
packetData[port_num].communication_result = COMM_NOT_AVAILABLE;
packetData[port_num].data_write = (uint8_t *)realloc(packetData[port_num].data_write, 4 * sizeof(uint8_t));
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));
packetData[port_num].data_write[3] = DXL_HIBYTE(DXL_HIWORD(data));
writeTxRx1(port_num, id, address, 4);
}

void regWriteTxOnly1(int port_num, uint8_t id, uint16_t address, uint16_t length)
Expand Down
20 changes: 15 additions & 5 deletions ros/src/protocol1_packet_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -523,15 +523,23 @@ int Protocol1PacketHandler::read2ByteTxRx(PortHandler *port, uint8_t id, uint16_

int Protocol1PacketHandler::read4ByteTx(PortHandler *port, uint8_t id, uint16_t address)
{
return COMM_NOT_AVAILABLE;
return readTx(port, id, address, 4);
}
int Protocol1PacketHandler::read4ByteRx(PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error)
{
return COMM_NOT_AVAILABLE;
uint8_t data_read[4] = {0};
int result = readRx(port, id, 4, data_read, error);
if (result == COMM_SUCCESS)
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
return result;
}
int Protocol1PacketHandler::read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error)
{
return COMM_NOT_AVAILABLE;
uint8_t data_read[4] = {0};
int result = readTxRx(port, id, address, 4, data_read, error);
if (result == COMM_SUCCESS)
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
return result;
}

int Protocol1PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
Expand Down Expand Up @@ -606,11 +614,13 @@ int Protocol1PacketHandler::write2ByteTxRx(PortHandler *port, uint8_t id, uint16

int Protocol1PacketHandler::write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data)
{
return COMM_NOT_AVAILABLE;
uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
return writeTxOnly(port, id, address, 4, data_write);
}
int Protocol1PacketHandler::write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error)
{
return COMM_NOT_AVAILABLE;
uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
return writeTxRx(port, id, address, 4, data_write, error);
}

int Protocol1PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
Expand Down

0 comments on commit 6ef5d28

Please sign in to comment.