68 controller_interface::return_type
update(
69 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
71 controller_interface::CallbackReturn
on_init()
override;
73 controller_interface::CallbackReturn on_configure(
74 const rclcpp_lifecycle::State & previous_state)
override;
76 controller_interface::CallbackReturn on_activate(
77 const rclcpp_lifecycle::State & previous_state)
override;
79 controller_interface::CallbackReturn on_deactivate(
80 const rclcpp_lifecycle::State & previous_state)
override;
82 controller_interface::CallbackReturn on_error(
83 const rclcpp_lifecycle::State & previous_state)
override;
88 const std::vector<std::string> allowed_interface_types_ = {
96 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
97 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
98 trajectory_msgs::msg::JointTrajectoryPoint command_next_;
99 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
100 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
104 size_t num_cmd_joints_;
105 std::vector<size_t> map_cmd_to_joints_;
108 std::vector<std::string> command_joint_names_;
111 std::shared_ptr<ParamListener> param_listener_;
113 rclcpp::Duration update_period_{0, 0};
115 rclcpp::Time traj_time_;
118 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
119 rclcpp::Time last_commanded_time_;
122 interpolation_methods::DEFAULT_INTERPOLATION};
127 template <
typename T>
128 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
130 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
131 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_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_;
156 std::atomic<bool> rt_is_holding_{
false};
158 std::atomic<bool> subscriber_is_active_{
false};
159 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
162 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
164 std::shared_ptr<Trajectory> current_trajectory_ =
nullptr;
168 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ =
nullptr;
170 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
172 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
173 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
174 StatePublisherPtr state_publisher_;
176 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
178 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
181 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
184 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
185 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
188 void topic_callback(
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
191 rclcpp_action::GoalResponse goal_received_callback(
192 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
193 rclcpp_action::CancelResponse goal_cancelled_callback(
194 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
195 void goal_accepted_callback(
196 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
198 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
209 JointTrajectoryPoint & error,
const size_t index,
const JointTrajectoryPoint & current,
210 const JointTrajectoryPoint & desired)
const;
213 void fill_partial_goal(
214 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
216 void sort_to_local_joint_order(
217 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
218 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
219 void add_new_trajectory_msg(
220 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
221 bool validate_trajectory_point_field(
222 size_t joint_names_size,
const std::vector<double> & vector_field,
223 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
230 void preempt_active_goal();
244 bool has_active_trajectory()
const;
247 const rclcpp::Time & time,
const JointTrajectoryPoint & desired_state,
248 const JointTrajectoryPoint & current_state,
const JointTrajectoryPoint & state_error);
250 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
259 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
261 void query_state_service(
262 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
263 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
268 bool contains_interface_type(
269 const std::vector<std::string> & interface_type_list,
const std::string & interface_type);
271 void init_hold_position_msg();
272 void resize_joint_trajectory_point(
273 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size,
double value = 0.0);
274 void resize_joint_trajectory_point_command(
275 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size,
double value = 0.0);
285 template <
typename T>
286 void assign_interface_from_point(
287 const T & joint_interface,
const std::vector<double> & trajectory_point_interface)
289 for (
size_t index = 0; index < num_cmd_joints_; ++index)
291 joint_interface[index].get().set_value(trajectory_point_interface[map_cmd_to_joints_[index]]);