Skip to content

Commit 3e907cc

Browse files
authored
[Review Ready] Action server for JointTrajectoryController (ros-navigation#26)
* Action server interface for JointTrajectoryController * trajectory gives linear interpolation of points * update function checks joint tolerances and goals * action server now aborts on path violations * action server succeeds on goal achieved * add action server tests * publish_state publishes state data * implemented hold position on cancellation received * minor rework to trajectory api
1 parent 3dcae47 commit 3e907cc

File tree

11 files changed

+1370
-182
lines changed

11 files changed

+1370
-182
lines changed

joint_trajectory_controller/CMakeLists.txt

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
1111
endif()
1212

1313
find_package(ament_cmake REQUIRED)
14+
find_package(angles REQUIRED)
1415
find_package(controller_interface REQUIRED)
1516
find_package(control_msgs REQUIRED)
1617
find_package(hardware_interface REQUIRED)
@@ -27,6 +28,7 @@ add_library(joint_trajectory_controller SHARED
2728
)
2829
target_include_directories(joint_trajectory_controller PRIVATE include)
2930
ament_target_dependencies(joint_trajectory_controller
31+
angles
3032
builtin_interfaces
3133
controller_interface
3234
control_msgs
@@ -40,7 +42,8 @@ ament_target_dependencies(joint_trajectory_controller
4042
)
4143
# Causes the visibility macros to use dllexport rather than dllimport,
4244
# which is appropriate when building the dll but not consuming it.
43-
target_compile_definitions(joint_trajectory_controller PRIVATE "JOINT_TRAJECTORY_CONTROLLER_BUILDING_DLL")
45+
target_compile_definitions(joint_trajectory_controller PRIVATE
46+
"JOINT_TRAJECTORY_CONTROLLER_BUILDING_DLL" "_USE_MATH_DEFINES")
4447

4548
pluginlib_export_plugin_description_file(controller_interface joint_trajectory_plugin.xml)
4649

@@ -95,6 +98,26 @@ if(BUILD_TESTING)
9598
controller_manager
9699
test_robot_hardware
97100
)
101+
102+
ament_add_gtest(
103+
test_trajectory_actions
104+
test/test_trajectory_actions.cpp
105+
)
106+
target_include_directories(test_trajectory_actions PRIVATE include)
107+
target_link_libraries(test_trajectory_actions
108+
joint_trajectory_controller
109+
)
110+
ament_target_dependencies(test_trajectory_actions
111+
controller_parameter_server
112+
control_msgs
113+
hardware_interface
114+
rclcpp
115+
rclcpp_lifecycle
116+
rcutils
117+
test_robot_hardware
118+
trajectory_msgs
119+
realtime_tools
120+
)
98121
endif()
99122

100123
ament_export_dependencies(

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 35 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,22 +22,27 @@
2222
#include "controller_interface/controller_interface.hpp"
2323

2424
#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
25+
#include "control_msgs/action/follow_joint_trajectory.hpp"
2526

2627
#include "hardware_interface/joint_command_handle.hpp"
2728
#include "hardware_interface/joint_state_handle.hpp"
2829
#include "hardware_interface/operation_mode_handle.hpp"
2930
#include "hardware_interface/robot_hardware.hpp"
3031

3132
#include "joint_trajectory_controller/trajectory.hpp"
33+
#include "joint_trajectory_controller/tolerances.hpp"
3234
#include "joint_trajectory_controller/visibility_control.h"
3335

36+
#include "rclcpp_action/rclcpp_action.hpp"
37+
3438
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3539
#include "rclcpp_lifecycle/state.hpp"
3640

3741
#include "rcutils/time.h"
3842

3943
#include "realtime_tools/realtime_buffer.h"
4044
#include "realtime_tools/realtime_publisher.h"
45+
#include "realtime_tools/realtime_server_goal_handle.h"
4146

4247
#include "trajectory_msgs/msg/joint_trajectory.hpp"
4348
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
@@ -103,7 +108,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
103108
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr
104109
joint_command_subscriber_ = nullptr;
105110

106-
TrajectoryPointConstIter prev_traj_point_ptr_;
107111
std::shared_ptr<Trajectory> * traj_point_active_ptr_ = nullptr;
108112
std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
109113
std::shared_ptr<Trajectory> traj_home_point_ptr_ = nullptr;
@@ -120,11 +124,40 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
120124
rclcpp::Duration state_publisher_period_ = rclcpp::Duration(RCUTILS_MS_TO_NS(20));
121125
rclcpp::Time last_state_publish_time_;
122126

127+
using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
128+
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<FollowJTrajAction>;
129+
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
130+
131+
rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
132+
bool allow_partial_joints_goal_;
133+
RealtimeGoalHandlePtr rt_active_goal_; ///< Currently active action goal, if any.
134+
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
135+
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(RCUTILS_MS_TO_NS(50));
136+
std::mutex trajectory_mtx_;
137+
138+
// callbacks for action_server_
139+
rclcpp_action::GoalResponse goal_callback(
140+
const rclcpp_action::GoalUUID & uuid,
141+
std::shared_ptr<const FollowJTrajAction::Goal> goal);
142+
rclcpp_action::CancelResponse cancel_callback(
143+
const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
144+
void feedback_setup_callback(
145+
std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
146+
147+
SegmentTolerances default_tolerances_;
148+
149+
void preempt_active_goal();
150+
void set_hold_position();
151+
123152
bool reset();
124153
void set_op_mode(const hardware_interface::OperationMode & mode);
125154
void halt();
126155

127-
void publish_state();
156+
using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
157+
void publish_state(
158+
const JointTrajectoryPoint & desired_state,
159+
const JointTrajectoryPoint & current_state,
160+
const JointTrajectoryPoint & state_error);
128161
};
129162

130163
} // namespace joint_trajectory_controller
Lines changed: 194 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,194 @@
1+
// Copyright 2013 PAL Robotics S.L.
2+
// All rights reserved.
3+
//
4+
// Software License Agreement (BSD License 2.0)
5+
// Redistribution and use in source and binary forms, with or without
6+
// modification, are permitted provided that the following conditions are met:
7+
// * Redistributions of source code must retain the above copyright notice,
8+
// this list of conditions and the following disclaimer.
9+
// * Redistributions in binary form must reproduce the above copyright
10+
// notice, this list of conditions and the following disclaimer in the
11+
// documentation and/or other materials provided with the distribution.
12+
// * Neither the name of PAL Robotics S.L. nor the names of its
13+
// contributors may be used to endorse or promote products derived from
14+
// this software without specific prior written permission.
15+
//
16+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26+
// POSSIBILITY OF SUCH DAMAGE.
27+
28+
/// \author Adolfo Rodriguez Tsouroukdissian
29+
30+
#ifndef JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
31+
#define JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
32+
33+
#include <cassert>
34+
#include <cmath>
35+
#include <string>
36+
#include <vector>
37+
38+
#include "control_msgs/action/follow_joint_trajectory.hpp"
39+
40+
#include "rclcpp/node.hpp"
41+
42+
namespace joint_trajectory_controller
43+
{
44+
45+
/**
46+
* \brief Trajectory state tolerances for position, velocity and acceleration variables.
47+
*
48+
* A tolerance value of zero means that no tolerance will be applied for that variable.
49+
*/
50+
struct StateTolerances
51+
{
52+
double position = 0.0;
53+
double velocity = 0.0;
54+
double acceleration = 0.0;
55+
};
56+
57+
/**
58+
* \brief Trajectory segment tolerances.
59+
*/
60+
struct SegmentTolerances
61+
{
62+
explicit SegmentTolerances(size_t size = 0)
63+
: state_tolerance(size),
64+
goal_state_tolerance(size)
65+
{}
66+
67+
/** State tolerances that apply during segment execution. */
68+
std::vector<StateTolerances> state_tolerance;
69+
70+
/** State tolerances that apply for the goal state only.*/
71+
std::vector<StateTolerances> goal_state_tolerance;
72+
73+
/** Extra time after the segment end time allowed to reach the goal state tolerances. */
74+
double goal_time_tolerance = 0.0;
75+
};
76+
77+
/**
78+
* \brief Populate trajectory segment tolerances using data from the ROS node.
79+
*
80+
* It is assumed that the following parameter structure is followed on the provided LifecycleNode. Unspecified parameters
81+
* will take the defaults shown in the comments:
82+
*
83+
* \code
84+
* constraints:
85+
* goal_time: 1.0 # Defaults to zero
86+
* stopped_velocity_tolerance: 0.02 # Defaults to 0.01
87+
* foo_joint:
88+
* trajectory: 0.05 # Defaults to zero (ie. the tolerance is not enforced)
89+
* goal: 0.03 # Defaults to zero (ie. the tolerance is not enforced)
90+
* bar_joint:
91+
* goal: 0.01
92+
* \endcode
93+
*
94+
* \param node LifecycleNode where the tolerances are specified.
95+
* \param joint_names Names of joints to look for in the parameter server for a tolerance specification.
96+
* \return Trajectory segment tolerances.
97+
*/
98+
SegmentTolerances get_segment_tolerances(
99+
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
100+
const std::vector<std::string> & joint_names)
101+
{
102+
auto n_joints = joint_names.size();
103+
SegmentTolerances tolerances;
104+
105+
// State and goal state tolerances
106+
double stopped_velocity_tolerance = 0.01;
107+
node->get_parameter_or<double>(
108+
"constraints.stopped_velocity_tolerance",
109+
stopped_velocity_tolerance, stopped_velocity_tolerance);
110+
111+
tolerances.state_tolerance.resize(n_joints);
112+
tolerances.goal_state_tolerance.resize(n_joints);
113+
for (auto i = 0ul; i < n_joints; ++i) {
114+
std::string prefix = "constraints." + joint_names[i];
115+
116+
node->get_parameter_or<double>(
117+
prefix + ".trajectory", tolerances.state_tolerance[i].position,
118+
0.0);
119+
node->get_parameter_or<double>(
120+
prefix + ".goal", tolerances.goal_state_tolerance[i].position,
121+
0.0);
122+
123+
auto logger = rclcpp::get_logger("tolerance");
124+
RCLCPP_DEBUG(
125+
logger, "%s %f",
126+
(prefix + ".trajectory").c_str(), tolerances.state_tolerance[i].position);
127+
RCLCPP_DEBUG(
128+
logger, "%s %f",
129+
(prefix + ".goal").c_str(), tolerances.goal_state_tolerance[i].position);
130+
131+
tolerances.goal_state_tolerance[i].velocity = stopped_velocity_tolerance;
132+
}
133+
134+
// Goal time tolerance
135+
node->get_parameter_or<double>("constraints.goal_time", tolerances.goal_time_tolerance, 0.0);
136+
137+
return tolerances;
138+
}
139+
140+
/**
141+
* \param state_error State error to check.
142+
* \param joint_idx Joint index for the state error
143+
* \param state_tolerance State tolerance of joint to check \p state_error against.
144+
* \param show_errors If the joint that violate its tolerance should be output to console. NOT REALTIME if true
145+
* \return True if \p state_error fulfills \p state_tolerance.
146+
*/
147+
inline bool check_state_tolerance_per_joint(
148+
const trajectory_msgs::msg::JointTrajectoryPoint & state_error,
149+
int joint_idx,
150+
const StateTolerances & state_tolerance,
151+
bool show_errors = false)
152+
{
153+
using std::abs;
154+
double error_position = state_error.positions[joint_idx];
155+
double error_velocity = state_error.velocities[joint_idx];
156+
double error_acceleration = state_error.accelerations[joint_idx];
157+
158+
const bool is_valid =
159+
!(state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) &&
160+
!(state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity) &&
161+
!(state_tolerance.acceleration > 0.0 && abs(error_acceleration) > state_tolerance.acceleration);
162+
163+
if (is_valid) {
164+
return true;
165+
}
166+
167+
if (show_errors) {
168+
auto logger = rclcpp::get_logger("tolerances");
169+
RCLCPP_ERROR_STREAM(logger, "Path state tolerances failed:");
170+
171+
if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) {
172+
RCLCPP_ERROR_STREAM(
173+
logger, "Position Error: " << error_position <<
174+
" Position Tolerance: " << state_tolerance.position);
175+
}
176+
if (state_tolerance.velocity > 0.0 && abs(error_velocity) > state_tolerance.velocity) {
177+
RCLCPP_ERROR_STREAM(
178+
logger, "Velocity Error: " << error_velocity <<
179+
" Velocity Tolerance: " << state_tolerance.velocity);
180+
}
181+
if (state_tolerance.acceleration > 0.0 &&
182+
abs(error_acceleration) > state_tolerance.acceleration)
183+
{
184+
RCLCPP_ERROR_STREAM(
185+
logger, "Acceleration Error: " << error_acceleration <<
186+
" Acceleration Tolerance: " << state_tolerance.acceleration);
187+
}
188+
}
189+
return false;
190+
}
191+
192+
} // namespace joint_trajectory_controller
193+
194+
#endif // JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_

0 commit comments

Comments
 (0)