ros2_control - rolling
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 <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/msg/speed_scaling_factor.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/loaned_command_interface.hpp"
31#include "hardware_interface/types/hardware_interface_type_values.hpp"
32#include "joint_trajectory_controller/interpolation_methods.hpp"
33#include "joint_trajectory_controller/tolerances.hpp"
34#include "joint_trajectory_controller/trajectory.hpp"
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/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:
59
61
63
64 controller_interface::return_type update(
65 const rclcpp::Time & time, const rclcpp::Duration & period) override;
66
67 controller_interface::CallbackReturn on_init() override;
68
69 controller_interface::CallbackReturn on_configure(
70 const rclcpp_lifecycle::State & previous_state) override;
71
72 controller_interface::CallbackReturn on_activate(
73 const rclcpp_lifecycle::State & previous_state) override;
74
75 controller_interface::CallbackReturn on_deactivate(
76 const rclcpp_lifecycle::State & previous_state) override;
77
78 controller_interface::CallbackReturn on_error(
79 const rclcpp_lifecycle::State & previous_state) override;
80
81protected:
82 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
83 // as the following constants
84 const std::vector<std::string> allowed_interface_types_ = {
89 };
90
91 // Preallocate variables used in the realtime update() function
92 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
93 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
94 trajectory_msgs::msg::JointTrajectoryPoint command_next_;
95 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
96 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
97
98 // Degrees of freedom
99 size_t dof_;
100 size_t num_cmd_joints_;
101 std::vector<size_t> map_cmd_to_joints_;
102
103 // Storing command joint names for interfaces
104 std::vector<std::string> command_joint_names_;
105
106 // Parameters from ROS for joint_trajectory_controller
107 std::shared_ptr<ParamListener> param_listener_;
108 Params params_;
109 rclcpp::Duration update_period_{0, 0};
110
111 rclcpp::Time traj_time_;
112
113 // variables for storing internal data for open-loop control
114 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
115 rclcpp::Time last_commanded_time_;
117 interpolation_methods::InterpolationMethod interpolation_method_{
118 interpolation_methods::DEFAULT_INTERPOLATION};
119
120 // The interfaces are defined as the types in 'allowed_interface_types_' member.
121 // For convenience, for each type the interfaces are ordered so that i-th position
122 // matches i-th index in joint_names_
123 template <typename T>
124 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
125
126 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
127 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
128 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
129 scaling_state_interface_;
130 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
131 scaling_command_interface_;
132
133 bool has_position_state_interface_ = false;
134 bool has_velocity_state_interface_ = false;
135 bool has_acceleration_state_interface_ = false;
136 bool has_position_command_interface_ = false;
137 bool has_velocity_command_interface_ = false;
138 bool has_acceleration_command_interface_ = false;
139 bool has_effort_command_interface_ = false;
140
143 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
144 std::vector<PidPtr> pids_;
145 // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
146 std::vector<double> ff_velocity_scale_;
147 // Configuration for every joint if it wraps around (ie. is continuous, position error is
148 // normalized)
149 std::vector<bool> joints_angle_wraparound_;
150 // reserved storage for result of the command when closed loop pid adapter is used
151 std::vector<double> tmp_command_;
152
153 // Things around speed scaling
154 std::atomic<double> scaling_factor_{1.0};
155 std::atomic<double> scaling_factor_cmd_{1.0};
156
157 // Timeout to consider commands old
158 double cmd_timeout_;
159 // True if holding position or repeating last trajectory point in case of success
160 std::atomic<bool> rt_is_holding_{false};
161 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
162 std::atomic<bool> subscriber_is_active_{false};
163 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
164 nullptr;
165
166 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
167
168 std::shared_ptr<Trajectory> current_trajectory_ = nullptr;
170 new_trajectory_msg_;
171
172 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ = nullptr;
173
174 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
176 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
177 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
178 StatePublisherPtr state_publisher_;
179 ControllerStateMsg state_msg_;
180
181 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
183 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
184 using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
185
187 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
188 std::atomic<bool> rt_has_pending_goal_{false};
189 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
190 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
191
192 // callback for topic interface
193 void topic_callback(const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
194
195 // callbacks for action_server_
196 rclcpp_action::GoalResponse goal_received_callback(
197 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
198 rclcpp_action::CancelResponse goal_cancelled_callback(
199 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
200 void goal_accepted_callback(
201 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
202
203 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
204
214 JointTrajectoryPoint & error, const size_t index, const JointTrajectoryPoint & current,
215 const JointTrajectoryPoint & desired) const;
216 // fill trajectory_msg so it matches joints controlled by this controller
217 // positions set to current position, velocities, accelerations and efforts to 0.0
218 void fill_partial_goal(
219 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
220 // sorts the joints of the incoming message to our local order
221 void sort_to_local_joint_order(
222 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
223 bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
224 void add_new_trajectory_msg(
225 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
226 bool validate_trajectory_point_field(
227 size_t joint_names_size, const std::vector<double> & vector_field,
228 const std::string & string_for_vector_field, size_t i, bool allow_empty) const;
229
230 // the tolerances from the node parameter
231 SegmentTolerances default_tolerances_;
232 // the tolerances used for the current goal
234
235 void preempt_active_goal();
236
239 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_hold_position();
240
245 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_success_trajectory_point();
246
247 bool reset();
248
249 bool has_active_trajectory() const;
250
251 void publish_state(
252 const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
253 const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error);
254
255 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
256
263 bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
264 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
265
266 void query_state_service(
267 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
268 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
269
270private:
271 void update_pids();
272
273 bool contains_interface_type(
274 const std::vector<std::string> & interface_type_list, const std::string & interface_type);
275
276 void init_hold_position_msg();
277 void resize_joint_trajectory_point(
278 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size, double value = 0.0);
279 void resize_joint_trajectory_point_command(
280 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size, double value = 0.0);
281
298 bool set_scaling_factor(double scaling_factor);
299
300 using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor;
301 rclcpp::Subscription<SpeedScalingMsg>::SharedPtr scaling_factor_sub_;
302
311 template <typename T>
312 void assign_interface_from_point(
313 const T & joint_interface, const std::vector<double> & trajectory_point_interface)
314 {
315 for (size_t index = 0; index < num_cmd_joints_; ++index)
316 {
317 if (!joint_interface[index].get().set_value(
318 trajectory_point_interface[map_cmd_to_joints_[index]]))
319 {
320 RCLCPP_ERROR(
321 get_node()->get_logger(),
322 "Failed to set value for joint '%s' in command interface '%s'. ",
323 command_joint_names_[index].c_str(), joint_interface[index].get().get_name().c_str());
324 return;
325 }
326 }
327 }
328};
329
330} // namespace joint_trajectory_controller
331
332#endif // JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
Definition controller_interface.hpp:27
Definition joint_trajectory_controller.hpp:56
interpolation_methods::InterpolationMethod interpolation_method_
Specify interpolation method. Default to splines.
Definition joint_trajectory_controller.hpp:117
void compute_error_for_joint(JointTrajectoryPoint &error, const size_t index, const JointTrajectoryPoint &current, const JointTrajectoryPoint &desired) const
Definition joint_trajectory_controller.cpp:1439
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition joint_trajectory_controller.cpp:143
bool read_state_from_command_interfaces(JointTrajectoryPoint &state)
Definition joint_trajectory_controller.cpp:536
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:1795
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:1783
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition joint_trajectory_controller.cpp:124
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition joint_trajectory_controller.cpp:104
bool use_closed_loop_pid_adapter_
If true, a velocity feedforward term plus corrective PID term is used.
Definition joint_trajectory_controller.hpp:142
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition joint_trajectory_controller.cpp:51
RealtimeGoalHandleBuffer rt_active_goal_
Currently active action goal, if any.
Definition joint_trajectory_controller.hpp:186
std::atomic< bool > rt_has_pending_goal_
Is there a pending action goal?
Definition joint_trajectory_controller.hpp:188
Definition realtime_buffer.hpp:44
Definition realtime_publisher.hpp:55
Definition realtime_server_goal_handle.hpp:44
constexpr char HW_IF_EFFORT[]
Constant defining effort interface name.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface name.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition hardware_interface_type_values.hpp:21
Definition interpolation_methods.hpp:24
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:60
Trajectory segment tolerances.
Definition tolerances.hpp:59