Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,8 @@ $ . install/setup.bash

### Configure Dynamixel motor parameters

Update the `usb_port`, `baud_rate`, and `joint_ids` parameters on [`open_manipulator_x_description/urdf/open_manipulator_x.ros2_control.xacro`](https://github.com/youtalk/dynamixel_control/blob/main/open_manipulator_x_description/urdf/open_manipulator_x.ros2_control.xacro#L9-L12) to correctly communicate with Dynamixel motors.
Update the `usb_port`, `baud_rate`, `return_delay_time` and `joint_ids` parameters on [`open_manipulator_x_description/urdf/open_manipulator_x.ros2_control.xacro`](https://github.com/youtalk/dynamixel_control/blob/main/open_manipulator_x_description/urdf/open_manipulator_x.ros2_control.xacro#L9-L12) to correctly communicate with Dynamixel motors.
The `return_delay_time` sets the amount of delay in microseconds before they respond to a packet.
The `use_dummy` parameter is required if you don't have a real OpenManipulator-X.

Note that `joint_ids` parameters must be splited by `,`.
Expand All @@ -35,6 +36,7 @@ Note that `joint_ids` parameters must be splited by `,`.
<plugin>dynamixel_hardware/DynamixelHardware</plugin>
<param name="usb_port">/dev/ttyUSB0</param>
<param name="baud_rate">1000000</param>
<param name="return_delay_time">10</param>
<!-- <param name="use_dummy">true</param> -->
</hardware>
```
Expand Down Expand Up @@ -86,6 +88,7 @@ index c6cdb74..111846d 100644
@@ -9,7 +9,7 @@
<param name="usb_port">/dev/ttyUSB0</param>
<param name="baud_rate">1000000</param>
<param name="return_delay_time">250</param>
- <!-- <param name="use_dummy">true</param> -->
+ <param name="use_dummy">true</param>
</hardware>
Expand Down
13 changes: 13 additions & 0 deletions dynamixel_hardware/src/dynamixel_hardware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ constexpr const char * kPresentVelocityItem = "Present_Velocity";
constexpr const char * kPresentSpeedItem = "Present_Speed";
constexpr const char * kPresentCurrentItem = "Present_Current";
constexpr const char * kPresentLoadItem = "Present_Load";
constexpr const char * kReturnDelayTimeItem = "Return_Delay_Time";
constexpr const char * const kExtraJointParameters[] = {
"Profile_Velocity",
"Profile_Acceleration",
Expand Down Expand Up @@ -83,10 +84,12 @@ CallbackReturn DynamixelHardware::on_init(const hardware_interface::HardwareInfo

auto usb_port = info_.hardware_parameters.at("usb_port");
auto baud_rate = std::stoi(info_.hardware_parameters.at("baud_rate"));
auto return_delay_time = std::stoi(info_.hardware_parameters.at("return_delay_time"));
const char * log = nullptr;

RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "usb_port: %s", usb_port.c_str());
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "baud_rate: %d", baud_rate);
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "return_delay_time: %d", return_delay_time);

if (!dynamixel_workbench_.init(usb_port.c_str(), baud_rate, &log)) {
RCLCPP_FATAL(rclcpp::get_logger(kDynamixelHardware), "%s", log);
Expand All @@ -99,6 +102,16 @@ CallbackReturn DynamixelHardware::on_init(const hardware_interface::HardwareInfo
RCLCPP_FATAL(rclcpp::get_logger(kDynamixelHardware), "%s", log);
return CallbackReturn::ERROR;
}
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "Ping successful for ID %d, Model number: %d", joint_ids_[i], model_number);
int32_t current_return_delay_time = 0;
if (dynamixel_workbench_.itemRead(joint_ids_[i], kReturnDelayTimeItem, &current_return_delay_time, &log) && current_return_delay_time != return_delay_time)
{
if (!dynamixel_workbench_.itemWrite(joint_ids_[i], kReturnDelayTimeItem, return_delay_time, &log)) {
RCLCPP_FATAL(rclcpp::get_logger(kDynamixelHardware), "%s", log);
return CallbackReturn::ERROR;
}
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "Successfully set return delay time for ID %d from %d to %d.", joint_ids_[i], current_return_delay_time, return_delay_time);
}
}

enable_torque(false);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<plugin>dynamixel_hardware/DynamixelHardware</plugin>
<param name="usb_port">/dev/ttyUSB0</param>
<param name="baud_rate">1000000</param>
<param name="return_delay_time">250</param>
<!-- <param name="use_dummy">true</param> -->
</hardware>
<joint name="joint1">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<plugin>dynamixel_hardware/DynamixelHardware</plugin>
<param name="usb_port">/dev/ttyUSB0</param>
<param name="baud_rate">1000000</param>
<param name="return_delay_time">250</param>
<!-- <param name="use_dummy">true</param> -->
</hardware>
<joint name="joint1">
Expand Down