Template Class GripperActionController

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public controller_interface::ControllerInterface

Class Documentation

template<const char *HardwareInterface>
class GripperActionController : public controller_interface::ControllerInterface

Controller for executing a gripper command action for simple single-dof grippers.

Template Parameters:

HardwareInterface – Controller hardware interface. Currently hardware_interface::HW_IF_POSITION and hardware_interface::HW_IF_EFFORT are supported out-of-the-box.

Public Functions

GRIPPER_ACTION_CONTROLLER_PUBLIC GripperActionController()
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override

command_interface_configuration This controller requires the position command interfaces for the controlled joints

GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override

command_interface_configuration This controller requires the position and velocity state interfaces for the controlled joints

GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
GRIPPER_ACTION_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override

Public Members

realtime_tools::RealtimeBuffer<Commands> command_
Commands command_struct_
Commands command_struct_rt_

Protected Types

using GripperCommandAction = control_msgs::action::GripperCommand
using ActionServer = rclcpp_action::Server<GripperCommandAction>
using ActionServerPtr = ActionServer::SharedPtr
using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<control_msgs::action::GripperCommand>
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>
using HwIfaceAdapter = HardwareInterfaceAdapter<HardwareInterface>

Protected Functions

rclcpp_action::GoalResponse goal_callback(const rclcpp_action::GoalUUID &uuid, std::shared_ptr<const GripperCommandAction::Goal> goal)
rclcpp_action::CancelResponse cancel_callback(const std::shared_ptr<GoalHandle> goal_handle)
void accepted_callback(std::shared_ptr<GoalHandle> goal_handle)
void preempt_active_goal()
void set_hold_position()
void check_for_success(const rclcpp::Time &time, double error_position, double current_position, double current_velocity)

Check for success and publish appropriate result and feedback.

Protected Attributes

bool update_hold_position_
bool verbose_ = false

Hard coded verbose flag to help in debugging.

std::string name_

Controller name.

std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> joint_command_interface_
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> joint_position_state_interface_
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> joint_velocity_state_interface_
std::shared_ptr<ParamListener> param_listener_
Params params_
HwIfaceAdapter hw_iface_adapter_

Adapts desired goal state to HW interface.

RealtimeGoalHandleBuffer rt_active_goal_

Container for the currently active action goal, if any.

control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_
rclcpp::Duration action_monitor_period_
ActionServerPtr action_server_
rclcpp::TimerBase::SharedPtr goal_handle_timer_
rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME)

Store stall time.

double computed_command_

Computed command.

struct Commands

Store position and max effort in struct to allow easier realtime buffer usage.

Public Members

double position_
double max_effort_