66 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
73 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
80 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
83 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
84 controller_interface::return_type update(
85 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
87 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
88 CallbackReturn on_init()
override;
90 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
91 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
93 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
94 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
96 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
97 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
99 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
100 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
102 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
103 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
105 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
106 CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & previous_state)
override;
109 std::vector<std::string> joint_names_;
110 std::vector<std::string> command_interface_types_;
111 std::vector<std::string> state_interface_types_;
115 const std::vector<std::string> allowed_interface_types_ = {
126 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
131 template <
typename T>
132 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
134 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
135 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
137 bool has_velocity_state_interface_ =
false;
138 bool has_acceleration_state_interface_ =
false;
139 bool has_position_command_interface_ =
false;
140 bool has_velocity_command_interface_ =
false;
141 bool has_acceleration_command_interface_ =
false;
150 bool subscriber_is_active_ =
false;
151 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
154 std::shared_ptr<Trajectory> * traj_point_active_ptr_ =
nullptr;
155 std::shared_ptr<Trajectory> traj_external_point_ptr_ =
nullptr;
156 std::shared_ptr<Trajectory> traj_home_point_ptr_ =
nullptr;
157 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> traj_msg_home_ptr_ =
nullptr;
159 traj_msg_external_point_ptr_;
163 bool is_halted_ =
true;
165 using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
167 using StatePublisherPtr = std::unique_ptr<StatePublisher>;
168 rclcpp::Publisher<ControllerStateMsg>::SharedPtr publisher_;
169 StatePublisherPtr state_publisher_;
171 rclcpp::Duration state_publisher_period_ = rclcpp::Duration(20ms);
172 rclcpp::Time last_state_publish_time_;
174 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
176 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
179 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
180 bool allow_partial_joints_goal_ =
false;
182 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
183 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
186 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
187 rclcpp_action::GoalResponse goal_callback(
188 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
189 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
190 rclcpp_action::CancelResponse cancel_callback(
192 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
193 void feedback_setup_callback(
198 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
199 void fill_partial_goal(
200 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
202 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
203 void sort_to_local_joint_order(
204 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg);
205 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
206 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
207 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
208 void add_new_trajectory_msg(
209 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
210 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
211 bool validate_trajectory_point_field(
212 size_t joint_names_size,
const std::vector<double> & vector_field,
213 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
217 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
218 void preempt_active_goal();
219 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
220 void set_hold_position();
222 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
225 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
226 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
228 const JointTrajectoryPoint & desired_state,
const JointTrajectoryPoint & current_state,
229 const JointTrajectoryPoint & state_error);
231 void read_state_from_hardware(JointTrajectoryPoint & state);
233 bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
236 bool contains_interface_type(
237 const std::vector<std::string> & interface_type_list,
const std::string & interface_type);
239 void resize_joint_trajectory_point(
240 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);