ros2_control - rolling
Classes | Public Member Functions | Public Attributes | Protected Types | Protected Member Functions | Protected Attributes | List of all members
gripper_action_controller::GripperActionController< HardwareInterface > Class Template Reference

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

#include <gripper_action_controller.hpp>

Inheritance diagram for gripper_action_controller::GripperActionController< HardwareInterface >:
Inheritance graph
[legend]
Collaboration diagram for gripper_action_controller::GripperActionController< HardwareInterface >:
Collaboration graph
[legend]

Classes

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

Public Member Functions

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
 Extending interface with initialization method which is individual for each controller.
 
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 Member Functions inherited from controller_interface::ControllerInterface
CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterfaceexport_state_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterfaceexport_reference_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode (bool chained_mode) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const final
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
virtual CONTROLLER_INTERFACE_PUBLIC void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 Method that assigns the Loaned interfaces to the controller. More...
 
virtual CONTROLLER_INTERFACE_PUBLIC void release_interfaces ()
 Method that releases the Loaned interfaces from the controller. More...
 
CONTROLLER_INTERFACE_PUBLIC return_type init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options)
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > get_node () const
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state () const
 
CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate () const
 
CONTROLLER_INTERFACE_PUBLIC bool is_async () const
 
CONTROLLER_INTERFACE_PUBLIC const std::string & get_robot_description () const
 
virtual CONTROLLER_INTERFACE_PUBLIC rclcpp::NodeOptions define_custom_node_options () const
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type. More...
 

Public Attributes

realtime_tools::RealtimeBuffer< Commandscommand_
 
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 Member 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.
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 

Detailed Description

template<const char * HardwareInterface>
class gripper_action_controller::GripperActionController< HardwareInterface >

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

Template Parameters
HardwareInterfaceController hardware interface. Currently hardware_interface::HW_IF_POSITION and hardware_interface::HW_IF_EFFORT are supported out-of-the-box.

Member Function Documentation

◆ update()

template<const char * HardwareInterface>
controller_interface::return_type gripper_action_controller::GripperActionController< HardwareInterface >::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ControllerInterfaceBase.


The documentation for this class was generated from the following files: