Skip to content

Commit e7fe8aa

Browse files
authored
Merge pull request #38 from ROBOTIS-GIT/feature-command-interfaces
Add Support for Various Command Interfaces
2 parents 541632c + 307e1fe commit e7fe8aa

File tree

11 files changed

+1179
-345
lines changed

11 files changed

+1179
-345
lines changed

CHANGELOG.rst

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,17 @@
22
Changelog for package dynamixel_hardware_interface
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
1.4.4 (2025-05-28)
6+
------------------
7+
* Added proper command interface support with ROS2-Dynamixel interface mapping
8+
* Improved error handling and robustness throughout the codebase
9+
* Implemented per-device torque enable control (replacing global control)
10+
* Added support for new sensor model (sensorxel_joy)
11+
* Enhanced joint state-command synchronization
12+
* Improved parameter initialization organization
13+
* Added robust error handling for model file reading
14+
* Contributors: Woojin Wie
15+
516
1.4.3 (2025-04-10)
617
------------------
718
* Fixed build errors

include/dynamixel_hardware_interface/dynamixel/dynamixel.hpp

Lines changed: 41 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414
//
15-
// Authors: Hye-Jong KIM, Sungho Woo
15+
// Authors: Hye-Jong KIM, Sungho Woo, Woojin Wie
1616

1717
#ifndef DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL__DYNAMIXEL_HPP_
1818
#define DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL__DYNAMIXEL_HPP_
@@ -110,8 +110,8 @@ class Dynamixel
110110
{
111111
private:
112112
// dxl communication variable
113-
dynamixel::PortHandler * port_handler_;
114-
dynamixel::PacketHandler * packet_handler_;
113+
dynamixel::PortHandler * port_handler_ = nullptr;
114+
dynamixel::PacketHandler * packet_handler_ = nullptr;
115115

116116
// dxl info variable from dxl_model file
117117
DynamixelInfo dxl_info_;
@@ -126,24 +126,35 @@ class Dynamixel
126126
std::vector<RWItemList> read_data_list_;
127127

128128
// sync read
129-
dynamixel::GroupFastSyncRead * group_sync_read_;
129+
dynamixel::GroupSyncRead * group_sync_read_ = nullptr;
130+
// bulk read
131+
dynamixel::GroupBulkRead * group_bulk_read_ = nullptr;
132+
// fast sync read
133+
dynamixel::GroupFastSyncRead * group_fast_sync_read_ = nullptr;
134+
// fast bulk read
135+
dynamixel::GroupFastBulkRead * group_fast_bulk_read_ = nullptr;
136+
137+
// fast read protocol state (applies to both sync and bulk)
138+
bool use_fast_read_protocol_ = true;
139+
bool fast_read_permanent_ = false;
140+
int fast_read_fail_count_ = 0;
141+
130142
// indirect inform for sync read
131143
std::map<uint8_t /*id*/, IndirectInfo> indirect_info_read_;
132144

133-
// bulk read
134-
dynamixel::GroupFastBulkRead * group_bulk_read_;
135-
136145
// write item (sync or bulk) variable
137146
bool write_type_;
138147
std::vector<RWItemList> write_data_list_;
139148

140149
// sync write
141-
dynamixel::GroupSyncWrite * group_sync_write_;
150+
dynamixel::GroupSyncWrite * group_sync_write_ = nullptr;
142151
// indirect inform for sync write
143152
std::map<uint8_t /*id*/, IndirectInfo> indirect_info_write_;
144153

145154
// bulk write
146-
dynamixel::GroupBulkWrite * group_bulk_write_;
155+
dynamixel::GroupBulkWrite * group_bulk_write_ = nullptr;
156+
// direct inform for bulk write
157+
std::map<uint8_t /*id*/, IndirectInfo> direct_info_write_;
147158

148159
public:
149160
explicit Dynamixel(const char * path);
@@ -202,11 +213,19 @@ class Dynamixel
202213
DxlError SetSyncReadItemAndHandler();
203214
DxlError SetSyncReadHandler(std::vector<uint8_t> id_arr);
204215
DxlError GetDxlValueFromSyncRead(double period_ms);
216+
DxlError SetFastSyncReadHandler(std::vector<uint8_t> id_arr);
205217

206218
// BulkRead
207219
DxlError SetBulkReadItemAndHandler();
208220
DxlError SetBulkReadHandler(std::vector<uint8_t> id_arr);
209221
DxlError GetDxlValueFromBulkRead(double period_ms);
222+
DxlError SetFastBulkReadHandler(std::vector<uint8_t> id_arr);
223+
224+
// DirectRead for BulkRead
225+
DxlError AddDirectRead(uint8_t id, std::string item_name, uint16_t item_addr, uint8_t item_size);
226+
227+
// Check Indirect Read
228+
DxlError CheckIndirectReadAvailable(uint8_t id);
210229

211230
// Read - Indirect Address
212231
void ResetIndirectRead(std::vector<uint8_t> id_arr);
@@ -225,13 +244,19 @@ class Dynamixel
225244
const std::vector<std::shared_ptr<double>> & data_ptrs,
226245
std::function<uint32_t(uint8_t, uint16_t, uint8_t)> get_data_func);
227246

