58 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
64 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
70 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
73 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
74 controller_interface::return_type
update(
75 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
77 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
78 controller_interface::CallbackReturn
on_init()
override;
80 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
81 controller_interface::CallbackReturn on_configure(
82 const rclcpp_lifecycle::State & previous_state)
override;
84 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
85 controller_interface::CallbackReturn on_activate(
86 const rclcpp_lifecycle::State & previous_state)
override;
88 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
89 controller_interface::CallbackReturn on_deactivate(
90 const rclcpp_lifecycle::State & previous_state)
override;
92 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
93 controller_interface::CallbackReturn on_cleanup(
94 const rclcpp_lifecycle::State & previous_state)
override;
96 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
97 controller_interface::CallbackReturn on_error(
98 const rclcpp_lifecycle::State & previous_state)
override;
103 const std::vector<std::string> allowed_interface_types_ = {
111 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
112 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
113 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
114 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
120 std::vector<std::string> command_joint_names_;
123 std::shared_ptr<ParamListener> param_listener_;
126 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
129 interpolation_methods::DEFAULT_INTERPOLATION};
134 template <
typename T>
135 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
137 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
138 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
140 bool has_position_state_interface_ =
false;
141 bool has_velocity_state_interface_ =
false;
142 bool has_acceleration_state_interface_ =
false;
143 bool has_position_command_interface_ =
false;
144 bool has_velocity_command_interface_ =
false;
145 bool has_acceleration_command_interface_ =
false;
146 bool has_effort_command_interface_ =
false;
150 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
151 std::vector<PidPtr> pids_;
153 std::vector<double> ff_velocity_scale_;
156 std::vector<bool> joints_angle_wraparound_;
158 std::vector<double> tmp_command_;
165 bool subscriber_is_active_ =
false;
166 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
169 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
171 std::shared_ptr<Trajectory> traj_external_point_ptr_ =
nullptr;
173 traj_msg_external_point_ptr_;
175 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ =
nullptr;
177 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
179 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
180 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_legacy_;
181 StatePublisherPtr state_publisher_legacy_;
182 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
183 StatePublisherPtr state_publisher_;
185 rclcpp::Duration state_publisher_period_ = rclcpp::Duration(20ms);
186 rclcpp::Time last_state_publish_time_;
188 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
190 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
193 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
196 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
197 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
200 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
201 void topic_callback(
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
204 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
205 rclcpp_action::GoalResponse goal_received_callback(
206 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
207 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
208 rclcpp_action::CancelResponse goal_cancelled_callback(
209 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
210 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
211 void goal_accepted_callback(
212 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
216 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
217 void fill_partial_goal(
218 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
220 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
221 void sort_to_local_joint_order(
222 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg);
223 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
224 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
225 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
226 void add_new_trajectory_msg(
227 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
228 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
229 bool validate_trajectory_point_field(
230 size_t joint_names_size,
const std::vector<double> & vector_field,
231 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
238 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
239 void preempt_active_goal();
243 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
250 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
253 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
256 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
257 bool has_active_trajectory()
const;
259 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
260 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
262 const JointTrajectoryPoint & desired_state,
const JointTrajectoryPoint & current_state,
263 const JointTrajectoryPoint & state_error);
265 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
274 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
276 void query_state_service(
277 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
278 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
283 bool contains_interface_type(
284 const std::vector<std::string> & interface_type_list,
const std::string & interface_type);
286 void init_hold_position_msg();
287 void resize_joint_trajectory_point(
288 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);
289 void resize_joint_trajectory_point_command(
290 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);