ros2_control - iron
Loading...
Searching...
No Matches
joint_trajectory_controller.hpp
1// Copyright (c) 2021 ros2_control Development Team
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
16#define JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
17
18#include <chrono>
19#include <functional> // for std::reference_wrapper
20#include <memory>
21#include <string>
22#include <vector>
23
24#include "control_msgs/action/follow_joint_trajectory.hpp"
25#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
26#include "control_msgs/srv/query_trajectory_state.hpp"
27#include "control_toolbox/pid.hpp"
28#include "controller_interface/controller_interface.hpp"
29#include "hardware_interface/types/hardware_interface_type_values.hpp"
30#include "joint_trajectory_controller/interpolation_methods.hpp"
31#include "joint_trajectory_controller/tolerances.hpp"
32#include "joint_trajectory_controller/trajectory.hpp"
33#include "joint_trajectory_controller/visibility_control.h"
34#include "rclcpp/duration.hpp"
35#include "rclcpp/subscription.hpp"
36#include "rclcpp/time.hpp"
37#include "rclcpp/timer.hpp"
38#include "rclcpp_action/server.hpp"
39#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
40#include "rclcpp_lifecycle/state.hpp"
41#include "realtime_tools/realtime_buffer.h"
42#include "realtime_tools/realtime_publisher.h"
43#include "realtime_tools/realtime_server_goal_handle.h"
44#include "trajectory_msgs/msg/joint_trajectory.hpp"
45#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
46
47// auto-generated by generate_parameter_library
48#include "joint_trajectory_controller_parameters.hpp"
49
50using namespace std::chrono_literals; // NOLINT
51
53{
54
56{
57public:
58 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
60
64 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
66
70 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
72
73 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
74 controller_interface::return_type update(
75 const rclcpp::Time & time, const rclcpp::Duration & period) override;
76
77 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
78 controller_interface::CallbackReturn on_init() override;
79
80 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
81 controller_interface::CallbackReturn on_configure(
82 const rclcpp_lifecycle::State & previous_state) override;
83
84 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
85 controller_interface::CallbackReturn on_activate(
86 const rclcpp_lifecycle::State & previous_state) override;
87
88 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
89 controller_interface::CallbackReturn on_deactivate(
90 const rclcpp_lifecycle::State & previous_state) override;
91
92 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
93 controller_interface::CallbackReturn on_cleanup(
94 const rclcpp_lifecycle::State & previous_state) override;
95
96 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
97 controller_interface::CallbackReturn on_error(
98 const rclcpp_lifecycle::State & previous_state) override;
99
100 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
101 controller_interface::CallbackReturn on_shutdown(
102 const rclcpp_lifecycle::State & previous_state) override;
103
104protected:
105 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
106 // as the following constants
107 const std::vector<std::string> allowed_interface_types_ = {
112 };
113
114 // Preallocate variables used in the realtime update() function
115 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
116 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
117 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
118 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
119
120 // Degrees of freedom
121 size_t dof_;
122
123 // Storing command joint names for interfaces
124 std::vector<std::string> command_joint_names_;
125
126 // Parameters from ROS for joint_trajectory_controller
127 std::shared_ptr<ParamListener> param_listener_;
128 Params params_;
129
130 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
132 interpolation_methods::InterpolationMethod interpolation_method_{
133 interpolation_methods::DEFAULT_INTERPOLATION};
134
135 // The interfaces are defined as the types in 'allowed_interface_types_' member.
136 // For convenience, for each type the interfaces are ordered so that i-th position
137 // matches i-th index in joint_names_
138 template <typename T>
139 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
140
141 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
142 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
143
144 bool has_position_state_interface_ = false;
145 bool has_velocity_state_interface_ = false;
146 bool has_acceleration_state_interface_ = false;
147 bool has_position_command_interface_ = false;
148 bool has_velocity_command_interface_ = false;
149 bool has_acceleration_command_interface_ = false;
150 bool has_effort_command_interface_ = false;
151
154 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
155 std::vector<PidPtr> pids_;
156 // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
157 std::vector<double> ff_velocity_scale_;
158 // Configuration for every joint if it wraps around (ie. is continuous, position error is
159 // normalized)
160 std::vector<bool> joints_angle_wraparound_;
161 // reserved storage for result of the command when closed loop pid adapter is used
162 std::vector<double> tmp_command_;
163
164 // Timeout to consider commands old
165 double cmd_timeout_;
166 // True if holding position or repeating last trajectory point in case of success
168 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
169 bool subscriber_is_active_ = false;
170 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
171 nullptr;
172
173 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
174
175 std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
177 traj_msg_external_point_ptr_;
178
179 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ = nullptr;
180
181 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
183 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
184 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
185 StatePublisherPtr state_publisher_;
186
187 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
189 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
191
192 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
195 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
196 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
197
198 // callback for topic interface
199 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
200 void topic_callback(const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
201
202 // callbacks for action_server_
203 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
204 rclcpp_action::GoalResponse goal_received_callback(
205 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
206 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
207 rclcpp_action::CancelResponse goal_cancelled_callback(
208 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
209 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
210 void goal_accepted_callback(
211 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
212
213 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
214
223 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
225 JointTrajectoryPoint & error, const size_t index, const JointTrajectoryPoint & current,
226 const JointTrajectoryPoint & desired) const;
227 // fill trajectory_msg so it matches joints controlled by this controller
228 // positions set to current position, velocities, accelerations and efforts to 0.0
229 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
230 void fill_partial_goal(
231 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
232 // sorts the joints of the incoming message to our local order
233 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
234 void sort_to_local_joint_order(
235 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
236 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
237 bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
238 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
239 void add_new_trajectory_msg(
240 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
241 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
242 bool validate_trajectory_point_field(
243 size_t joint_names_size, const std::vector<double> & vector_field,
244 const std::string & string_for_vector_field, size_t i, bool allow_empty) const;
245
246 // the tolerances from the node parameter
247 SegmentTolerances default_tolerances_;
248 // the tolerances used for the current goal
250
251 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
252 void preempt_active_goal();
253
256 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
257 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_hold_position();
258
263 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
264 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_success_trajectory_point();
265
266 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
267 bool reset();
268
269 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
270 bool has_active_trajectory() const;
271
272 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
273 void publish_state(
274 const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
275 const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error);
276
277 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
278
285 bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
286 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
287
288 void query_state_service(
289 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
290 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
291
292private:
293 void update_pids();
294
295 bool contains_interface_type(
296 const std::vector<std::string> & interface_type_list, const std::string & interface_type);
297
298 void init_hold_position_msg();
299 void resize_joint_trajectory_point(
300 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
301 void resize_joint_trajectory_point_command(
302 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
303
312 template <typename T>
313 void assign_interface_from_point(
314 const T & joint_interface, const std::vector<double> & trajectory_point_interface)
315 {
316 for (size_t index = 0; index < dof_; ++index)
317 {
318 joint_interface[index].get().set_value(trajectory_point_interface[index]);
319 }
320 }
321};
322
323} // namespace joint_trajectory_controller
324
325#endif // JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
Definition controller_interface.hpp:29
Definition joint_trajectory_controller.hpp:56
interpolation_methods::InterpolationMethod interpolation_method_
Specify interpolation method. Default to splines.
Definition joint_trajectory_controller.hpp:132
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void compute_error_for_joint(JointTrajectoryPoint &error, const size_t index, const JointTrajectoryPoint &current, const JointTrajectoryPoint &desired) const
Definition joint_trajectory_controller.cpp:1198
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition joint_trajectory_controller.cpp:114
bool read_state_from_command_interfaces(JointTrajectoryPoint &state)
Definition joint_trajectory_controller.cpp:424
JOINT_TRAJECTORY_CONTROLLER_PUBLIC std::shared_ptr< trajectory_msgs::msg::JointTrajectory > set_success_trajectory_point()
set last trajectory point to be repeated at success
Definition joint_trajectory_controller.cpp:1515
JOINT_TRAJECTORY_CONTROLLER_PUBLIC std::shared_ptr< trajectory_msgs::msg::JointTrajectory > set_hold_position()
set the current position with zero velocity and acceleration as new command
Definition joint_trajectory_controller.cpp:1503
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
command_interface_configuration
Definition joint_trajectory_controller.cpp:99
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
command_interface_configuration
Definition joint_trajectory_controller.cpp:74
bool use_closed_loop_pid_adapter_
If true, a velocity feedforward term plus corrective PID term is used.
Definition joint_trajectory_controller.hpp:153
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition joint_trajectory_controller.cpp:47
realtime_tools::RealtimeBuffer< bool > rt_has_pending_goal_
Is there a pending action goal?
Definition joint_trajectory_controller.hpp:194
RealtimeGoalHandleBuffer rt_active_goal_
Currently active action goal, if any.
Definition joint_trajectory_controller.hpp:193
Definition realtime_buffer.hpp:44
Definition realtime_publisher.hpp:54
Definition realtime_server_goal_handle.hpp:44
constexpr char HW_IF_EFFORT[]
Constant defining effort interface.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition hardware_interface_type_values.hpp:21
Definition interpolation_methods.hpp:24
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:56
Trajectory segment tolerances.
Definition tolerances.hpp:62