Skip to content

Commit 61617b3

Browse files
[JTC] Parse URDF for continuous joints (#949)
1 parent 7d38fb9 commit 61617b3

File tree

9 files changed

+360
-32
lines changed

9 files changed

+360
-32
lines changed

joint_trajectory_controller/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1919
rsl
2020
tl_expected
2121
trajectory_msgs
22+
urdf
2223
)
2324

2425
find_package(ament_cmake REQUIRED)

joint_trajectory_controller/doc/parameters_context.yaml

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,5 +9,10 @@ gains: |
99
1010
.. math:: u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
1111
12-
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see ``angle_wraparound`` below),
12+
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see below),
1313
the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively.
14+
15+
If the joint is of continuous type, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`,
16+
i.e., the shortest rotation to the target position is the desired motion.
17+
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
18+
position :math:`s` from the state interface.

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include "realtime_tools/realtime_server_goal_handle.h"
4444
#include "trajectory_msgs/msg/joint_trajectory.hpp"
4545
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
46+
#include "urdf/model.h"
4647

4748
// auto-generated by generate_parameter_library
4849
#include "joint_trajectory_controller_parameters.hpp"
@@ -298,6 +299,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
298299
void resize_joint_trajectory_point_command(
299300
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
300301

302+
urdf::Model model_;
303+
301304
/**
302305
* @brief Assigns the values from a trajectory point interface to a joint interface.
303306
*

joint_trajectory_controller/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
<depend>rsl</depend>
2626
<depend>tl_expected</depend>
2727
<depend>trajectory_msgs</depend>
28+
<depend>urdf</depend>
2829

2930
<test_depend>ament_cmake_gmock</test_depend>
3031
<test_depend>controller_manager</test_depend>

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 41 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
#include "rclcpp_action/create_server.hpp"
3737
#include "rclcpp_action/server_goal_handle.hpp"
3838
#include "rclcpp_lifecycle/state.hpp"
39+
#include "urdf/model.h"
3940

4041
namespace joint_trajectory_controller
4142
{
@@ -46,6 +47,23 @@ JointTrajectoryController::JointTrajectoryController()
4647

4748
controller_interface::CallbackReturn JointTrajectoryController::on_init()
4849
{
50+
if (!urdf_.empty())
51+
{
52+
if (!model_.initString(urdf_))
53+
{
54+
RCLCPP_ERROR(get_node()->get_logger(), "Failed to parse URDF file");
55+
}
56+
else
57+
{
58+
RCLCPP_DEBUG(get_node()->get_logger(), "Successfully parsed URDF file");
59+
}
60+
}
61+
else
62+
{
63+
// empty URDF is used for some tests
64+
RCLCPP_DEBUG(get_node()->get_logger(), "No URDF file given");
65+
}
66+
4967
try
5068
{
5169
// Create the parameter listener and get the parameters
@@ -684,12 +702,33 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
684702
update_pids();
685703
}
686704

687-
// Configure joint position error normalization from ROS parameters (angle_wraparound)
705+
// Configure joint position error normalization (angle_wraparound)
688706
joints_angle_wraparound_.resize(dof_);
689707
for (size_t i = 0; i < dof_; ++i)
690708
{
691709
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
692-
joints_angle_wraparound_[i] = gains.angle_wraparound;
710+
if (gains.angle_wraparound)
711+
{
712+
// TODO(christophfroehlich): remove this warning in a future release (ROS-J)
713+
RCLCPP_WARN(
714+
logger,
715+
"[Deprecated] Parameter 'gains.<joint>.angle_wraparound' is deprecated. The "
716+
"angle_wraparound is now used if a continuous joint is configured in the URDF.");
717+
joints_angle_wraparound_[i] = true;
718+
}
719+
720+
if (!urdf_.empty())
721+
{
722+
auto urdf_joint = model_.getJoint(params_.joints[i]);
723+
if (urdf_joint && urdf_joint->type == urdf::Joint::CONTINUOUS)
724+
{
725+
RCLCPP_DEBUG(
726+
logger, "joint '%s' is of type continuous, use angle_wraparound.",
727+
params_.joints[i].c_str());
728+
joints_angle_wraparound_[i] = true;
729+
}
730+
// do nothing if joint is not found in the URDF
731+
}
693732
}
694733

695734
if (params_.state_interfaces.empty())

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -125,11 +125,8 @@ joint_trajectory_controller:
125125
angle_wraparound: {
126126
type: bool,
127127
default_value: false,
128-
description: 'For joints that wrap around (without end stop, ie. are continuous),
129-
where the shortest rotation to the target position is the desired motion.
130-
If true, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`.
131-
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
132-
position :math:`s` from the state interface.'
128+
description: "[deprecated] For joints that wrap around (ie. are continuous).
129+
Normalizes position-error to -pi to pi."
133130
}
134131
constraints:
135132
stopped_velocity_tolerance: {

0 commit comments

Comments
 (0)