77 GRIPPER_ACTION_CONTROLLER_PUBLIC
84 GRIPPER_ACTION_CONTROLLER_PUBLIC
87 GRIPPER_ACTION_CONTROLLER_PUBLIC
88 controller_interface::return_type
update(
89 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
91 GRIPPER_ACTION_CONTROLLER_PUBLIC
92 controller_interface::CallbackReturn
on_init()
override;
94 GRIPPER_ACTION_CONTROLLER_PUBLIC
95 controller_interface::CallbackReturn on_configure(
96 const rclcpp_lifecycle::State & previous_state)
override;
98 GRIPPER_ACTION_CONTROLLER_PUBLIC
99 controller_interface::CallbackReturn on_activate(
100 const rclcpp_lifecycle::State & previous_state)
override;
102 GRIPPER_ACTION_CONTROLLER_PUBLIC
103 controller_interface::CallbackReturn on_deactivate(
104 const rclcpp_lifecycle::State & previous_state)
override;
108 Commands command_struct_, command_struct_rt_;
111 using GripperCommandAction = control_msgs::action::GripperCommand;
112 using ActionServer = rclcpp_action::Server<GripperCommandAction>;
113 using ActionServerPtr = ActionServer::SharedPtr;
114 using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
117 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
122 bool update_hold_position_;
126 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
127 joint_command_interface_;
128 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
129 joint_position_state_interface_;
130 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
131 joint_velocity_state_interface_;
133 std::shared_ptr<ParamListener> param_listener_;
140 control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_;
142 rclcpp::Duration action_monitor_period_;
145 ActionServerPtr action_server_;
147 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
149 rclcpp_action::GoalResponse goal_callback(
150 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
152 rclcpp_action::CancelResponse cancel_callback(
const std::shared_ptr<GoalHandle> goal_handle);
154 void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
156 void preempt_active_goal();
158 void set_hold_position();
167 const rclcpp::Time & time,
double error_position,
double current_position,
168 double current_velocity);