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
64
69
70 controller_interface::return_type update(
71 const rclcpp::Time & time, const rclcpp::Duration & period) override;
72
73 controller_interface::CallbackReturn on_init() override;
74
75 controller_interface::CallbackReturn on_configure(
76 const rclcpp_lifecycle::State & previous_state) override;
77
78 controller_interface::CallbackReturn on_activate(
79 const rclcpp_lifecycle::State & previous_state) override;
80
81 controller_interface::CallbackReturn on_deactivate(
82 const rclcpp_lifecycle::State & previous_state) override;
83
84 controller_interface::CallbackReturn on_error(
85 const rclcpp_lifecycle::State & previous_state) override;
86
87protected:
88 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
89 // as the following constants
90 const std::vector<std::string> allowed_interface_types_ = {
95 };
96
97 // Preallocate variables used in the realtime update() function
98 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
99 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
100 trajectory_msgs::msg::JointTrajectoryPoint command_next_;
101 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
102 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
103
104 // Degrees of freedom
105 size_t dof_;
106 size_t num_cmd_joints_;
107 std::vector<size_t> map_cmd_to_joints_;
108
109 // Storing command joint names for interfaces
110 std::vector<std::string> command_joint_names_;
111
112 // Parameters from ROS for joint_trajectory_controller
113 std::shared_ptr<ParamListener> param_listener_;
114 Params params_;
115 rclcpp::Duration update_period_{0, 0};
116
117 rclcpp::Time traj_time_;
118
119 // variables for storing internal data for open-loop control
120 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
121 rclcpp::Time last_commanded_time_;
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 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
135 scaling_state_interface_;
136 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
137 scaling_command_interface_;
138
139 bool has_position_state_interface_ = false;
140 bool has_velocity_state_interface_ = false;
141 bool has_acceleration_state_interface_ = false;
142 bool has_position_command_interface_ = false;
143 bool has_velocity_command_interface_ = false;
144 bool has_acceleration_command_interface_ = false;
145 bool has_effort_command_interface_ = false;
146
149 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
150 std::vector<PidPtr> pids_;
151 // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
152 std::vector<double> ff_velocity_scale_;
153 // Configuration for every joint if it wraps around (ie. is continuous, position error is
154 // normalized)
155 std::vector<bool> joints_angle_wraparound_;
156 // reserved storage for result of the command when closed loop pid adapter is used
157 std::vector<double> tmp_command_;
158
159 // Things around speed scaling
160 std::atomic<double> scaling_factor_{1.0};
161 std::atomic<double> scaling_factor_cmd_{1.0};
162
163 // Timeout to consider commands old
164 double cmd_timeout_;
165 // True if holding position or repeating last trajectory point in case of success
166 std::atomic<bool> rt_is_holding_{false};
167 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
168 std::atomic<bool> subscriber_is_active_{false};
169 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
170 nullptr;
171
172 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
173
174 std::shared_ptr<Trajectory> current_trajectory_ = nullptr;
176 new_trajectory_msg_;
177
178 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ = nullptr;
179
180 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
182 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
183 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
184 StatePublisherPtr state_publisher_;
185
186 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
188 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
189 using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
190
191 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
193 std::atomic<bool> rt_has_pending_goal_{false};
194 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
195 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
196
197 // callback for topic interface
198 void topic_callback(const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
199
200 // callbacks for action_server_
201 rclcpp_action::GoalResponse goal_received_callback(
202 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
203 rclcpp_action::CancelResponse goal_cancelled_callback(
204 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
205 void goal_accepted_callback(
206 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
207
208 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
209
219 JointTrajectoryPoint & error, const size_t index, const JointTrajectoryPoint & current,
220 const JointTrajectoryPoint & desired) const;
221 // fill trajectory_msg so it matches joints controlled by this controller
222 // positions set to current position, velocities, accelerations and efforts to 0.0
223 void fill_partial_goal(
224 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
225 // sorts the joints of the incoming message to our local order
226 void sort_to_local_joint_order(
227 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
228 bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
229 void add_new_trajectory_msg(
230 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
231 bool validate_trajectory_point_field(
232 size_t joint_names_size, const std::vector<double> & vector_field,
233 const std::string & string_for_vector_field, size_t i, bool allow_empty) const;
234
235 // the tolerances from the node parameter
236 SegmentTolerances default_tolerances_;
237 // the tolerances used for the current goal
239
240 void preempt_active_goal();
241
244 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_hold_position();
245
250 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_success_trajectory_point();
251
252 bool reset();
253
254 bool has_active_trajectory() const;
255
256 void publish_state(
257 const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
258 const JointTrajectoryPoint & current_state, 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, double value = 0.0);
284 void resize_joint_trajectory_point_command(
285 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size, double value = 0.0);
286
303 bool set_scaling_factor(double scaling_factor);
304
305 using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor;
306 rclcpp::Subscription<SpeedScalingMsg>::SharedPtr scaling_factor_sub_;
307
316 template <typename T>
317 void assign_interface_from_point(
318 const T & joint_interface, const std::vector<double> & trajectory_point_interface)
319 {
320 for (size_t index = 0; index < num_cmd_joints_; ++index)
321 {
322 if (!joint_interface[index].get().set_value(
323 trajectory_point_interface[map_cmd_to_joints_[index]]))
324 {
325 RCLCPP_ERROR(
326 get_node()->get_logger(),
327 "Failed to set value for joint '%s' in command interface '%s'. ",
328 command_joint_names_[index].c_str(), joint_interface[index].get().get_name().c_str());
329 return;
330 }
331 }
332 }
333};
334
335} // namespace joint_trajectory_controller
336
337#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:123
void compute_error_for_joint(JointTrajectoryPoint &error, const size_t index, const JointTrajectoryPoint &current, const JointTrajectoryPoint &desired) const
Definition joint_trajectory_controller.cpp:1435
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:1791
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:1779
controller_interface::InterfaceConfiguration state_interface_configuration() const override
command_interface_configuration
Definition joint_trajectory_controller.cpp:124
controller_interface::InterfaceConfiguration command_interface_configuration() const override
command_interface_configuration
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:148
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:192
std::atomic< bool > rt_has_pending_goal_
Is there a pending action goal?
Definition joint_trajectory_controller.hpp:193
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:58
Trajectory segment tolerances.
Definition tolerances.hpp:59