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;
100 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
101 controller_interface::CallbackReturn on_shutdown(
102 const rclcpp_lifecycle::State & previous_state)
override;
107 const std::vector<std::string> allowed_interface_types_ = {
115 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
116 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
117 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
118 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
124 std::vector<std::string> command_joint_names_;
127 std::shared_ptr<ParamListener> param_listener_;
130 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
133 interpolation_methods::DEFAULT_INTERPOLATION};
138 template <
typename T>
139 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
141 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
142 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
144 bool has_position_state_interface_ =
false;
145 bool has_velocity_state_interface_ =
false;
146 bool has_acceleration_state_interface_ =
false;
147 bool has_position_command_interface_ =
false;
148 bool has_velocity_command_interface_ =
false;
149 bool has_acceleration_command_interface_ =
false;
150 bool has_effort_command_interface_ =
false;
154 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
155 std::vector<PidPtr> pids_;
157 std::vector<double> ff_velocity_scale_;
160 std::vector<bool> joints_angle_wraparound_;
162 std::vector<double> tmp_command_;
169 bool subscriber_is_active_ =
false;
170 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
173 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
175 std::shared_ptr<Trajectory> traj_external_point_ptr_ =
nullptr;
177 traj_msg_external_point_ptr_;
179 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ =
nullptr;
181 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
183 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
184 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
185 StatePublisherPtr state_publisher_;
187 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
189 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
192 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
195 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
196 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
199 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
200 void topic_callback(
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
203 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
204 rclcpp_action::GoalResponse goal_received_callback(
205 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
206 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
207 rclcpp_action::CancelResponse goal_cancelled_callback(
208 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
209 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
210 void goal_accepted_callback(
211 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
213 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
223 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
225 JointTrajectoryPoint & error,
const size_t index,
const JointTrajectoryPoint & current,
226 const JointTrajectoryPoint & desired)
const;
229 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
230 void fill_partial_goal(
231 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
233 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
234 void sort_to_local_joint_order(
235 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
236 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
237 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
238 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
239 void add_new_trajectory_msg(
240 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
241 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
242 bool validate_trajectory_point_field(
243 size_t joint_names_size,
const std::vector<double> & vector_field,
244 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
251 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
252 void preempt_active_goal();
256 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
263 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
266 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
269 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
270 bool has_active_trajectory()
const;
272 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
274 const rclcpp::Time & time,
const JointTrajectoryPoint & desired_state,
275 const JointTrajectoryPoint & current_state,
const JointTrajectoryPoint & state_error);
277 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
286 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
288 void query_state_service(
289 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
290 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
295 bool contains_interface_type(
296 const std::vector<std::string> & interface_type_list,
const std::string & interface_type);
298 void init_hold_position_msg();
299 void resize_joint_trajectory_point(
300 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);
301 void resize_joint_trajectory_point_command(
302 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);
312 template <
typename T>
313 void assign_interface_from_point(
314 const T & joint_interface,
const std::vector<double> & trajectory_point_interface)
316 for (
size_t index = 0; index < dof_; ++index)
318 joint_interface[index].get().set_value(trajectory_point_interface[index]);