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. 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) |
![]() | |
Controller () | |
virtual bool | init (HardwareInterface *, ros::NodeHandle &) |
virtual | ~Controller () |
![]() | |
ControllerBase () | |
bool | isRunning () |
bool | isRunning () |
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 | ~ControllerBase () |
Public Attributes | |
realtime_tools::RealtimeBuffer< Commands > | command_ |
Commands | command_struct_ |
Commands | command_struct_rt_ |
![]() | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum controller_interface::ControllerBase:: { ... } | state_ |
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. 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 | |
![]() | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
![]() | |
std::string | getHardwareInterfaceType () const |
virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
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.
|
private |
Definition at line 111 of file gripper_action_controller.h.
|
private |
Definition at line 112 of file gripper_action_controller.h.
|
private |
Definition at line 113 of file gripper_action_controller.h.
|
private |
Definition at line 117 of file gripper_action_controller.h.
|
private |
Definition at line 114 of file gripper_action_controller.h.
|
private |
Definition at line 115 of file gripper_action_controller.h.
gripper_action_controller::GripperActionController< HardwareInterface >::GripperActionController | ( | ) |
Definition at line 127 of file gripper_action_controller_impl.h.
|
private |
Definition at line 285 of file gripper_action_controller_impl.h.
|
private |
Check for success and publish appropriate result and feedback.
Definition at line 315 of file gripper_action_controller_impl.h.
|
private |
Definition at line 244 of file gripper_action_controller_impl.h.
|
virtual |
Reimplemented from controller_interface::Controller< HardwareInterface >.
Definition at line 132 of file gripper_action_controller_impl.h.
|
inlineprivate |
Definition at line 111 of file gripper_action_controller_impl.h.
|
private |
Definition at line 306 of file gripper_action_controller_impl.h.
|
inlinevirtual |
Holds the current position.
Reimplemented from controller_interface::ControllerBase.
Definition at line 91 of file gripper_action_controller_impl.h.
|
inlinevirtual |
Cancels the active action goal, if any.
Reimplemented from controller_interface::ControllerBase.
Definition at line 104 of file gripper_action_controller_impl.h.
|
virtual |
Implements controller_interface::ControllerBase.
Definition at line 224 of file gripper_action_controller_impl.h.
|
private |
Definition at line 131 of file gripper_action_controller.h.
|
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.
|
private |
Computed command.
Definition at line 145 of file gripper_action_controller.h.
|
private |
Definition at line 134 of file gripper_action_controller.h.
|
private |
Max allowed effort.
Definition at line 148 of file gripper_action_controller.h.
|
private |
Definition at line 137 of file gripper_action_controller.h.
|
private |
Definition at line 149 of file gripper_action_controller.h.
|
private |
Adapts desired goal state to HW interface.
Definition at line 126 of file gripper_action_controller.h.
|
private |
Handles to controlled joints.
Definition at line 123 of file gripper_action_controller.h.
|
private |
Controlled joint names.
Definition at line 124 of file gripper_action_controller.h.
|
private |
Store stall time.
Definition at line 144 of file gripper_action_controller.h.
|
private |
Controller name.
Definition at line 122 of file gripper_action_controller.h.
|
private |
Definition at line 129 of file gripper_action_controller.h.
|
private |
Currently active action goal, if any.
Definition at line 128 of file gripper_action_controller.h.
|
private |
Definition at line 147 of file gripper_action_controller.h.
|
private |
Stall related parameters.
Definition at line 147 of file gripper_action_controller.h.
|
private |
Definition at line 119 of file gripper_action_controller.h.
|
private |
Hard coded verbose flag to help in debugging.
Definition at line 121 of file gripper_action_controller.h.