Skip to content

Commit

Permalink
[JTC] Parse URDF for continuous joints (#949)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Mar 2, 2024
1 parent 7d38fb9 commit 61617b3
Show file tree
Hide file tree
Showing 9 changed files with 360 additions and 32 deletions.
1 change: 1 addition & 0 deletions joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
rsl
tl_expected
trajectory_msgs
urdf
)

find_package(ament_cmake REQUIRED)
Expand Down
7 changes: 6 additions & 1 deletion joint_trajectory_controller/doc/parameters_context.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -9,5 +9,10 @@ gains: |
.. math:: u = k_{ff} v_d + k_p e + k_i \sum e dt + k_d (v_d - v)
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see ``angle_wraparound`` below),
with the desired velocity :math:`v_d`, the measured velocity :math:`v`, the position error :math:`e` (definition see below),
the controller period :math:`dt`, and the ``velocity`` or ``effort`` manipulated variable (control variable) :math:`u`, respectively.
If the joint is of continuous type, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`,
i.e., the shortest rotation to the target position is the desired motion.
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
position :math:`s` from the state interface.
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include "realtime_tools/realtime_server_goal_handle.h"
#include "trajectory_msgs/msg/joint_trajectory.hpp"
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
#include "urdf/model.h"

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

urdf::Model model_;

/**
* @brief Assigns the values from a trajectory point interface to a joint interface.
*
Expand Down
1 change: 1 addition & 0 deletions joint_trajectory_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>rsl</depend>
<depend>tl_expected</depend>
<depend>trajectory_msgs</depend>
<depend>urdf</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>controller_manager</test_depend>
Expand Down
43 changes: 41 additions & 2 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include "rclcpp_action/create_server.hpp"
#include "rclcpp_action/server_goal_handle.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "urdf/model.h"

namespace joint_trajectory_controller
{
Expand All @@ -46,6 +47,23 @@ JointTrajectoryController::JointTrajectoryController()

controller_interface::CallbackReturn JointTrajectoryController::on_init()
{
if (!urdf_.empty())
{
if (!model_.initString(urdf_))
{
RCLCPP_ERROR(get_node()->get_logger(), "Failed to parse URDF file");
}
else
{
RCLCPP_DEBUG(get_node()->get_logger(), "Successfully parsed URDF file");
}
}
else
{
// empty URDF is used for some tests
RCLCPP_DEBUG(get_node()->get_logger(), "No URDF file given");
}

try
{
// Create the parameter listener and get the parameters
Expand Down Expand Up @@ -684,12 +702,33 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
update_pids();
}

// Configure joint position error normalization from ROS parameters (angle_wraparound)
// Configure joint position error normalization (angle_wraparound)
joints_angle_wraparound_.resize(dof_);
for (size_t i = 0; i < dof_; ++i)
{
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
joints_angle_wraparound_[i] = gains.angle_wraparound;
if (gains.angle_wraparound)
{
// TODO(christophfroehlich): remove this warning in a future release (ROS-J)
RCLCPP_WARN(
logger,
"[Deprecated] Parameter 'gains.<joint>.angle_wraparound' is deprecated. The "
"angle_wraparound is now used if a continuous joint is configured in the URDF.");
joints_angle_wraparound_[i] = true;
}

if (!urdf_.empty())
{
auto urdf_joint = model_.getJoint(params_.joints[i]);
if (urdf_joint && urdf_joint->type == urdf::Joint::CONTINUOUS)
{
RCLCPP_DEBUG(
logger, "joint '%s' is of type continuous, use angle_wraparound.",
params_.joints[i].c_str());
joints_angle_wraparound_[i] = true;
}
// do nothing if joint is not found in the URDF
}
}

if (params_.state_interfaces.empty())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -125,11 +125,8 @@ joint_trajectory_controller:
angle_wraparound: {
type: bool,
default_value: false,
description: 'For joints that wrap around (without end stop, ie. are continuous),
where the shortest rotation to the target position is the desired motion.
If true, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`.
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
position :math:`s` from the state interface.'
description: "[deprecated] For joints that wrap around (ie. are continuous).
Normalizes position-error to -pi to pi."
}
constraints:
stopped_velocity_tolerance: {
Expand Down
Loading

0 comments on commit 61617b3

Please sign in to comment.