247+
DxlError ProcessDirectReadData(
248+
uint8_t id,
249+
const std::vector<uint16_t> & item_addrs,
250+
const std::vector<uint8_t> & item_sizes,
251+
const std::vector<std::shared_ptr<double>> & data_ptrs,
252+
std::function<uint32_t(uint8_t, uint16_t, uint8_t)> get_data_func);
253+
228254
// Read - Communication
229255
DxlError ProcessReadCommunication(
230-
dynamixel::GroupFastSyncRead * group_sync_read,
231-
dynamixel::GroupFastBulkRead * group_bulk_read,
232256
dynamixel::PortHandler * port_handler,
233257
double period_ms,
234-
bool is_sync);
258+
bool is_sync,
259+
bool is_fast);
235260

236261
// SyncWrite
237262
DxlError SetSyncWriteItemAndHandler();
@@ -243,8 +268,12 @@ class Dynamixel
243268
DxlError SetBulkWriteHandler(std::vector<uint8_t> id_arr);
244269
DxlError SetDxlValueToBulkWrite();
245270

271+
// Check Indirect Write
272+
DxlError CheckIndirectWriteAvailable(uint8_t id);
273+
246274
// Write - Indirect Address
247275
void ResetIndirectWrite(std::vector<uint8_t> id_arr);
276+
void ResetDirectWrite(std::vector<uint8_t> id_arr);
248277
DxlError AddIndirectWrite(
249278
uint8_t id,
250279
std::string item_name,

include/dynamixel_hardware_interface/dynamixel/dynamixel_info.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414
//
15-
// Authors: Hye-Jong KIM, Sungho Woo
15+
// Authors: Hye-Jong KIM, Sungho Woo, Woojin Wie
1616

1717
#ifndef DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL__DYNAMIXEL_INFO_HPP_
1818
#define DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL__DYNAMIXEL_INFO_HPP_

include/dynamixel_hardware_interface/dynamixel_hardware_interface.hpp

Lines changed: 43 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414
//
15-
// Authors: Hye-Jong KIM, Sungho Woo
15+
// Authors: Hye-Jong KIM, Sungho Woo, Woojin Wie
1616

1717
#ifndef DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL_HARDWARE_INTERFACE_HPP_
1818
#define DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL_HARDWARE_INTERFACE_HPP_
@@ -21,6 +21,8 @@
2121
#include <string>
2222
#include <vector>
2323
#include <map>
24+
#include <unordered_map>
25+
#include <functional>
2426

2527
#include "rclcpp/rclcpp.hpp"
2628
#include "ament_index_cpp/get_package_share_directory.hpp"
@@ -29,6 +31,7 @@
2931
#include "hardware_interface/hardware_info.hpp"
3032
#include "hardware_interface/system_interface.hpp"
3133
#include "hardware_interface/types/hardware_interface_return_values.hpp"
34+
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3235

3336
#include "dynamixel_hardware_interface/visibility_control.h"
3437
#include "dynamixel_hardware_interface/dynamixel/dynamixel.hpp"
@@ -43,13 +46,6 @@
4346

4447
#include "std_srvs/srv/set_bool.hpp"
4548

46-
#define PRESENT_POSITION_INDEX 0
47-
#define PRESENT_VELOCITY_INDEX 1
48-
#define PRESENT_EFFORT_INDEX 2
49-
50-
#define GOAL_POSITION_INDEX 0
51-
// #define GOAL_VELOCITY_INDEX 1 // TODO: to be implemented
52-
#define GOAL_CURRENT_INDEX 1
5349

5450
namespace dynamixel_hardware_interface
5551
{
@@ -185,14 +181,13 @@ class DynamixelHardware : public
185181
std::map<uint8_t /*id*/, uint8_t /*err*/> dxl_hw_err_;
186182
DxlTorqueStatus dxl_torque_status_;
187183
std::map<uint8_t /*id*/, bool /*enable*/> dxl_torque_state_;
184+
std::map<uint8_t /*id*/, bool /*enable*/> dxl_torque_enable_;
188185
double err_timeout_ms_;
189186
rclcpp::Duration read_error_duration_{0, 0};
190187
rclcpp::Duration write_error_duration_{0, 0};
191188
bool is_read_in_error_{false};
192189
bool is_write_in_error_{false};
193190

194-
bool global_torque_enable_{true};
195-
196191
bool use_revolute_to_prismatic_{false};
197192
std::string conversion_dxl_name_{""};
198193
std::string conversion_joint_name_{""};
@@ -229,7 +224,6 @@ class DynamixelHardware : public
229224
bool CommReset();
230225

231226
///// dxl variable
232-
std::shared_ptr<Dynamixel> dxl_comm_;
233227
std::string port_name_;
234228
std::string baud_rate_;
235229
std::vector<uint8_t> dxl_id_;
@@ -250,6 +244,9 @@ class DynamixelHardware : public
250244
std::vector<HandlerVarType> hdl_gpio_sensor_states_;
251245
std::vector<HandlerVarType> hdl_sensor_states_;
252246

247+
///// handler controller variable
248+
std::vector<HandlerVarType> hdl_gpio_controller_commands_;
249+
253250
bool is_set_hdl_{false};
254251

255252
// joint <-> transmission matrix
@@ -360,6 +357,41 @@ class DynamixelHardware : public
360357
double revoluteToPrismatic(double revolute_value);
361358

362359
double prismaticToRevolute(double prismatic_value);
360+
361+
void MapInterfaces(
362+
size_t outer_size,
363+
size_t inner_size,
364+
std::vector<HandlerVarType> & outer_handlers,
365+
const std::vector<HandlerVarType> & inner_handlers,
366+
double ** matrix,
367+
const std::unordered_map<std::string, std::vector<std::string>> & iface_map,
368+
const std::string & conversion_iface = "",
369+
const std::string & conversion_name = "",
370+
std::function<double(double)> conversion = nullptr);
371+
372+
// Move dxl_comm_ to the end for safe destruction order
373+
std::shared_ptr<Dynamixel> dxl_comm_;
374+
};
375+
376+
// Conversion maps between ROS2 and Dynamixel interface names
377+
inline const std::unordered_map<std::string, std::vector<std::string>> ros2_to_dxl_cmd_map = {
378+
{hardware_interface::HW_IF_POSITION, {"Goal Position"}},
379+
{hardware_interface::HW_IF_VELOCITY, {"Goal Velocity"}},
380+
{hardware_interface::HW_IF_EFFORT, {"Goal Current"}}
381+
};
382+
383+
// Mapping for Dynamixel command interface names to ROS2 state interface names
384+
inline const std::unordered_map<std::string, std::vector<std::string>> dxl_to_ros2_cmd_map = {
385+
{"Goal Position", {hardware_interface::HW_IF_POSITION}},
386+
{"Goal Velocity", {hardware_interface::HW_IF_VELOCITY}},
387+
{"Goal Current", {hardware_interface::HW_IF_EFFORT}}
388+
};
389+
390+
// Mapping for ROS2 state interface names to Dynamixel state interface names
391+
inline const std::unordered_map<std::string, std::vector<std::string>> ros2_to_dxl_state_map = {
392+
{hardware_interface::HW_IF_POSITION, {"Present Position"}},
393+
{hardware_interface::HW_IF_VELOCITY, {"Present Velocity"}},
394+
{hardware_interface::HW_IF_EFFORT, {"Present Current", "Present Load"}}
363395
};
364396

365397
} // namespace dynamixel_hardware_interface

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>dynamixel_hardware_interface</name>
5-
<version>1.4.3</version>
5+
<version>1.4.4</version>
66
<description>
77
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
88
</description>

