82 controller_interface::return_type
update(
83 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
85 controller_interface::CallbackReturn
on_init()
override;
87 controller_interface::CallbackReturn on_configure(
88 const rclcpp_lifecycle::State & previous_state)
override;
90 controller_interface::CallbackReturn on_activate(
91 const rclcpp_lifecycle::State & previous_state)
override;
93 controller_interface::CallbackReturn on_deactivate(
94 const rclcpp_lifecycle::State & previous_state)
override;
97 using GripperCommandAction = control_msgs::action::ParallelGripperCommand;
98 using ActionServer = rclcpp_action::Server<GripperCommandAction>;
99 using ActionServerPtr = ActionServer::SharedPtr;
100 using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
103 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
114 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
115 joint_command_interface_;
116 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
118 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
120 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
121 joint_position_state_interface_;
122 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
123 joint_velocity_state_interface_;
125 std::shared_ptr<ParamListener> param_listener_;
130 control_msgs::action::ParallelGripperCommand::Result::SharedPtr pre_alloc_result_;
132 rclcpp::Duration action_monitor_period_;
135 ActionServerPtr action_server_;
137 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
139 rclcpp_action::GoalResponse goal_callback(
140 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
142 rclcpp_action::CancelResponse cancel_callback(
const std::shared_ptr<GoalHandle> goal_handle);
144 void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
146 void preempt_active_goal();
148 void set_hold_position();
157 const rclcpp::Time & time,
double error_position,
double current_position,
158 double current_velocity);