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 <atomic>
19#include <chrono>
20#include <functional> // for std::reference_wrapper
21#include <memory>
22#include <string>
23#include <vector>
24
25#include "control_msgs/action/follow_joint_trajectory.hpp"
26#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
27#include "control_msgs/srv/query_trajectory_state.hpp"
28#include "control_toolbox/pid.hpp"
29#include "controller_interface/controller_interface.hpp"
30#include "hardware_interface/types/hardware_interface_type_values.hpp"
31#include "joint_trajectory_controller/interpolation_methods.hpp"
32#include "joint_trajectory_controller/tolerances.hpp"
33#include "joint_trajectory_controller/trajectory.hpp"
34#include "joint_trajectory_controller/visibility_control.h"
35#include "rclcpp/duration.hpp"
36#include "rclcpp/subscription.hpp"
37#include "rclcpp/time.hpp"
38#include "rclcpp/timer.hpp"
39#include "rclcpp_action/server.hpp"
40#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
41#include "rclcpp_lifecycle/state.hpp"
42#include "realtime_tools/realtime_buffer.hpp"
43#include "realtime_tools/realtime_publisher.hpp"
44#include "realtime_tools/realtime_server_goal_handle.hpp"
45#include "trajectory_msgs/msg/joint_trajectory.hpp"
46#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
47
48// auto-generated by generate_parameter_library
49#include "joint_trajectory_controller/joint_trajectory_controller_parameters.hpp"
50
51using namespace std::chrono_literals; // NOLINT
52
54{
55
57{
58public:
59 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
61
62 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
64
65 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
67
68 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
69 controller_interface::return_type update(
70 const rclcpp::Time & time, const rclcpp::Duration & period) override;
71
72 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
73 controller_interface::CallbackReturn on_init() override;
74
75 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
76 controller_interface::CallbackReturn on_configure(
77 const rclcpp_lifecycle::State & previous_state) override;
78
79 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
80 controller_interface::CallbackReturn on_activate(
81 const rclcpp_lifecycle::State & previous_state) override;
82
83 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
84 controller_interface::CallbackReturn on_deactivate(
85 const rclcpp_lifecycle::State & previous_state) override;
86
87 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
88 controller_interface::CallbackReturn on_cleanup(
89 const rclcpp_lifecycle::State & previous_state) override;
90
91 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
92 controller_interface::CallbackReturn on_error(
93 const rclcpp_lifecycle::State & previous_state) override;
94
95protected:
96 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
97 // as the following constants
98 const std::vector<std::string> allowed_interface_types_ = {
103 };
104
105 // Preallocate variables used in the realtime update() function
106 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
107 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
108 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
109 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
110
111 // Degrees of freedom
112 size_t dof_;
113
114 // Storing command joint names for interfaces
115 std::vector<std::string> command_joint_names_;
116
117 // Parameters from ROS for joint_trajectory_controller
118 std::shared_ptr<ParamListener> param_listener_;
119 Params params_;
120
121 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
123 interpolation_methods::InterpolationMethod interpolation_method_{
124 interpolation_methods::DEFAULT_INTERPOLATION};
125
126 // The interfaces are defined as the types in 'allowed_interface_types_' member.
127 // For convenience, for each type the interfaces are ordered so that i-th position
128 // matches i-th index in joint_names_
129 template <typename T>
130 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
131
132 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
133 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
134
135 bool has_position_state_interface_ = false;
136 bool has_velocity_state_interface_ = false;
137 bool has_acceleration_state_interface_ = false;
138 bool has_position_command_interface_ = false;
139 bool has_velocity_command_interface_ = false;
140 bool has_acceleration_command_interface_ = false;
141 bool has_effort_command_interface_ = false;
142
145 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
146 std::vector<PidPtr> pids_;
147 // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
148 std::vector<double> ff_velocity_scale_;
149 // Configuration for every joint if it wraps around (ie. is continuous, position error is
150 // normalized)
151 std::vector<bool> joints_angle_wraparound_;
152 // reserved storage for result of the command when closed loop pid adapter is used
153 std::vector<double> tmp_command_;
154
155 // Timeout to consider commands old
156 double cmd_timeout_;
157 // True if holding position or repeating last trajectory point in case of success
158 std::atomic<bool> rt_is_holding_{false};
159 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
160 std::atomic<bool> subscriber_is_active_{false};
161 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
162 nullptr;
163
164 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
165
166 std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
168 traj_msg_external_point_ptr_;
169
170 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ = nullptr;
171
172 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
174 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
175 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_legacy_;
176 StatePublisherPtr state_publisher_legacy_;
177 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
178 StatePublisherPtr state_publisher_;
179
180 rclcpp::Duration state_publisher_period_ = rclcpp::Duration(20ms);
181 rclcpp::Time last_state_publish_time_;
182
183 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
185 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
186 using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
187
188 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
190 std::atomic<bool> rt_has_pending_goal_{false};
191 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
192 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
193
194 // callback for topic interface
195 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
196 void topic_callback(const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
197
198 // callbacks for action_server_
199 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
200 rclcpp_action::GoalResponse goal_received_callback(
201 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
202 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
203 rclcpp_action::CancelResponse goal_cancelled_callback(
204 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
205 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
206 void goal_accepted_callback(
207 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
208
209 // fill trajectory_msg so it matches joints controlled by this controller
210 // positions set to current position, velocities, accelerations and efforts to 0.0
211 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
212 void fill_partial_goal(
213 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
214 // sorts the joints of the incoming message to our local order
215 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
216 void sort_to_local_joint_order(
217 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg);
218 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
219 bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
220 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
221 void add_new_trajectory_msg(
222 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
223 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
224 bool validate_trajectory_point_field(
225 size_t joint_names_size, const std::vector<double> & vector_field,
226 const std::string & string_for_vector_field, size_t i, bool allow_empty) const;
227
228 // the tolerances from the node parameter
229 SegmentTolerances default_tolerances_;
230 // the tolerances used for the current goal
232
233 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
234 void preempt_active_goal();
235
238 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
239 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_hold_position();
240
245 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
246 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_success_trajectory_point();
247
248 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
249 bool reset();
250
251 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
252 bool has_active_trajectory() const;
253
254 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
255 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
256 void publish_state(
257 const JointTrajectoryPoint & desired_state, const JointTrajectoryPoint & current_state,
258 const JointTrajectoryPoint & state_error);
259
260 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
261
268 bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
269 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
270
271 void query_state_service(
272 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
273 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
274
275private:
276 void update_pids();
277
278 bool contains_interface_type(
279 const std::vector<std::string> & interface_type_list, const std::string & interface_type);
280
281 void init_hold_position_msg();
282 void resize_joint_trajectory_point(
283 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
284 void resize_joint_trajectory_point_command(
285 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
286};
287
288} // namespace joint_trajectory_controller
289
290#endif // JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
Definition controller_interface.hpp:29
Definition joint_trajectory_controller.hpp:57
interpolation_methods::InterpolationMethod interpolation_method_
Specify interpolation method. Default to splines.
Definition joint_trajectory_controller.hpp:123
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:465
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:1615
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:1603
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition joint_trajectory_controller.cpp:102
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
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:144
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
RealtimeGoalHandleBuffer rt_active_goal_
Currently active action goal, if any.
Definition joint_trajectory_controller.hpp:189
std::atomic< bool > rt_has_pending_goal_
Is there a pending action goal?
Definition joint_trajectory_controller.hpp:190
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