Controller for executing a gripper command action for simple single-dof grippers. More...
#include <gripper_action_controller.h>

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. | |
| void | stopping (const ros::Time &time) |
| Cancels the active action goal, if any. | |
| void | update (const ros::Time &time, const ros::Duration &period) |
Public Attributes | |
| realtime_tools::RealtimeBuffer < Commands > | command_ |
| Commands | command_struct_ |
| Commands | command_struct_rt_ |
Private Types | |
| typedef actionlib::ActionServer < control_msgs::GripperCommandAction > | ActionServer |
| typedef boost::shared_ptr < ActionServer > | ActionServerPtr |
| typedef ActionServer::GoalHandle | GoalHandle |
| typedef HardwareInterfaceAdapter < HardwareInterface > | HwIfaceAdapter |
| typedef realtime_tools::RealtimeServerGoalHandle < control_msgs::GripperCommandAction > | RealtimeGoalHandle |
| typedef boost::shared_ptr < RealtimeGoalHandle > | RealtimeGoalHandlePtr |
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. | |
| 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. | |
| ros::NodeHandle | controller_nh_ |
| double | default_max_effort_ |
| Max allowed effort. | |
| ros::Timer | goal_handle_timer_ |
| double | goal_tolerance_ |
| HwIfaceAdapter | hw_iface_adapter_ |
| Adapts desired goal state to HW interface. | |
| hardware_interface::JointHandle | joint_ |
| Handles to controlled joints. | |
| std::string | joint_name_ |
| Controlled joint names. | |
| ros::Time | last_movement_time_ |
| Store stall time. | |
| std::string | name_ |
| Controller name. | |
| control_msgs::GripperCommandResultPtr | pre_alloc_result_ |
| RealtimeGoalHandlePtr | rt_active_goal_ |
| Currently active action goal, if any. | |
| double | stall_timeout_ |
| double | stall_velocity_threshold_ |
| Stall related parameters. | |
| bool | update_hold_position_ |
| bool | verbose_ |
| Hard coded verbose flag to help in debugging. | |
Controller for executing a gripper command action for simple single-dof grippers.
| HardwareInterface | Controller hardware interface. Currently hardware_interface::PositionJointInterface and hardware_interface::EffortJointInterface are supported out-of-the-box. |
Definition at line 75 of file gripper_action_controller.h.
typedef actionlib::ActionServer<control_msgs::GripperCommandAction> gripper_action_controller::GripperActionController< HardwareInterface >::ActionServer [private] |
Definition at line 111 of file gripper_action_controller.h.
typedef boost::shared_ptr<ActionServer> gripper_action_controller::GripperActionController< HardwareInterface >::ActionServerPtr [private] |
Definition at line 112 of file gripper_action_controller.h.
typedef ActionServer::GoalHandle gripper_action_controller::GripperActionController< HardwareInterface >::GoalHandle [private] |
Definition at line 113 of file gripper_action_controller.h.
typedef HardwareInterfaceAdapter<HardwareInterface> gripper_action_controller::GripperActionController< HardwareInterface >::HwIfaceAdapter [private] |
Definition at line 117 of file gripper_action_controller.h.
typedef realtime_tools::RealtimeServerGoalHandle<control_msgs::GripperCommandAction> gripper_action_controller::GripperActionController< HardwareInterface >::RealtimeGoalHandle [private] |
Definition at line 114 of file gripper_action_controller.h.
typedef boost::shared_ptr<RealtimeGoalHandle> gripper_action_controller::GripperActionController< HardwareInterface >::RealtimeGoalHandlePtr [private] |
Definition at line 115 of file gripper_action_controller.h.
| gripper_action_controller::GripperActionController< HardwareInterface >::GripperActionController | ( | ) |
Definition at line 128 of file gripper_action_controller_impl.h.
| void gripper_action_controller::GripperActionController< HardwareInterface >::cancelCB | ( | GoalHandle | gh | ) | [private] |
Definition at line 286 of file gripper_action_controller_impl.h.
| 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 316 of file gripper_action_controller_impl.h.
| void gripper_action_controller::GripperActionController< HardwareInterface >::goalCB | ( | GoalHandle | gh | ) | [private] |
Definition at line 245 of file gripper_action_controller_impl.h.
| bool gripper_action_controller::GripperActionController< HardwareInterface >::init | ( | HardwareInterface * | hw, |
| ros::NodeHandle & | root_nh, | ||
| ros::NodeHandle & | controller_nh | ||
| ) | [virtual] |
Reimplemented from controller_interface::Controller< HardwareInterface >.
Definition at line 133 of file gripper_action_controller_impl.h.
| void gripper_action_controller::GripperActionController< HardwareInterface >::preemptActiveGoal | ( | ) | [inline, private] |
Definition at line 112 of file gripper_action_controller_impl.h.
| void gripper_action_controller::GripperActionController< HardwareInterface >::setHoldPosition | ( | const ros::Time & | time | ) | [private] |
Definition at line 307 of file gripper_action_controller_impl.h.
| void gripper_action_controller::GripperActionController< HardwareInterface >::starting | ( | const ros::Time & | time | ) | [inline, virtual] |
Holds the current position.
Reimplemented from controller_interface::ControllerBase.
Definition at line 92 of file gripper_action_controller_impl.h.
| void gripper_action_controller::GripperActionController< HardwareInterface >::stopping | ( | const ros::Time & | time | ) | [inline, virtual] |
Cancels the active action goal, if any.
Reimplemented from controller_interface::ControllerBase.
Definition at line 105 of file gripper_action_controller_impl.h.
| void gripper_action_controller::GripperActionController< HardwareInterface >::update | ( | const ros::Time & | time, |
| const ros::Duration & | period | ||
| ) | [virtual] |
Implements controller_interface::ControllerBase.
Definition at line 225 of file gripper_action_controller_impl.h.
ros::Duration gripper_action_controller::GripperActionController< HardwareInterface >::action_monitor_period_ [private] |
Definition at line 131 of file gripper_action_controller.h.
ActionServerPtr gripper_action_controller::GripperActionController< HardwareInterface >::action_server_ [private] |
Definition at line 135 of file gripper_action_controller.h.
| realtime_tools::RealtimeBuffer<Commands> gripper_action_controller::GripperActionController< HardwareInterface >::command_ |
Definition at line 106 of file gripper_action_controller.h.
| Commands gripper_action_controller::GripperActionController< HardwareInterface >::command_struct_ |
Definition at line 107 of file gripper_action_controller.h.
| Commands gripper_action_controller::GripperActionController< HardwareInterface >::command_struct_rt_ |
Definition at line 107 of file gripper_action_controller.h.
double gripper_action_controller::GripperActionController< HardwareInterface >::computed_command_ [private] |
Computed command.
Definition at line 145 of file gripper_action_controller.h.
ros::NodeHandle gripper_action_controller::GripperActionController< HardwareInterface >::controller_nh_ [private] |
Definition at line 134 of file gripper_action_controller.h.
double gripper_action_controller::GripperActionController< HardwareInterface >::default_max_effort_ [private] |
Max allowed effort.
Definition at line 148 of file gripper_action_controller.h.
ros::Timer gripper_action_controller::GripperActionController< HardwareInterface >::goal_handle_timer_ [private] |
Definition at line 137 of file gripper_action_controller.h.
double gripper_action_controller::GripperActionController< HardwareInterface >::goal_tolerance_ [private] |
Definition at line 149 of file gripper_action_controller.h.
HwIfaceAdapter gripper_action_controller::GripperActionController< HardwareInterface >::hw_iface_adapter_ [private] |
Adapts desired goal state to HW interface.
Definition at line 126 of file gripper_action_controller.h.
hardware_interface::JointHandle gripper_action_controller::GripperActionController< HardwareInterface >::joint_ [private] |
Handles to controlled joints.
Definition at line 123 of file gripper_action_controller.h.
std::string gripper_action_controller::GripperActionController< HardwareInterface >::joint_name_ [private] |
Controlled joint names.
Definition at line 124 of file gripper_action_controller.h.
ros::Time gripper_action_controller::GripperActionController< HardwareInterface >::last_movement_time_ [private] |
Store stall time.
Definition at line 144 of file gripper_action_controller.h.
std::string gripper_action_controller::GripperActionController< HardwareInterface >::name_ [private] |
Controller name.
Definition at line 122 of file gripper_action_controller.h.
control_msgs::GripperCommandResultPtr gripper_action_controller::GripperActionController< HardwareInterface >::pre_alloc_result_ [private] |
Definition at line 129 of file gripper_action_controller.h.
RealtimeGoalHandlePtr gripper_action_controller::GripperActionController< HardwareInterface >::rt_active_goal_ [private] |
Currently active action goal, if any.
Definition at line 128 of file gripper_action_controller.h.
double gripper_action_controller::GripperActionController< HardwareInterface >::stall_timeout_ [private] |
Definition at line 147 of file gripper_action_controller.h.
double gripper_action_controller::GripperActionController< HardwareInterface >::stall_velocity_threshold_ [private] |
Stall related parameters.
Definition at line 147 of file gripper_action_controller.h.
bool gripper_action_controller::GripperActionController< HardwareInterface >::update_hold_position_ [private] |
Definition at line 119 of file gripper_action_controller.h.
bool gripper_action_controller::GripperActionController< HardwareInterface >::verbose_ [private] |
Hard coded verbose flag to help in debugging.
Definition at line 121 of file gripper_action_controller.h.