79 GRIPPER_ACTION_CONTROLLER_PUBLIC
86 GRIPPER_ACTION_CONTROLLER_PUBLIC
89 GRIPPER_ACTION_CONTROLLER_PUBLIC
90 controller_interface::return_type
update(
91 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
93 GRIPPER_ACTION_CONTROLLER_PUBLIC
94 controller_interface::CallbackReturn
on_init()
override;
96 GRIPPER_ACTION_CONTROLLER_PUBLIC
97 controller_interface::CallbackReturn on_configure(
98 const rclcpp_lifecycle::State & previous_state)
override;
100 GRIPPER_ACTION_CONTROLLER_PUBLIC
101 controller_interface::CallbackReturn on_activate(
102 const rclcpp_lifecycle::State & previous_state)
override;
104 GRIPPER_ACTION_CONTROLLER_PUBLIC
105 controller_interface::CallbackReturn on_deactivate(
106 const rclcpp_lifecycle::State & previous_state)
override;
110 Commands command_struct_, command_struct_rt_;
113 using GripperCommandAction = control_msgs::action::GripperCommand;
114 using ActionServer = rclcpp_action::Server<GripperCommandAction>;
115 using ActionServerPtr = ActionServer::SharedPtr;
116 using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
119 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
124 bool update_hold_position_;
128 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
129 joint_command_interface_;
130 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
131 joint_position_state_interface_;
132 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
133 joint_velocity_state_interface_;
135 std::shared_ptr<ParamListener> param_listener_;
142 control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_;
144 rclcpp::Duration action_monitor_period_;
147 ActionServerPtr action_server_;
149 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
151 rclcpp_action::GoalResponse goal_callback(
152 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
154 rclcpp_action::CancelResponse cancel_callback(
const std::shared_ptr<GoalHandle> goal_handle);
156 void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
158 void preempt_active_goal();
160 void set_hold_position();
169 const rclcpp::Time & time,
double error_position,
double current_position,
170 double current_velocity);