param/dxl_model/dynamixel.model

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,3 +46,5 @@ Number Name
4646
35074 rh_p12_rn.model
4747
220 omy_hat.model
4848
230 omy_end.model
49+
536 sensorxel_joy.model
50+
600 sensorxel_joy.model

param/dxl_model/ph42_020_s300.model

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,9 @@ Address Size Data Name
6262
592 2 Present Input Voltage
6363
594 1 Present Temperature
6464
878 1 Backup Ready
65+
168 2 Indirect Address 1
66+
634 1 Indirect Data 1
6567
168 2 Indirect Address Write
6668
634 1 Indirect Data Write
67-
350 2 Indirect Address Read
69+
296 2 Indirect Address Read
6870
698 1 Indirect Data Read
Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
[control table]
2+
Address Size Data Name
3+
0 2 Model Number
4+
2 1 ROBOT_Generation
5+
3 1 Board_Number
6+
5 1 Firmware_Version_Major
7+
6 1 Firmware_Version_Minor
8+
7 1 ID
9+
8 1 Baud Rate
10+
10 1 Boot_Version_Major
11+
11 1 Boot_Version_MInor
12+
12 4 Error_Code
13+
20 4 Micros
14+
24 4 Millis
15+
28 1 JOYSTICK TACT SWITCH
16+
29 2 JOYSTICK X VALUE
17+
31 2 JOYSTICK Y VALUE
18+
40 2 IMU ACC X
19+
42 2 IMU ACC Y
20+
44 2 IMU ACC Z
21+
46 2 IMU ACC SUM

0 commit comments

Comments
 (0)