Skip to content
Merged
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
44 changes: 28 additions & 16 deletions .github/workflows/ros-ci.yml
Original file line number Diff line number Diff line change
@@ -1,45 +1,57 @@
name: ros-ci
# The name of the workflow
name: CI

# Controls when the action will run. Triggers the workflow on push or pull request
# Specifies the events that trigger the workflow
on:
push:
branches: [ humble ]
branches: [ main, humble, jazzy ]
pull_request:
branches: [ humble ]
branches: [ main, humble, jazzy ]

# A workflow run is made up of one or more jobs that can run sequentially or in parallel
# Defines a set of jobs to be run as part of the workflow
jobs:
humble:
# The name of the job
ROS_CI:
runs-on: ubuntu-22.04
strategy:
fail-fast: false
matrix:
ros_distribution:
- humble
- jazzy
- rolling
include:
# ROS 2 Humble Hawksbill
- docker_image: ubuntu:jammy
ros_distribution: humble
ros_version: 2
# # Rolling
# - docker_image: ubuntu:jammy
# ros_distribution: rolling
# ros_version: 2
# ROS 2 Jazzy Jalisco
- docker_image: ubuntu:noble
ros_distribution: jazzy
ros_version: 2
# ROS 2 Rolling Ridley
- docker_image: ubuntu:noble
ros_distribution: rolling
ros_version: 2
container:
image: ${{ matrix.docker_image }}
steps:
- name: Setup directories
- name: Setup workspace
run: mkdir -p ros_ws/src
- name: checkout
uses: actions/checkout@v3

- name: Checkout code
uses: actions/checkout@v4
with:
path: ros_ws/src

- name: Setup ROS environment
uses: ros-tooling/setup-ros@0.7.1
uses: ros-tooling/setup-ros@v0.7
with:
required-ros-distributions: ${{ matrix.ros_distribution }}

- name: Build and Test
uses: ros-tooling/action-ros-ci@0.3.5
uses: ros-tooling/action-ros-ci@v0.3
with:
package-name: dynamixel_hardware_interface
target-ros2-distro: ${{ matrix.ros_distribution }}
vcs-repo-file-url: "https://raw.githubusercontent.com/ROBOTIS-GIT/dynamixel_hardware_interface/main/dynamixel_hardware_interface_ci.repos"
package-name: dynamixel_hardware_interface
32 changes: 32 additions & 0 deletions .github/workflows/ros-lint.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
# The name of the workflow
name: Lint

# Specifies the events that trigger the workflow
on:
pull_request:

# Defines a set of jobs to be run as part of the workflow
jobs:
ament_lint:
runs-on: ubuntu-latest
container:
image: rostooling/setup-ros-docker:ubuntu-noble-ros-rolling-ros-base-latest
strategy:
fail-fast: false
matrix:
linter: [cppcheck, cpplint, uncrustify, flake8, pep257, lint_cmake, xmllint, copyright]
steps:
- name: Checkout code
uses: actions/checkout@v4

- name: Setup ROS environment
uses: ros-tooling/[email protected]

- name: Run Linter
env:
AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS: 1
uses: ros-tooling/action-ros-lint@master
with:
linter: ${{ matrix.linter }}
distribution: rolling
package-name: "*"
7 changes: 7 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@
Changelog for package dynamixel_hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.3.0 (2025-02-17)
------------------
* Enhance Error Handling and Timeout Management
* Use GroupFastSyncRead and GroupFastBulkRead
* Remove deprecated parameter ros_update_freq_ to prevent stoi failure
* Contributors: Woojin Wie

1.2.0 (2025-01-17)
------------------
* Extend Bulk/Sync Selection Logic to Include Indirect Operations
Expand Down
4 changes: 2 additions & 2 deletions dynamixel_hardware_interface_ci.repos
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@ repositories:
utils/DynamixelSDK:
type: git
url: https://github.com/ROBOTIS-GIT/DynamixelSDK.git
version: humble
version: main
dynamixel_hardware_interface/dynamixel_interfaces:
type: git
url: https://github.com/ROBOTIS-GIT/dynamixel_interfaces.git
version: humble
version: main
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
#include "dynamixel_interfaces/srv/set_data_to_dxl.hpp"
#include "dynamixel_interfaces/srv/reboot_dxl.hpp"

#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.hpp"
#include "realtime_tools/realtime_buffer.hpp"

#include "std_srvs/srv/set_bool.hpp"

Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version='1.0' encoding='UTF-8'?>
<package format="3">
<name>dynamixel_hardware_interface</name>
<version>1.2.0</version>
<version>1.3.0</version>
<description>
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
</description>
Expand Down
16 changes: 10 additions & 6 deletions src/dynamixel_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,10 @@ hardware_interface::CallbackReturn DynamixelHardware::on_init(
baud_rate_ = info_.hardware_parameters["baud_rate"];
try {
err_timeout_ms_ = stod(info_.hardware_parameters["error_timeout_ms"]);
} catch (const std::exception& e) {
RCLCPP_ERROR(logger_, "Failed to parse error_timeout_ms parameter: %s, using default value", e.what());
} catch (const std::exception & e) {
RCLCPP_ERROR(
logger_, "Failed to parse error_timeout_ms parameter: %s, using default value",
e.what());
}

RCLCPP_INFO_STREAM(
Expand Down Expand Up @@ -405,10 +407,11 @@ hardware_interface::return_type DynamixelHardware::read(
read_error_duration_ = rclcpp::Duration(0, 0);
}
read_error_duration_ = read_error_duration_ + period;

RCLCPP_ERROR_STREAM(
logger_,
"Dynamixel Read Fail (Duration: " << read_error_duration_.seconds() * 1000 << "ms/" << err_timeout_ms_ << "ms)");
"Dynamixel Read Fail (Duration: " << read_error_duration_.seconds() * 1000 << "ms/" <<
err_timeout_ms_ << "ms)");

if (read_error_duration_.seconds() * 1000 >= err_timeout_ms_) {
return hardware_interface::return_type::ERROR;
Expand Down Expand Up @@ -470,10 +473,11 @@ hardware_interface::return_type DynamixelHardware::write(
return hardware_interface::return_type::OK;
} else {
write_error_duration_ = write_error_duration_ + period;

RCLCPP_ERROR_STREAM(
logger_,
"Dynamixel Write Fail (Duration: " << write_error_duration_.seconds() * 1000 << "ms/" << err_timeout_ms_ << "ms)");
"Dynamixel Write Fail (Duration: " << write_error_duration_.seconds() * 1000 << "ms/" <<
err_timeout_ms_ << "ms)");

if (write_error_duration_.seconds() * 1000 >= err_timeout_ms_) {
return hardware_interface::return_type::ERROR;
Expand Down
Loading