$search

GripperPoseAction Class Reference

An action for getting a gripper pose using interactive markers. More...

List of all members.

Public Member Functions

void eraseAllGraspMarkers ()
geometry_msgs::PoseStamped fromWrist (const geometry_msgs::PoseStamped &ps)
 Translate to the control pose.
geometry_msgs::PoseStamped getDefaultPose (std::string arm_name)
void goalCB ()
 Callback to accept a new action goal.
 GripperPoseAction ()
void initButtonMarker ()
void initGraspMarkers ()
void initGripperControl ()
void initGripperMarker ()
void initMarkers ()
 Re-initializes all markers.
void initObjectMarker ()
void preemptCB ()
 Callback to allow this action to get preempted by backend.
void selectGrasp (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void setIdle ()
 Remove the markers.
void setSeed (const geometry_msgs::PoseStampedConstPtr &seed)
geometry_msgs::PoseStamped toWrist (const geometry_msgs::PoseStamped &ps)
 Translate the control pose to the wrist.
bool transformGripperPose (const std::string frame_id="/base_link")
void updateGripperAngle ()
void updateGripperOpening ()
void updatePoses ()
 Update the pose of certain markers.
 ~GripperPoseAction ()

Protected Member Functions

void acceptCB ()
 Return with the gripper pose if the pose is valid, otherwise do nothing.
void cancelCB ()
 Cancel this action call.
void cycleGrasps (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void focusCB ()
 Sends a request for the 3D camera to focus on the ghosted gripper.
bool getModelMesh (int model_id, arm_navigation_msgs::Shape &mesh)
void graspPlanCB ()
 Return with the gripper pose if the pose is valid, otherwise do nothing.
void graspPlanResultCB (const actionlib::SimpleClientGoalState &state, const object_manipulation_msgs::GraspPlanningResultConstPtr &result)
 Callback that receives the result of a TestGripperPose action.
void gripperClickCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Called when the gripper is clicked; each call cycles through gripper opening values.
void initMenus ()
 Initialize the menus for all markers.
visualization_msgs::InteractiveMarker makeCloudMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float point_size, std_msgs::ColorRGBA color)
 Create an interactive marker from a point cloud.
void slowSync ()
void spinOnce ()
 ROS spin update callback.
void testGripperResultCallback (const actionlib::SimpleClientGoalState &state, const pr2_object_manipulation_msgs::TestGripperPoseResultConstPtr &result)
 Callback that receives the result of a TestGripperPose action.
void testPose (geometry_msgs::PoseStamped pose, float opening)
void updateGripper (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Callback for pose updates from the controls.

Protected Attributes

MenuHandler::EntryHandle accept_handle_
bool active_
bool always_call_planner_
geometry_msgs::PoseStamped button_marker_pose_
MenuHandler::EntryHandle cancel_handle_
object_manipulator::ActionWrapper
< point_cloud_server::StoreCloudAction
cloud_server_client_
geometry_msgs::PoseStamped control_offset_
bool double_menu_
MenuHandler::EntryHandle focus_handle_
ros::ServiceClient get_model_mesh_client_
std::string get_pose_name_
actionlib::SimpleActionServer
< pr2_object_manipulation_msgs::GetGripperPoseAction
get_pose_server_
object_manipulator::ActionWrapper
< object_manipulation_msgs::GraspPlanningAction
grasp_plan_client_
float gripper_angle_
float gripper_opening_
geometry_msgs::PoseStamped gripper_pose_
int interface_number_
object_manipulator::MechanismInterface mechanism_
MenuHandler menu_gripper_
ros::NodeHandle nh_
pcl::PointCloud< PointT >::Ptr object_cloud_
bool object_model_
int planner_index_
std::vector
< geometry_msgs::PoseStamped
planner_poses_
std::vector< PoseStateplanner_states_
ros::NodeHandle pnh_
PoseState pose_state_
ros::Publisher pub_cloud_
ros::Publisher pub_focus_
InteractiveMarkerServer server_
ros::Timer slow_sync_timer_
ros::Timer spin_timer_
ros::Subscriber sub_seed_
int task_number_
object_manipulator::ActionWrapper
< pr2_object_manipulation_msgs::TestGripperPoseAction
test_pose_client_
int tested_grasp_index_
bool testing_current_grasp_
bool testing_planned_grasp_
tf::TransformListener tfl_

Detailed Description

An action for getting a gripper pose using interactive markers.

Definition at line 83 of file pr2_interactive_gripper_pose_action.cpp.


Constructor & Destructor Documentation

GripperPoseAction::GripperPoseAction (  )  [inline]

Definition at line 144 of file pr2_interactive_gripper_pose_action.cpp.

GripperPoseAction::~GripperPoseAction (  )  [inline]

Definition at line 203 of file pr2_interactive_gripper_pose_action.cpp.


Member Function Documentation

void GripperPoseAction::acceptCB (  )  [inline, protected]

Return with the gripper pose if the pose is valid, otherwise do nothing.

Definition at line 814 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::cancelCB (  )  [inline, protected]

Cancel this action call.

Definition at line 832 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::cycleGrasps ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [inline, protected]

Definition at line 781 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::eraseAllGraspMarkers (  )  [inline]

Definition at line 525 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::focusCB (  )  [inline, protected]

Sends a request for the 3D camera to focus on the ghosted gripper.

Definition at line 844 of file pr2_interactive_gripper_pose_action.cpp.

geometry_msgs::PoseStamped GripperPoseAction::fromWrist ( const geometry_msgs::PoseStamped ps  )  [inline]

Translate to the control pose.

Definition at line 456 of file pr2_interactive_gripper_pose_action.cpp.

geometry_msgs::PoseStamped GripperPoseAction::getDefaultPose ( std::string  arm_name  )  [inline]

Definition at line 477 of file pr2_interactive_gripper_pose_action.cpp.

bool GripperPoseAction::getModelMesh ( int  model_id,
arm_navigation_msgs::Shape mesh 
) [inline, protected]

Definition at line 935 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::goalCB (  )  [inline]

Callback to accept a new action goal.

Definition at line 294 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::graspPlanCB (  )  [inline, protected]

Return with the gripper pose if the pose is valid, otherwise do nothing.

Definition at line 681 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::graspPlanResultCB ( const actionlib::SimpleClientGoalState state,
const object_manipulation_msgs::GraspPlanningResultConstPtr result 
) [inline, protected]

Callback that receives the result of a TestGripperPose action.

Definition at line 726 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::gripperClickCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [inline, protected]

Called when the gripper is clicked; each call cycles through gripper opening values.

Definition at line 853 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::initButtonMarker (  )  [inline]

Definition at line 561 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::initGraspMarkers (  )  [inline]

Definition at line 510 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::initGripperControl (  )  [inline]

Definition at line 602 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::initGripperMarker (  )  [inline]

Definition at line 581 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::initMarkers (  )  [inline]

Re-initializes all markers.

Definition at line 503 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::initMenus (  )  [inline, protected]

Initialize the menus for all markers.

Definition at line 920 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::initObjectMarker (  )  [inline]

Definition at line 572 of file pr2_interactive_gripper_pose_action.cpp.

visualization_msgs::InteractiveMarker GripperPoseAction::makeCloudMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  point_size,
std_msgs::ColorRGBA  color 
) [inline, protected]

Create an interactive marker from a point cloud.

Definition at line 959 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::preemptCB (  )  [inline]

Callback to allow this action to get preempted by backend.

Definition at line 433 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::selectGrasp ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [inline]

Definition at line 536 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::setIdle (  )  [inline]

Remove the markers.

Definition at line 281 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::setSeed ( const geometry_msgs::PoseStampedConstPtr seed  )  [inline]

Definition at line 232 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::slowSync (  )  [inline, protected]

Definition at line 622 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::spinOnce (  )  [inline, protected]

ROS spin update callback.

Definition at line 616 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::testGripperResultCallback ( const actionlib::SimpleClientGoalState state,
const pr2_object_manipulation_msgs::TestGripperPoseResultConstPtr result 
) [inline, protected]

Callback that receives the result of a TestGripperPose action.

Definition at line 627 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::testPose ( geometry_msgs::PoseStamped  pose,
float  opening 
) [inline, protected]

Definition at line 874 of file pr2_interactive_gripper_pose_action.cpp.

geometry_msgs::PoseStamped GripperPoseAction::toWrist ( const geometry_msgs::PoseStamped ps  )  [inline]

Translate the control pose to the wrist.

Definition at line 443 of file pr2_interactive_gripper_pose_action.cpp.

bool GripperPoseAction::transformGripperPose ( const std::string  frame_id = "/base_link"  )  [inline]

Definition at line 207 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::updateGripper ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [inline, protected]

Callback for pose updates from the controls.

Definition at line 883 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::updateGripperAngle (  )  [inline]

Definition at line 227 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::updateGripperOpening (  )  [inline]

Definition at line 222 of file pr2_interactive_gripper_pose_action.cpp.

void GripperPoseAction::updatePoses (  )  [inline]

Update the pose of certain markers.

Definition at line 471 of file pr2_interactive_gripper_pose_action.cpp.


Member Data Documentation

Definition at line 123 of file pr2_interactive_gripper_pose_action.cpp.

bool GripperPoseAction::active_ [protected]

Definition at line 99 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 101 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 92 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 124 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 137 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 95 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 105 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 125 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 114 of file pr2_interactive_gripper_pose_action.cpp.

std::string GripperPoseAction::get_pose_name_ [protected]

Definition at line 139 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 140 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 136 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 97 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 96 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 94 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 103 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 129 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 122 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 111 of file pr2_interactive_gripper_pose_action.cpp.

pcl::PointCloud<PointT>::Ptr GripperPoseAction::object_cloud_ [protected]

Definition at line 98 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 100 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 91 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 89 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 90 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 112 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 110 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 119 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 120 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 117 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 116 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 115 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 113 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 104 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 135 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 107 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 108 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 106 of file pr2_interactive_gripper_pose_action.cpp.

Definition at line 127 of file pr2_interactive_gripper_pose_action.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pr2_interactive_gripper_pose_action
Author(s): Adam Leeper
autogenerated on Tue Mar 5 14:21:21 2013