70 controller_interface::return_type
update(
71 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
73 controller_interface::CallbackReturn
on_init()
override;
75 controller_interface::CallbackReturn on_configure(
76 const rclcpp_lifecycle::State & previous_state)
override;
78 controller_interface::CallbackReturn on_activate(
79 const rclcpp_lifecycle::State & previous_state)
override;
81 controller_interface::CallbackReturn on_deactivate(
82 const rclcpp_lifecycle::State & previous_state)
override;
84 controller_interface::CallbackReturn on_error(
85 const rclcpp_lifecycle::State & previous_state)
override;
90 const std::vector<std::string> allowed_interface_types_ = {
98 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
99 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
100 trajectory_msgs::msg::JointTrajectoryPoint command_next_;
101 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
102 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
106 size_t num_cmd_joints_;
107 std::vector<size_t> map_cmd_to_joints_;
110 std::vector<std::string> command_joint_names_;
113 std::shared_ptr<ParamListener> param_listener_;
115 rclcpp::Duration update_period_{0, 0};
117 rclcpp::Time traj_time_;
120 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
121 rclcpp::Time last_commanded_time_;
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_;
134 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
135 scaling_state_interface_;
136 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
137 scaling_command_interface_;
139 bool has_position_state_interface_ =
false;
140 bool has_velocity_state_interface_ =
false;
141 bool has_acceleration_state_interface_ =
false;
142 bool has_position_command_interface_ =
false;
143 bool has_velocity_command_interface_ =
false;
144 bool has_acceleration_command_interface_ =
false;
145 bool has_effort_command_interface_ =
false;
149 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
150 std::vector<PidPtr> pids_;
152 std::vector<double> ff_velocity_scale_;
155 std::vector<bool> joints_angle_wraparound_;
157 std::vector<double> tmp_command_;
160 std::atomic<double> scaling_factor_{1.0};
161 std::atomic<double> scaling_factor_cmd_{1.0};
166 std::atomic<bool> rt_is_holding_{
false};
168 std::atomic<bool> subscriber_is_active_{
false};
169 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
172 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
174 std::shared_ptr<Trajectory> current_trajectory_ =
nullptr;
178 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ =
nullptr;
180 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
182 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
183 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
184 StatePublisherPtr state_publisher_;
186 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
188 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
191 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
194 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
195 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
198 void topic_callback(
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
201 rclcpp_action::GoalResponse goal_received_callback(
202 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
203 rclcpp_action::CancelResponse goal_cancelled_callback(
204 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
205 void goal_accepted_callback(
206 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
208 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
219 JointTrajectoryPoint & error,
const size_t index,
const JointTrajectoryPoint & current,
220 const JointTrajectoryPoint & desired)
const;
223 void fill_partial_goal(
224 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
226 void sort_to_local_joint_order(
227 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
228 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
229 void add_new_trajectory_msg(
230 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
231 bool validate_trajectory_point_field(
232 size_t joint_names_size,
const std::vector<double> & vector_field,
233 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
240 void preempt_active_goal();
254 bool has_active_trajectory()
const;
257 const rclcpp::Time & time,
const JointTrajectoryPoint & desired_state,
258 const JointTrajectoryPoint & current_state,
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,
double value = 0.0);
284 void resize_joint_trajectory_point_command(
285 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size,
double value = 0.0);
303 bool set_scaling_factor(
double scaling_factor);
305 using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor;
306 rclcpp::Subscription<SpeedScalingMsg>::SharedPtr scaling_factor_sub_;
316 template <
typename T>
317 void assign_interface_from_point(
318 const T & joint_interface,
const std::vector<double> & trajectory_point_interface)
320 for (
size_t index = 0; index < num_cmd_joints_; ++index)
322 if (!joint_interface[index].get().set_value(
323 trajectory_point_interface[map_cmd_to_joints_[index]]))
326 get_node()->get_logger(),
327 "Failed to set value for joint '%s' in command interface '%s'. ",
328 command_joint_names_[index].c_str(), joint_interface[index].get().get_name().c_str());