67 controller_interface::return_type
update(
68 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
70 controller_interface::CallbackReturn
on_init()
override;
72 controller_interface::CallbackReturn on_configure(
73 const rclcpp_lifecycle::State & previous_state)
override;
75 controller_interface::CallbackReturn on_activate(
76 const rclcpp_lifecycle::State & previous_state)
override;
78 controller_interface::CallbackReturn on_deactivate(
79 const rclcpp_lifecycle::State & previous_state)
override;
81 controller_interface::CallbackReturn on_error(
82 const rclcpp_lifecycle::State & previous_state)
override;
87 const std::vector<std::string> allowed_interface_types_ = {
95 trajectory_msgs::msg::JointTrajectoryPoint state_current_;
96 trajectory_msgs::msg::JointTrajectoryPoint command_current_;
97 trajectory_msgs::msg::JointTrajectoryPoint command_next_;
98 trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
99 trajectory_msgs::msg::JointTrajectoryPoint state_error_;
105 std::vector<std::string> command_joint_names_;
108 std::shared_ptr<ParamListener> param_listener_;
110 rclcpp::Duration update_period_{0, 0};
112 rclcpp::Time traj_time_;
114 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;
117 interpolation_methods::DEFAULT_INTERPOLATION};
122 template <
typename T>
123 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
125 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
126 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
128 bool has_position_state_interface_ =
false;
129 bool has_velocity_state_interface_ =
false;
130 bool has_acceleration_state_interface_ =
false;
131 bool has_position_command_interface_ =
false;
132 bool has_velocity_command_interface_ =
false;
133 bool has_acceleration_command_interface_ =
false;
134 bool has_effort_command_interface_ =
false;
138 using PidPtr = std::shared_ptr<control_toolbox::Pid>;
139 std::vector<PidPtr> pids_;
141 std::vector<double> ff_velocity_scale_;
144 std::vector<bool> joints_angle_wraparound_;
146 std::vector<double> tmp_command_;
153 bool subscriber_is_active_ =
false;
154 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
157 rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
159 std::shared_ptr<Trajectory> traj_external_point_ptr_ =
nullptr;
161 traj_msg_external_point_ptr_;
163 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> hold_position_msg_ptr_ =
nullptr;
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 using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
173 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
176 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
179 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
180 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
183 void topic_callback(
const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);
186 rclcpp_action::GoalResponse goal_received_callback(
187 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const FollowJTrajAction::Goal> goal);
188 rclcpp_action::CancelResponse goal_cancelled_callback(
189 const std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
190 void goal_accepted_callback(
191 std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
193 using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
204 JointTrajectoryPoint & error,
const size_t index,
const JointTrajectoryPoint & current,
205 const JointTrajectoryPoint & desired)
const;
208 void fill_partial_goal(
209 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
211 void sort_to_local_joint_order(
212 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
const;
213 bool validate_trajectory_msg(
const trajectory_msgs::msg::JointTrajectory & trajectory)
const;
214 void add_new_trajectory_msg(
215 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg);
216 bool validate_trajectory_point_field(
217 size_t joint_names_size,
const std::vector<double> & vector_field,
218 const std::string & string_for_vector_field,
size_t i,
bool allow_empty)
const;
225 void preempt_active_goal();
239 bool has_active_trajectory()
const;
242 const rclcpp::Time & time,
const JointTrajectoryPoint & desired_state,
243 const JointTrajectoryPoint & current_state,
const JointTrajectoryPoint & state_error);
245 void read_state_from_state_interfaces(JointTrajectoryPoint & state);
254 bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
256 void query_state_service(
257 const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
258 std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
263 bool contains_interface_type(
264 const std::vector<std::string> & interface_type_list,
const std::string & interface_type);
266 void init_hold_position_msg();
267 void resize_joint_trajectory_point(
268 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);
269 void resize_joint_trajectory_point_command(
270 trajectory_msgs::msg::JointTrajectoryPoint & point,
size_t size);
280 template <
typename T>
281 void assign_interface_from_point(
282 const T & joint_interface,
const std::vector<double> & trajectory_point_interface)
284 for (
size_t index = 0; index < dof_; ++index)
286 joint_interface[index].get().set_value(trajectory_point_interface[index]);