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_
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"
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"
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
5450namespace 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
0 commit comments