74 GRIPPER_ACTION_CONTROLLER_PUBLIC
75 controller_interface::return_type init(
const std::string & controller_name)
override;
81 GRIPPER_ACTION_CONTROLLER_PUBLIC
88 GRIPPER_ACTION_CONTROLLER_PUBLIC
91 GRIPPER_ACTION_CONTROLLER_PUBLIC
92 controller_interface::return_type update()
override;
94 GRIPPER_ACTION_CONTROLLER_PUBLIC
95 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
96 const rclcpp_lifecycle::State & previous_state)
override;
98 GRIPPER_ACTION_CONTROLLER_PUBLIC
99 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
100 const rclcpp_lifecycle::State & previous_state)
override;
102 GRIPPER_ACTION_CONTROLLER_PUBLIC
103 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::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;
117 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
121 bool update_hold_position_;
123 bool verbose_ =
false;
125 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
126 joint_position_command_interface_;
127 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
128 joint_position_state_interface_;
129 std::experimental::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
130 joint_velocity_state_interface_;
132 std::string joint_name_;
136 RealtimeGoalHandlePtr rt_active_goal_;
137 control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_;
139 rclcpp::Duration action_monitor_period_;
142 ActionServerPtr action_server_;
144 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
146 rclcpp_action::GoalResponse goal_callback(
147 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
149 rclcpp_action::CancelResponse cancel_callback(
const std::shared_ptr<GoalHandle> goal_handle);
151 void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
153 void preempt_active_goal();
155 void set_hold_position();
157 rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
158 double computed_command_;
160 double stall_timeout_,
161 stall_velocity_threshold_;
162 double default_max_effort_;
163 double goal_tolerance_;
168 void check_for_success(
169 const rclcpp::Time & time,
double error_position,
double current_position,
170 double current_velocity);