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