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 <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 "rclcpp/duration.hpp"
33#include "rclcpp/subscription.hpp"
34#include "rclcpp/time.hpp"
35#include "rclcpp/timer.hpp"
36#include "rclcpp_action/server.hpp"
37#include "rclcpp_lifecycle/state.hpp"
38#include "realtime_tools/realtime_buffer.hpp"
39#include "realtime_tools/realtime_publisher.hpp"
40#include "realtime_tools/realtime_server_goal_handle.hpp"
41#include "trajectory_msgs/msg/joint_trajectory.hpp"
42#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
43
44// auto-generated by generate_parameter_library
45#include "joint_trajectory_controller/joint_trajectory_controller_parameters.hpp"
46
47using namespace std::chrono_literals; // NOLINT
48
50{
51
53{
54public:
56
61
66
67 controller_interface::return_type update(
68 const rclcpp::Time & time, const rclcpp::Duration & period) override;
69
70 controller_interface::CallbackReturn on_init() override;
71
72 controller_interface::CallbackReturn on_configure(
73 const rclcpp_lifecycle::State & previous_state) override;
74
75 controller_interface::CallbackReturn on_activate(
76 const rclcpp_lifecycle::State & previous_state) override;
77
78 controller_interface::CallbackReturn on_deactivate(
79 const rclcpp_lifecycle::State & previous_state) override;
80
81 controller_interface::CallbackReturn on_error(
82 const rclcpp_lifecycle::State & previous_state) override;
83
84protected:
85 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
86 // as the following constants
87 const std::vector<std::string> allowed_interface_types_ = {
92 };
93
94 // Preallocate variables used in the realtime update() function
95 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
96 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
97 trajectory_msgs::msg::JointTrajectoryPoint command_next_;
98 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
99 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
100
101 // Degrees of freedom
102 size_t dof_;
103
104 // Storing command joint names for interfaces
105 std::vector<std::string> command_joint_names_;
106
107 // Parameters from ROS for joint_trajectory_controller
108 std::shared_ptr<ParamListener> param_listener_;
109 Params params_;
110 rclcpp::Duration update_period_{0, 0};
111
112 rclcpp::Time traj_time_;
113
114 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
116 interpolation_methods::InterpolationMethod interpolation_method_{
117 interpolation_methods::DEFAULT_INTERPOLATION};
118
119 // The interfaces are defined as the types in 'allowed_interface_types_' member.
120 // For convenience, for each type the interfaces are ordered so that i-th position
121 // matches i-th index in joint_names_
122 template <typename T>
123 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
124
125 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
126 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
127
128 bool has_position_state_interface_ = false;
129 bool has_velocity_state_interface_ = false;
130 bool has_acceleration_state_interface_ = false;
131 bool has_position_command_interface_ = false;
132 bool has_velocity_command_interface_ = false;
133 bool has_acceleration_command_interface_ = false;
134 bool has_effort_command_interface_ = false;
135
138 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
139 std::vector<PidPtr> pids_;
140 // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
141 std::vector<double> ff_velocity_scale_;
142 // Configuration for every joint if it wraps around (ie. is continuous, position error is
143 // normalized)
144 std::vector<bool> joints_angle_wraparound_;
145 // reserved storage for result of the command when closed loop pid adapter is used
146 std::vector<double> tmp_command_;
147
148 // Timeout to consider commands old
149 double cmd_timeout_;
150 // True if holding position or repeating last trajectory point in case of success
152 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
153 bool subscriber_is_active_ = false;
154 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
155 nullptr;
156
157 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
158
159 std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
161 traj_msg_external_point_ptr_;
162
163 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ = nullptr;
164
165 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
167 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
168 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
169 StatePublisherPtr state_publisher_;
170
171 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
173 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
175
176 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
179 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
180 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
181
182 // callback for topic interface
183 void topic_callback(const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
184
185 // callbacks for action_server_
186 rclcpp_action::GoalResponse goal_received_callback(
187 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
188 rclcpp_action::CancelResponse goal_cancelled_callback(
189 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
190 void goal_accepted_callback(
191 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
192
193 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
194
204 JointTrajectoryPoint & error, const size_t index, const JointTrajectoryPoint & current,
205 const JointTrajectoryPoint & desired) const;
206 // fill trajectory_msg so it matches joints controlled by this controller
207 // positions set to current position, velocities, accelerations and efforts to 0.0
208 void fill_partial_goal(
209 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
210 // sorts the joints of the incoming message to our local order
211 void sort_to_local_joint_order(
212 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
213 bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
214 void add_new_trajectory_msg(
215 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
216 bool validate_trajectory_point_field(
217 size_t joint_names_size, const std::vector<double> & vector_field,
218 const std::string & string_for_vector_field, size_t i, bool allow_empty) const;
219
220 // the tolerances from the node parameter
221 SegmentTolerances default_tolerances_;
222 // the tolerances used for the current goal
224
225 void preempt_active_goal();
226
229 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_hold_position();
230
235 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_success_trajectory_point();
236
237 bool reset();
238
239 bool has_active_trajectory() const;
240
241 void publish_state(
242 const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
243 const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error);
244
245 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
246
253 bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
254 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
255
256 void query_state_service(
257 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
258 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
259
260private:
261 void update_pids();
262
263 bool contains_interface_type(
264 const std::vector<std::string> & interface_type_list, const std::string & interface_type);
265
266 void init_hold_position_msg();
267 void resize_joint_trajectory_point(
268 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
269 void resize_joint_trajectory_point_command(
270 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
271
280 template <typename T>
281 void assign_interface_from_point(
282 const T & joint_interface, const std::vector<double> & trajectory_point_interface)
283 {
284 for (size_t index = 0; index < dof_; ++index)
285 {
286 joint_interface[index].get().set_value(trajectory_point_interface[index]);
287 }
288 }
289};
290
291} // namespace joint_trajectory_controller
292
293#endif // JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
Definition controller_interface.hpp:27
Definition joint_trajectory_controller.hpp:53
interpolation_methods::InterpolationMethod interpolation_method_
Specify interpolation method. Default to splines.
Definition joint_trajectory_controller.hpp:116
void compute_error_for_joint(JointTrajectoryPoint &error, const size_t index, const JointTrajectoryPoint &current, const JointTrajectoryPoint &desired) const
Definition joint_trajectory_controller.cpp:1203
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition joint_trajectory_controller.cpp:144
bool read_state_from_command_interfaces(JointTrajectoryPoint &state)
Definition joint_trajectory_controller.cpp:464
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:1527
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:1515
controller_interface::InterfaceConfiguration state_interface_configuration() const override
command_interface_configuration
Definition joint_trajectory_controller.cpp:129
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:137
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition joint_trajectory_controller.cpp:51
realtime_tools::RealtimeBuffer< bool > rt_has_pending_goal_
Is there a pending action goal?
Definition joint_trajectory_controller.hpp:178
RealtimeGoalHandleBuffer rt_active_goal_
Currently active action goal, if any.
Definition joint_trajectory_controller.hpp:177
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 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:57
Trajectory segment tolerances.
Definition tolerances.hpp:59