Classes | Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private 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.h>

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

Classes

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

Public Member Functions

 GripperActionController ()
 
Non Real-Time Safe Functions
bool init (HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
Real-Time Safe Functions
void starting (const ros::Time &time)
 Holds the current position. More...
 
void stopping (const ros::Time &time)
 Cancels the active action goal, if any. More...
 
void update (const ros::Time &time, const ros::Duration &period)
 
- Public Member Functions inherited from controller_interface::Controller< HardwareInterface >
virtual bool init (T *, ros::NodeHandle &)
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

Public Attributes

realtime_tools::RealtimeBuffer< Commandscommand_
 
Commands command_struct_
 
Commands command_struct_rt_
 
- Public Attributes inherited from controller_interface::ControllerBase
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 

Private Types

typedef actionlib::ActionServer< control_msgs::GripperCommandAction > ActionServer
 
typedef std::shared_ptr< ActionServerActionServerPtr
 
typedef ActionServer::GoalHandle GoalHandle
 
typedef HardwareInterfaceAdapter< HardwareInterface > HwIfaceAdapter
 
typedef realtime_tools::RealtimeServerGoalHandle< control_msgs::GripperCommandAction > RealtimeGoalHandle
 
typedef boost::shared_ptr< RealtimeGoalHandleRealtimeGoalHandlePtr
 

Private Member Functions

void cancelCB (GoalHandle gh)
 
void checkForSuccess (const ros::Time &time, double error_position, double current_position, double current_velocity)
 Check for success and publish appropriate result and feedback. More...
 
void goalCB (GoalHandle gh)
 
void preemptActiveGoal ()
 
void setHoldPosition (const ros::Time &time)
 

Private Attributes

ros::Duration action_monitor_period_
 
ActionServerPtr action_server_
 
double computed_command_
 Computed command. More...
 
ros::NodeHandle controller_nh_
 
double default_max_effort_
 Max allowed effort. More...
 
ros::Timer goal_handle_timer_
 
double goal_tolerance_
 
HwIfaceAdapter hw_iface_adapter_
 Adapts desired goal state to HW interface. More...
 
hardware_interface::JointHandle joint_
 Handles to controlled joints. More...
 
std::string joint_name_
 Controlled joint names. More...
 
ros::Time last_movement_time_
 Store stall time. More...
 
std::string name_
 Controller name. More...
 
control_msgs::GripperCommandResultPtr pre_alloc_result_
 
RealtimeGoalHandlePtr rt_active_goal_
 Currently active action goal, if any. More...
 
double stall_timeout_
 
double stall_velocity_threshold_
 Stall related parameters. More...
 
bool update_hold_position_
 
bool verbose_
 Hard coded verbose flag to help in debugging. More...
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Protected Member Functions inherited from controller_interface::Controller< HardwareInterface >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Detailed Description

template<class 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::PositionJointInterface and hardware_interface::EffortJointInterface are supported out-of-the-box.

Definition at line 71 of file gripper_action_controller.h.

Member Typedef Documentation

◆ ActionServer

template<class HardwareInterface >
typedef actionlib::ActionServer<control_msgs::GripperCommandAction> gripper_action_controller::GripperActionController< HardwareInterface >::ActionServer
private

Definition at line 107 of file gripper_action_controller.h.

◆ ActionServerPtr

template<class HardwareInterface >
typedef std::shared_ptr<ActionServer> gripper_action_controller::GripperActionController< HardwareInterface >::ActionServerPtr
private

Definition at line 108 of file gripper_action_controller.h.

◆ GoalHandle

template<class HardwareInterface >
typedef ActionServer::GoalHandle gripper_action_controller::GripperActionController< HardwareInterface >::GoalHandle
private

Definition at line 109 of file gripper_action_controller.h.

◆ HwIfaceAdapter

template<class HardwareInterface >
typedef HardwareInterfaceAdapter<HardwareInterface> gripper_action_controller::GripperActionController< HardwareInterface >::HwIfaceAdapter
private

Definition at line 113 of file gripper_action_controller.h.

◆ RealtimeGoalHandle

template<class HardwareInterface >
typedef realtime_tools::RealtimeServerGoalHandle<control_msgs::GripperCommandAction> gripper_action_controller::GripperActionController< HardwareInterface >::RealtimeGoalHandle
private

Definition at line 110 of file gripper_action_controller.h.

◆ RealtimeGoalHandlePtr

template<class HardwareInterface >
typedef boost::shared_ptr<RealtimeGoalHandle> gripper_action_controller::GripperActionController< HardwareInterface >::RealtimeGoalHandlePtr
private

Definition at line 111 of file gripper_action_controller.h.

Constructor & Destructor Documentation

◆ GripperActionController()

template<class HardwareInterface >
gripper_action_controller::GripperActionController< HardwareInterface >::GripperActionController ( )

Definition at line 127 of file gripper_action_controller_impl.h.

Member Function Documentation

◆ cancelCB()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::cancelCB ( GoalHandle  gh)
private

Definition at line 285 of file gripper_action_controller_impl.h.

◆ checkForSuccess()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::checkForSuccess ( const ros::Time time,
double  error_position,
double  current_position,
double  current_velocity 
)
private

Check for success and publish appropriate result and feedback.

Definition at line 315 of file gripper_action_controller_impl.h.

◆ goalCB()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::goalCB ( GoalHandle  gh)
private

Definition at line 244 of file gripper_action_controller_impl.h.

◆ init()

template<class HardwareInterface >
bool gripper_action_controller::GripperActionController< HardwareInterface >::init ( HardwareInterface *  hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)

Definition at line 132 of file gripper_action_controller_impl.h.

◆ preemptActiveGoal()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::preemptActiveGoal ( )
inlineprivate

Definition at line 111 of file gripper_action_controller_impl.h.

◆ setHoldPosition()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::setHoldPosition ( const ros::Time time)
private

Definition at line 306 of file gripper_action_controller_impl.h.

◆ starting()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::starting ( const ros::Time time)
inlinevirtual

Holds the current position.

Reimplemented from controller_interface::ControllerBase.

Definition at line 91 of file gripper_action_controller_impl.h.

◆ stopping()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::stopping ( const ros::Time time)
inlinevirtual

Cancels the active action goal, if any.

Reimplemented from controller_interface::ControllerBase.

Definition at line 104 of file gripper_action_controller_impl.h.

◆ update()

template<class HardwareInterface >
void gripper_action_controller::GripperActionController< HardwareInterface >::update ( const ros::Time time,
const ros::Duration period 
)
virtual

Member Data Documentation

◆ action_monitor_period_

template<class HardwareInterface >
ros::Duration gripper_action_controller::GripperActionController< HardwareInterface >::action_monitor_period_
private

Definition at line 127 of file gripper_action_controller.h.

◆ action_server_

template<class HardwareInterface >
ActionServerPtr gripper_action_controller::GripperActionController< HardwareInterface >::action_server_
private

Definition at line 131 of file gripper_action_controller.h.

◆ command_

template<class HardwareInterface >
realtime_tools::RealtimeBuffer<Commands> gripper_action_controller::GripperActionController< HardwareInterface >::command_

Definition at line 102 of file gripper_action_controller.h.

◆ command_struct_

template<class HardwareInterface >
Commands gripper_action_controller::GripperActionController< HardwareInterface >::command_struct_

Definition at line 103 of file gripper_action_controller.h.

◆ command_struct_rt_

template<class HardwareInterface >
Commands gripper_action_controller::GripperActionController< HardwareInterface >::command_struct_rt_

Definition at line 103 of file gripper_action_controller.h.

◆ computed_command_

template<class HardwareInterface >
double gripper_action_controller::GripperActionController< HardwareInterface >::computed_command_
private

Computed command.

Definition at line 141 of file gripper_action_controller.h.

◆ controller_nh_

template<class HardwareInterface >
ros::NodeHandle gripper_action_controller::GripperActionController< HardwareInterface >::controller_nh_
private

Definition at line 130 of file gripper_action_controller.h.

◆ default_max_effort_

template<class HardwareInterface >
double gripper_action_controller::GripperActionController< HardwareInterface >::default_max_effort_
private

Max allowed effort.

Definition at line 144 of file gripper_action_controller.h.

◆ goal_handle_timer_

template<class HardwareInterface >
ros::Timer gripper_action_controller::GripperActionController< HardwareInterface >::goal_handle_timer_
private

Definition at line 133 of file gripper_action_controller.h.

◆ goal_tolerance_

template<class HardwareInterface >
double gripper_action_controller::GripperActionController< HardwareInterface >::goal_tolerance_
private

Definition at line 145 of file gripper_action_controller.h.

◆ hw_iface_adapter_

template<class HardwareInterface >
HwIfaceAdapter gripper_action_controller::GripperActionController< HardwareInterface >::hw_iface_adapter_
private

Adapts desired goal state to HW interface.

Definition at line 122 of file gripper_action_controller.h.

◆ joint_

template<class HardwareInterface >
hardware_interface::JointHandle gripper_action_controller::GripperActionController< HardwareInterface >::joint_
private

Handles to controlled joints.

Definition at line 119 of file gripper_action_controller.h.

◆ joint_name_

template<class HardwareInterface >
std::string gripper_action_controller::GripperActionController< HardwareInterface >::joint_name_
private

Controlled joint names.

Definition at line 120 of file gripper_action_controller.h.

◆ last_movement_time_

template<class HardwareInterface >
ros::Time gripper_action_controller::GripperActionController< HardwareInterface >::last_movement_time_
private

Store stall time.

Definition at line 140 of file gripper_action_controller.h.

◆ name_

template<class HardwareInterface >
std::string gripper_action_controller::GripperActionController< HardwareInterface >::name_
private

Controller name.

Definition at line 118 of file gripper_action_controller.h.

◆ pre_alloc_result_

template<class HardwareInterface >
control_msgs::GripperCommandResultPtr gripper_action_controller::GripperActionController< HardwareInterface >::pre_alloc_result_
private

Definition at line 125 of file gripper_action_controller.h.

◆ rt_active_goal_

template<class HardwareInterface >
RealtimeGoalHandlePtr gripper_action_controller::GripperActionController< HardwareInterface >::rt_active_goal_
private

Currently active action goal, if any.

Definition at line 124 of file gripper_action_controller.h.

◆ stall_timeout_

template<class HardwareInterface >
double gripper_action_controller::GripperActionController< HardwareInterface >::stall_timeout_
private

Definition at line 143 of file gripper_action_controller.h.

◆ stall_velocity_threshold_

template<class HardwareInterface >
double gripper_action_controller::GripperActionController< HardwareInterface >::stall_velocity_threshold_
private

Stall related parameters.

Definition at line 143 of file gripper_action_controller.h.

◆ update_hold_position_

template<class HardwareInterface >
bool gripper_action_controller::GripperActionController< HardwareInterface >::update_hold_position_
private

Definition at line 115 of file gripper_action_controller.h.

◆ verbose_

template<class HardwareInterface >
bool gripper_action_controller::GripperActionController< HardwareInterface >::verbose_
private

Hard coded verbose flag to help in debugging.

Definition at line 117 of file gripper_action_controller.h.


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


gripper_action_controller
Author(s): Sachin Chitta
autogenerated on Fri Feb 3 2023 03:19:12