59 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
62 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
65 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
68 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
69 controller_interface::return_type
update(
70 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
72 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
73 controller_interface::CallbackReturn
on_init()
override;
75 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
76 controller_interface::CallbackReturn on_configure(
77 const rclcpp_lifecycle::State & previous_state)
override;
79 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
80 controller_interface::CallbackReturn on_activate(
81 const rclcpp_lifecycle::State & previous_state)
override;
83 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
84 controller_interface::CallbackReturn on_deactivate(
85 const rclcpp_lifecycle::State & previous_state)
override;
87 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
88 controller_interface::CallbackReturn on_cleanup(
89 const rclcpp_lifecycle::State & previous_state)
override;
91 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
92 controller_interface::CallbackReturn on_error(
93 const rclcpp_lifecycle::State & previous_state)
override;
98 const std::vector<std::string> allowed_interface_types_ = {
106 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
107 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
108 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
109 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
115 std::vector<std::string> command_joint_names_;
118 std::shared_ptr<ParamListener> param_listener_;
121 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
124 interpolation_methods::DEFAULT_INTERPOLATION};
129 template <
typename T>
130 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
132 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
133 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
135 bool has_position_state_interface_ =
false;
136 bool has_velocity_state_interface_ =
false;
137 bool has_acceleration_state_interface_ =
false;
138 bool has_position_command_interface_ =
false;
139 bool has_velocity_command_interface_ =
false;
140 bool has_acceleration_command_interface_ =
false;
141 bool has_effort_command_interface_ =
false;
145 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
146 std::vector<PidPtr> pids_;
148 std::vector<double> ff_velocity_scale_;
151 std::vector<bool> joints_angle_wraparound_;
153 std::vector<double> tmp_command_;
158 std::atomic<bool> rt_is_holding_{
false};
160 std::atomic<bool> subscriber_is_active_{
false};
161 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
164 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
166 std::shared_ptr<Trajectory> traj_external_point_ptr_ =
nullptr;
168 traj_msg_external_point_ptr_;
170 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ =
nullptr;
172 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
174 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
175 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_legacy_;
176 StatePublisherPtr state_publisher_legacy_;
177 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
178 StatePublisherPtr state_publisher_;
180 rclcpp::Duration state_publisher_period_ = rclcpp::Duration(20ms);
181 rclcpp::Time last_state_publish_time_;
183 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
185 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
188 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
191 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
192 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
195 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
196 void topic_callback(
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
199 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
200 rclcpp_action::GoalResponse goal_received_callback(
201 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
202 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
203 rclcpp_action::CancelResponse goal_cancelled_callback(
204 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
205 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
206 void goal_accepted_callback(
207 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
211 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
212 void fill_partial_goal(
213 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
215 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
216 void sort_to_local_joint_order(
217 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg);
218 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
219 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
220 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
221 void add_new_trajectory_msg(
222 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
223 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
224 bool validate_trajectory_point_field(
225 size_t joint_names_size,
const std::vector<double> & vector_field,
226 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
233 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
234 void preempt_active_goal();
238 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
245 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
248 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
251 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
252 bool has_active_trajectory()
const;
254 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
255 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
257 const JointTrajectoryPoint & desired_state,
const JointTrajectoryPoint & current_state,
258 const JointTrajectoryPoint & state_error);
260 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
269 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
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);
278 bool contains_interface_type(
279 const std::vector<std::string> & interface_type_list,
const std::string & interface_type);
281 void init_hold_position_msg();
282 void resize_joint_trajectory_point(
283 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);
284 void resize_joint_trajectory_point_command(
285 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);