Public Member Functions | Protected Member Functions | Protected Attributes
BasePoseAction Class Reference

An action for getting a full robot pose using interactive markers. More...

List of all members.

Public Member Functions

 BasePoseAction ()
geometry_msgs::PoseStamped getDefaultPose ()
void goalCB ()
 Callback to accept a new action goal.
void initControlMarkers ()
void initMarkers ()
 Re-initializes all markers.
void initMeshMarkers ()
void preemptCB ()
 Callback to allow this action to get preempted by backend.
void setIdle ()
 Remove the markers.
void setSeed (const geometry_msgs::PoseStampedConstPtr &seed)
void updatePoses ()
 Update the pose of certain markers.
 ~BasePoseAction ()

Protected Member Functions

void acceptCB ()
 Return with the gripper pose if the pose is valid, otherwise do nothing.
void cancelCB ()
 Cancel this action call.
geometry_msgs::PoseStamped clipToRadius (const geometry_msgs::PoseStamped &input, const float &radius)
void fast_update ()
 ROS spin update callback.
void focusCB ()
 Sends a request for the 3D camera to focus on the controls.
void initMenus ()
 Initialize the menus for all markers.
void poseControlCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Callback for pose updates from the controls.
void poseMeshCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Called when the gripper is clicked; each call cycles through gripper opening values.
void slow_update ()

Protected Attributes

MenuHandler::EntryHandle accept_handle_
bool active_
geometry_msgs::PoseStamped base_pose_
MenuHandler::EntryHandle cancel_handle_
geometry_msgs::PoseStamped control_offset_
ros::Timer fast_update_timer_
MenuHandler::EntryHandle focus_handle_
std::string get_pose_name_
actionlib::SimpleActionServer
< pr2_object_manipulation_msgs::GetNavPoseAction
get_pose_server_
int interface_number_
double max_direct_move_radius_
object_manipulator::MechanismInterface mechanism_
MenuHandler menu_controls_
ros::NodeHandle nh_
ros::NodeHandle pnh_
ros::Publisher pub_focus_
InteractiveMarkerServer server_
ros::Timer slow_update_timer_
ros::Subscriber sub_seed_
int task_number_
int tested_grasp_index_
bool testing_current_grasp_
bool testing_planned_grasp_
tf::TransformListener tfl_

Detailed Description

An action for getting a full robot pose using interactive markers.

Definition at line 78 of file pr2_interactive_nav_action.cpp.


Constructor & Destructor Documentation

Definition at line 121 of file pr2_interactive_nav_action.cpp.

Definition at line 165 of file pr2_interactive_nav_action.cpp.


Member Function Documentation

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

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

Definition at line 366 of file pr2_interactive_nav_action.cpp.

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

Cancel this action call.

Definition at line 376 of file pr2_interactive_nav_action.cpp.

geometry_msgs::PoseStamped BasePoseAction::clipToRadius ( const geometry_msgs::PoseStamped &  input,
const float &  radius 
) [inline, protected]

Definition at line 396 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::fast_update ( ) [inline, protected]

ROS spin update callback.

Definition at line 354 of file pr2_interactive_nav_action.cpp.

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

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

Definition at line 383 of file pr2_interactive_nav_action.cpp.

geometry_msgs::PoseStamped BasePoseAction::getDefaultPose ( ) [inline]

Definition at line 236 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::goalCB ( ) [inline]

Callback to accept a new action goal.

Definition at line 187 of file pr2_interactive_nav_action.cpp.

Definition at line 260 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::initMarkers ( ) [inline]

Re-initializes all markers.

Definition at line 250 of file pr2_interactive_nav_action.cpp.

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

Initialize the menus for all markers.

Definition at line 466 of file pr2_interactive_nav_action.cpp.

Definition at line 256 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::poseControlCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [inline, protected]

Callback for pose updates from the controls.

Definition at line 440 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::poseMeshCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [inline, protected]

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

Definition at line 392 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::preemptCB ( ) [inline]

Callback to allow this action to get preempted by backend.

Definition at line 221 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::setIdle ( ) [inline]

Remove the markers.

Definition at line 180 of file pr2_interactive_nav_action.cpp.

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

Definition at line 169 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::slow_update ( ) [inline, protected]

Definition at line 360 of file pr2_interactive_nav_action.cpp.

void BasePoseAction::updatePoses ( ) [inline]

Update the pose of certain markers.

Definition at line 231 of file pr2_interactive_nav_action.cpp.


Member Data Documentation

Definition at line 108 of file pr2_interactive_nav_action.cpp.

Definition at line 87 of file pr2_interactive_nav_action.cpp.

geometry_msgs::PoseStamped BasePoseAction::base_pose_ [protected]

Definition at line 84 of file pr2_interactive_nav_action.cpp.

Definition at line 109 of file pr2_interactive_nav_action.cpp.

geometry_msgs::PoseStamped BasePoseAction::control_offset_ [protected]

Definition at line 85 of file pr2_interactive_nav_action.cpp.

Definition at line 101 of file pr2_interactive_nav_action.cpp.

Definition at line 110 of file pr2_interactive_nav_action.cpp.

std::string BasePoseAction::get_pose_name_ [protected]

Definition at line 116 of file pr2_interactive_nav_action.cpp.

Definition at line 117 of file pr2_interactive_nav_action.cpp.

Definition at line 89 of file pr2_interactive_nav_action.cpp.

Definition at line 95 of file pr2_interactive_nav_action.cpp.

Definition at line 114 of file pr2_interactive_nav_action.cpp.

Definition at line 107 of file pr2_interactive_nav_action.cpp.

Definition at line 97 of file pr2_interactive_nav_action.cpp.

Definition at line 98 of file pr2_interactive_nav_action.cpp.

Definition at line 105 of file pr2_interactive_nav_action.cpp.

Definition at line 103 of file pr2_interactive_nav_action.cpp.

Definition at line 102 of file pr2_interactive_nav_action.cpp.

Definition at line 99 of file pr2_interactive_nav_action.cpp.

Definition at line 90 of file pr2_interactive_nav_action.cpp.

Definition at line 93 of file pr2_interactive_nav_action.cpp.

Definition at line 94 of file pr2_interactive_nav_action.cpp.

Definition at line 92 of file pr2_interactive_nav_action.cpp.

Definition at line 112 of file pr2_interactive_nav_action.cpp.


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


pr2_interactive_gripper_pose_action
Author(s): Adam Leeper
autogenerated on Fri Jan 3 2014 12:05:16