64 controller_interface::return_type
update(
65 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
67 controller_interface::CallbackReturn
on_init()
override;
69 controller_interface::CallbackReturn on_configure(
70 const rclcpp_lifecycle::State & previous_state)
override;
72 controller_interface::CallbackReturn on_activate(
73 const rclcpp_lifecycle::State & previous_state)
override;
75 controller_interface::CallbackReturn on_deactivate(
76 const rclcpp_lifecycle::State & previous_state)
override;
78 controller_interface::CallbackReturn on_error(
79 const rclcpp_lifecycle::State & previous_state)
override;
84 const std::vector<std::string> allowed_interface_types_ = {
92 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
93 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
94 trajectory_msgs::msg::JointTrajectoryPoint command_next_;
95 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
96 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
100 size_t num_cmd_joints_;
101 std::vector<size_t> map_cmd_to_joints_;
104 std::vector<std::string> command_joint_names_;
107 std::shared_ptr<ParamListener> param_listener_;
109 rclcpp::Duration update_period_{0, 0};
111 rclcpp::Time traj_time_;
114 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
115 rclcpp::Time last_commanded_time_;
118 interpolation_methods::DEFAULT_INTERPOLATION};
123 template <
typename T>
124 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
126 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
127 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
128 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
129 scaling_state_interface_;
130 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
131 scaling_command_interface_;
133 bool has_position_state_interface_ =
false;
134 bool has_velocity_state_interface_ =
false;
135 bool has_acceleration_state_interface_ =
false;
136 bool has_position_command_interface_ =
false;
137 bool has_velocity_command_interface_ =
false;
138 bool has_acceleration_command_interface_ =
false;
139 bool has_effort_command_interface_ =
false;
143 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
144 std::vector<PidPtr> pids_;
146 std::vector<double> ff_velocity_scale_;
149 std::vector<bool> joints_angle_wraparound_;
151 std::vector<double> tmp_command_;
154 bool should_decelerate_on_cancel_ =
false;
156 std::vector<double> max_decel_;
158 std::vector<double> stop_time_;
160 std::vector<double> hold_position_;
162 std::vector<double> stop_direction_;
164 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> stop_trajectory_;
167 std::atomic<double> scaling_factor_{1.0};
168 std::atomic<double> scaling_factor_cmd_{1.0};
173 std::atomic<bool> rt_is_holding_{
false};
175 std::atomic<bool> subscriber_is_active_{
false};
176 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
179 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
181 std::shared_ptr<Trajectory> current_trajectory_ =
nullptr;
185 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ =
nullptr;
187 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
189 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
190 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
191 StatePublisherPtr state_publisher_;
192 ControllerStateMsg state_msg_;
194 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
196 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
200 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
202 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
203 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
206 void topic_callback(
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
209 rclcpp_action::GoalResponse goal_received_callback(
210 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
211 rclcpp_action::CancelResponse goal_cancelled_callback(
212 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
213 void goal_accepted_callback(
214 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
216 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
227 JointTrajectoryPoint & error,
const size_t index,
const JointTrajectoryPoint & current,
228 const JointTrajectoryPoint & desired)
const;
231 void fill_partial_goal(
232 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
234 void sort_to_local_joint_order(
235 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
236 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
237 void add_new_trajectory_msg(
238 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
239 bool validate_trajectory_point_field(
240 size_t joint_names_size,
const std::vector<double> & vector_field,
241 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
248 void preempt_active_goal();
267 bool has_active_trajectory()
const;
270 const rclcpp::Time & time,
const JointTrajectoryPoint & desired_state,
271 const JointTrajectoryPoint & current_state,
const JointTrajectoryPoint & state_error);
273 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
282 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
284 void query_state_service(
285 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
286 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
291 bool contains_interface_type(
292 const std::vector<std::string> & interface_type_list,
const std::string & interface_type);
294 void init_hold_position_msg();
295 void resize_joint_trajectory_point(
296 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size,
double value = 0.0);
297 void resize_joint_trajectory_point_command(
298 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size,
double value = 0.0);
316 bool set_scaling_factor(
double scaling_factor);
318 using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor;
319 rclcpp::Subscription<SpeedScalingMsg>::SharedPtr scaling_factor_sub_;
329 template <
typename T>
330 void assign_interface_from_point(
331 const T & joint_interface,
const std::vector<double> & trajectory_point_interface)
333 for (
size_t index = 0; index < num_cmd_joints_; ++index)
335 if (!joint_interface[index].get().set_value(
336 trajectory_point_interface[map_cmd_to_joints_[index]]))
339 get_node()->get_logger(),
340 "Failed to set value for joint '%s' in command interface '%s'. ",
341 command_joint_names_[index].c_str(), joint_interface[index].get().get_name().c_str());