ros2_control - galactic
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 <chrono>
19#include <memory>
20#include <mutex>
21#include <string>
22#include <utility>
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 "controller_interface/controller_interface.hpp"
28#include "hardware_interface/types/hardware_interface_type_values.hpp"
29#include "joint_trajectory_controller/tolerances.hpp"
30#include "joint_trajectory_controller/visibility_control.h"
31#include "rclcpp/duration.hpp"
32#include "rclcpp/subscription.hpp"
33#include "rclcpp/time.hpp"
34#include "rclcpp/timer.hpp"
35#include "rclcpp_action/server.hpp"
36#include "rclcpp_action/types.hpp"
37#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
38#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
39#include "realtime_tools/realtime_buffer.h"
40#include "realtime_tools/realtime_publisher.h"
41#include "realtime_tools/realtime_server_goal_handle.h"
42#include "trajectory_msgs/msg/joint_trajectory.hpp"
43#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
44
45using namespace std::chrono_literals; // NOLINT
46
47namespace rclcpp_action
48{
49template <typename ActionT>
51} // namespace rclcpp_action
52namespace rclcpp_lifecycle
53{
54class State;
55} // namespace rclcpp_lifecycle
56
58{
59using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
60
61class Trajectory;
62
64{
65public:
66 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
68
73 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
75
80 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
82
83 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
84 controller_interface::return_type update(
85 const rclcpp::Time & time, const rclcpp::Duration & period) override;
86
87 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
88 CallbackReturn on_init() override;
89
90 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
91 CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;
92
93 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
94 CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
95
96 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
97 CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
98
99 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
100 CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override;
101
102 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
103 CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;
104
105 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
106 CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;
107
108protected:
109 std::vector<std::string> joint_names_;
110 std::vector<std::string> command_interface_types_;
111 std::vector<std::string> state_interface_types_;
112
113 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
114 // as the following constants
115 const std::vector<std::string> allowed_interface_types_ = {
120 };
121
122 // Parameters for some special cases, e.g. hydraulics powered robots
125 bool open_loop_control_ = false;
126 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
127
128 // The interfaces are defined as the types in 'allowed_interface_types_' member.
129 // For convenience, for each type the interfaces are ordered so that i-th position
130 // matches i-th index in joint_names_
131 template <typename T>
132 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
133
134 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
135 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
136
137 bool has_velocity_state_interface_ = false;
138 bool has_acceleration_state_interface_ = false;
139 bool has_position_command_interface_ = false;
140 bool has_velocity_command_interface_ = false;
141 bool has_acceleration_command_interface_ = false;
142
144 // TODO(anyone): This flag is not used for now
145 // There should be PID-approach used as in ROS1:
146 // https://github.com/ros-controls/ros_controllers/blob/noetic-devel/joint_trajectory_controller/include/joint_trajectory_controller/hardware_interface_adapter.h#L283
148
149 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
150 bool subscriber_is_active_ = false;
151 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
152 nullptr;
153
154 std::shared_ptr<Trajectory> * traj_point_active_ptr_ = nullptr;
155 std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
156 std::shared_ptr<Trajectory> traj_home_point_ptr_ = nullptr;
157 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> traj_msg_home_ptr_ = nullptr;
159 traj_msg_external_point_ptr_;
160
161 // The controller should be in halted state after creation otherwise memory corruption
162 // TODO(anyone): Is the variable relevant, since we are using lifecycle?
163 bool is_halted_ = true;
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 rclcpp::Duration state_publisher_period_ = rclcpp::Duration(20ms);
172 rclcpp::Time last_state_publish_time_;
173
174 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
176 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
178
179 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
180 bool allow_partial_joints_goal_ = false;
182 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
183 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
184
185 // callbacks for action_server_
186 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
187 rclcpp_action::GoalResponse goal_callback(
188 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
189 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
190 rclcpp_action::CancelResponse cancel_callback(
191 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
192 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
193 void feedback_setup_callback(
194 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
195
196 // fill trajectory_msg so it matches joints controlled by this controller
197 // positions set to current position, velocities, accelerations and efforts to 0.0
198 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
199 void fill_partial_goal(
200 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
201 // sorts the joints of the incoming message to our local order
202 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
203 void sort_to_local_joint_order(
204 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg);
205 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
206 bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
207 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
208 void add_new_trajectory_msg(
209 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
210 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
211 bool validate_trajectory_point_field(
212 size_t joint_names_size, const std::vector<double> & vector_field,
213 const std::string & string_for_vector_field, size_t i, bool allow_empty) const;
214
215 SegmentTolerances default_tolerances_;
216
217 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
218 void preempt_active_goal();
219 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
220 void set_hold_position();
221
222 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
223 bool reset();
224
225 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
226 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
227 void publish_state(
228 const JointTrajectoryPoint & desired_state, const JointTrajectoryPoint & current_state,
229 const JointTrajectoryPoint & state_error);
230
231 void read_state_from_hardware(JointTrajectoryPoint & state);
232
233 bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
234
235private:
236 bool contains_interface_type(
237 const std::vector<std::string> & interface_type_list, const std::string & interface_type);
238
239 void resize_joint_trajectory_point(
240 trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
241};
242
243} // namespace joint_trajectory_controller
244
245#endif // JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
Definition controller_interface.hpp:69
Definition joint_trajectory_controller.hpp:64
bool use_closed_loop_pid_adapter
If true, a velocity feedforward term plus corrective PID term is used.
Definition joint_trajectory_controller.hpp:147
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
command_interface_configuration This controller requires the position and velocity state interfaces f...
Definition joint_trajectory_controller.cpp:94
JOINT_TRAJECTORY_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
command_interface_configuration This controller requires the position command interfaces for the cont...
Definition joint_trajectory_controller.cpp:78
bool open_loop_control_
Definition joint_trajectory_controller.hpp:125
RealtimeGoalHandleBuffer rt_active_goal_
Currently active action goal, if any.
Definition joint_trajectory_controller.hpp:181
Definition trajectory.hpp:32
Definition joint_trajectory_controller.hpp:50
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 joint_trajectory_controller.hpp:58
Configuring what command/state interfaces to claim.
Definition controller_interface.hpp:63
Trajectory segment tolerances.
Definition tolerances.hpp:60