Trajectory controller handler for the pr2 gripper. More...
#include <pr2_gripper_trajectory_controller_handler.h>

| Public Member Functions | |
| void | cancelExecution () | 
| cancel the execution of the trajectory. This should be implemented by derived classes. | |
| void | controllerActiveCallback () | 
| void | controllerDoneCallback (const actionlib::SimpleClientGoalState &state, const pr2_controllers_msgs::Pr2GripperCommandResultConstPtr &result) | 
| void | controllerFeedbackCallback (const pr2_controllers_msgs::Pr2GripperCommandFeedbackConstPtr &feedback) | 
| bool | enableOvershoot (double max_overshoot_velocity_epsilon, ros::Duration min_overshoot_time, ros::Duration max_overshoot_time) | 
| Gripper does not monitor overshoot. This function returns false;. | |
| bool | executeTrajectory (const trajectory_msgs::JointTrajectory &trajectory, boost::shared_ptr< trajectory_execution_monitor::TrajectoryRecorder > &recorder, const trajectory_execution_monitor::TrajectoryFinishedCallbackFunction &traj_callback) | 
| Start executing. Gripper will either open or close. | |
| Pr2GripperTrajectoryControllerHandler (const std::string &group_name, const std::string &controller_name) | |
| Static Public Attributes | |
| static const double | DEFAULT_GRIPPER_OBJECT_PRESENCE_THRESHOLD = 0.0021 | 
| static const double | GRIPPER_CLOSED = 0.0 | 
| static const double | GRIPPER_OPEN = 0.086 | 
| Protected Attributes | |
| actionlib::SimpleActionClient < pr2_controllers_msgs::Pr2GripperCommandAction > | pr2_gripper_action_client_ | 
Trajectory controller handler for the pr2 gripper.
Definition at line 46 of file pr2_gripper_trajectory_controller_handler.h.
| Pr2GripperTrajectoryControllerHandler::Pr2GripperTrajectoryControllerHandler | ( | const std::string & | group_name, | 
| const std::string & | controller_name | ||
| ) |  [inline] | 
Definition at line 54 of file pr2_gripper_trajectory_controller_handler.h.
| void Pr2GripperTrajectoryControllerHandler::cancelExecution | ( | ) |  [inline, virtual] | 
cancel the execution of the trajectory. This should be implemented by derived classes.
Implements trajectory_execution_monitor::TrajectoryControllerHandler.
Definition at line 104 of file pr2_gripper_trajectory_controller_handler.h.
| void Pr2GripperTrajectoryControllerHandler::controllerActiveCallback | ( | ) |  [inline] | 
Definition at line 130 of file pr2_gripper_trajectory_controller_handler.h.
| void Pr2GripperTrajectoryControllerHandler::controllerDoneCallback | ( | const actionlib::SimpleClientGoalState & | state, | 
| const pr2_controllers_msgs::Pr2GripperCommandResultConstPtr & | result | ||
| ) |  [inline] | 
Definition at line 107 of file pr2_gripper_trajectory_controller_handler.h.
| void Pr2GripperTrajectoryControllerHandler::controllerFeedbackCallback | ( | const pr2_controllers_msgs::Pr2GripperCommandFeedbackConstPtr & | feedback | ) |  [inline] | 
Definition at line 135 of file pr2_gripper_trajectory_controller_handler.h.
| bool Pr2GripperTrajectoryControllerHandler::enableOvershoot | ( | double | max_overshoot_velocity_epsilon, | 
| ros::Duration | min_overshoot_time, | ||
| ros::Duration | max_overshoot_time | ||
| ) |  [inline] | 
Gripper does not monitor overshoot. This function returns false;.
Reimplemented from trajectory_execution_monitor::TrajectoryControllerHandler.
Definition at line 65 of file pr2_gripper_trajectory_controller_handler.h.
| bool Pr2GripperTrajectoryControllerHandler::executeTrajectory | ( | const trajectory_msgs::JointTrajectory & | trajectory, | 
| boost::shared_ptr< trajectory_execution_monitor::TrajectoryRecorder > & | recorder, | ||
| const trajectory_execution_monitor::TrajectoryFinishedCallbackFunction & | traj_callback | ||
| ) |  [inline, virtual] | 
Start executing. Gripper will either open or close.
Implements trajectory_execution_monitor::TrajectoryControllerHandler.
Definition at line 73 of file pr2_gripper_trajectory_controller_handler.h.
| const double Pr2GripperTrajectoryControllerHandler::DEFAULT_GRIPPER_OBJECT_PRESENCE_THRESHOLD = 0.0021  [static] | 
Definition at line 52 of file pr2_gripper_trajectory_controller_handler.h.
| const double Pr2GripperTrajectoryControllerHandler::GRIPPER_CLOSED = 0.0  [static] | 
Definition at line 51 of file pr2_gripper_trajectory_controller_handler.h.
| const double Pr2GripperTrajectoryControllerHandler::GRIPPER_OPEN = 0.086  [static] | 
Definition at line 50 of file pr2_gripper_trajectory_controller_handler.h.
| actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> Pr2GripperTrajectoryControllerHandler::pr2_gripper_action_client_  [protected] | 
Definition at line 143 of file pr2_gripper_trajectory_controller_handler.h.