ros2_control - humble
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.hpp"
42#include "realtime_tools/realtime_publisher.hpp"
43#include "realtime_tools/realtime_server_goal_handle.hpp"
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/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
100protected:
101 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
102 // as the following constants
103 const std::vector<std::string> allowed_interface_types_ = {
108 };
109
110 // Preallocate variables used in the realtime update() function
111 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
112 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
113 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
114 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
115
116 // Degrees of freedom
117 size_t dof_;
118
119 // Storing command joint names for interfaces
120 std::vector<std::string> command_joint_names_;
121
122 // Parameters from ROS for joint_trajectory_controller
123 std::shared_ptr<ParamListener> param_listener_;
124 Params params_;
125
126 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
128 interpolation_methods::InterpolationMethod interpolation_method_{
129 interpolation_methods::DEFAULT_INTERPOLATION};
130
131 // The interfaces are defined as the types in 'allowed_interface_types_' member.
132 // For convenience, for each type the interfaces are ordered so that i-th position
133 // matches i-th index in joint_names_
134 template <typename T>
135 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
136
137 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
138 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
139
140 bool has_position_state_interface_ = false;
141 bool has_velocity_state_interface_ = false;
142 bool has_acceleration_state_interface_ = false;
143 bool has_position_command_interface_ = false;
144 bool has_velocity_command_interface_ = false;
145 bool has_acceleration_command_interface_ = false;
146 bool has_effort_command_interface_ = false;
147
150 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
151 std::vector<PidPtr> pids_;
152 // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
153 std::vector<double> ff_velocity_scale_;
154 // Configuration for every joint if it wraps around (ie. is continuous, position error is
155 // normalized)
156 std::vector<bool> joints_angle_wraparound_;
157 // reserved storage for result of the command when closed loop pid adapter is used
158 std::vector<double> tmp_command_;
159
160 // Timeout to consider commands old
161 double cmd_timeout_;
162 // True if holding position or repeating last trajectory point in case of success
164 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
165 bool subscriber_is_active_ = false;
166 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
167 nullptr;
168
169 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
170
171 std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
173 traj_msg_external_point_ptr_;
174
175 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ = nullptr;
176
177 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
179 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
180 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_legacy_;
181 StatePublisherPtr state_publisher_legacy_;
182 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
183 StatePublisherPtr state_publisher_;
184
185 rclcpp::Duration state_publisher_period_ = rclcpp::Duration(20ms);
186 rclcpp::Time last_state_publish_time_;
187
188 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
190 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
192
193 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
196 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
197 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
198
199 // callback for topic interface
200 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
201 void topic_callback(const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
202
203 // callbacks for action_server_
204 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
205 rclcpp_action::GoalResponse goal_received_callback(
206 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
207 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
208 rclcpp_action::CancelResponse goal_cancelled_callback(
209 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
210 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
211 void goal_accepted_callback(
212 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
213
214 // fill trajectory_msg so it matches joints controlled by this controller
215 // positions set to current position, velocities, accelerations and efforts to 0.0
216 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
217 void fill_partial_goal(
218 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
219 // sorts the joints of the incoming message to our local order
220 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
221 void sort_to_local_joint_order(
222 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg);
223 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
224 bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
225 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
226 void add_new_trajectory_msg(
227 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
228 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
229 bool validate_trajectory_point_field(
230 size_t joint_names_size, const std::vector<double> & vector_field,
231 const std::string & string_for_vector_field, size_t i, bool allow_empty) const;
232
233 // the tolerances from the node parameter
234 SegmentTolerances default_tolerances_;
235 // the tolerances used for the current goal
237
238 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
239 void preempt_active_goal();
240
243 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
244 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_hold_position();
245
250 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
251 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_success_trajectory_point();
252
253 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
254 bool reset();
255
256 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
257 bool has_active_trajectory() const;
258
259 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
260 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
261 void publish_state(
262 const JointTrajectoryPoint & desired_state, const JointTrajectoryPoint & current_state,
263 const JointTrajectoryPoint & state_error);
264
265 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
266
273 bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
274 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
275
276 void query_state_service(
277 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
278 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
279
280private:
281 void update_pids();
282
283 bool contains_interface_type(
284 const std::vector<std::string> & interface_type_list, const std::string & interface_type);
285
286 void init_hold_position_msg();
287 void resize_joint_trajectory_point(
288 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
289 void resize_joint_trajectory_point_command(
290 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
291};
292
293} // namespace joint_trajectory_controller
294
295#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:128
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition joint_trajectory_controller.cpp:117
bool read_state_from_command_interfaces(JointTrajectoryPoint &state)
Definition joint_trajectory_controller.cpp:467
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:1601
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:1589
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
command_interface_configuration
Definition joint_trajectory_controller.cpp:102
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
command_interface_configuration
Definition joint_trajectory_controller.cpp:77
bool use_closed_loop_pid_adapter_
If true, a velocity feedforward term plus corrective PID term is used.
Definition joint_trajectory_controller.hpp:149
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:195
RealtimeGoalHandleBuffer rt_active_goal_
Currently active action goal, if any.
Definition joint_trajectory_controller.hpp:194
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