Classes | |
| struct | AdvancedGraspOptions |
| class | AdvancedOptionsDialog |
| class | CartesianGripperControl |
| class | CartesianGripperControlDisplay |
| class | CartesianGripperControlTool |
| class | GripperController |
| class | InteractiveManipulationBackend |
| class | InteractiveManipulationDisplay |
| class | InteractiveManipulationFrame |
| class | InteractiveManipulationFrontend |
| class | InteractiveManipulationFrontendDisplay |
| class | ObjectSelectionFrame |
| class | PointHeadCameraDisplay |
| class | PointHeadViewController |
Typedefs | |
| typedef actionlib::SimpleActionClient < IMGUIAction > | Client |
Functions | |
| std::vector< double > | getFrontPosition (std::string arm_name) |
| std::vector< std::vector < double > > | getFrontTrajectory (std::string arm_name) |
| std::string | getGraspResultInfo (object_manipulation_msgs::GraspResult result) |
| std::vector< double > | getHandoffPosition (std::string arm_name) |
| std::vector< std::vector < double > > | getHandoffTrajectory (std::string arm_name) |
| std::string | getPlaceLocationResultInfo (object_manipulation_msgs::PlaceLocationResult result) |
| std::vector< double > | getSideHandoffPosition (std::string arm_name) |
| std::vector< std::vector < double > > | getSideHandoffTrajectory (std::string arm_name) |
| std::vector< double > | getSidePosition (std::string arm_name) |
| std::vector< std::vector < double > > | getSideTrajectory (std::string arm_name) |
| wxString | getWxString (std::string str) |
| void | populateGraspOptions (object_manipulation_msgs::PickupGoal &pickup_goal, std::string arm_name, const IMGUIOptions &options) |
| void | populatePlaceOptions (object_manipulation_msgs::PlaceGoal &place_goal, std::string arm_name, const IMGUIOptions &options) |
| geometry_msgs::Pose | preTranslatePose (geometry_msgs::Pose pose_in, btVector3 translation) |
| geometry_msgs::Pose | translatePose (geometry_msgs::Pose pose_in, btVector3 translation) |
Variables | |
| static const std::string | JOINT_STATES_TOPIC = "joint_states" |
| typedef actionlib::SimpleActionClient<IMGUIAction> pr2_interactive_manipulation::Client |
Definition at line 36 of file interactive_manipulation_frontend.cpp.
| std::vector<double> pr2_interactive_manipulation::getFrontPosition | ( | std::string | arm_name | ) | [inline] |
Definition at line 50 of file arm_locations.h.
| std::vector< std::vector<double> > pr2_interactive_manipulation::getFrontTrajectory | ( | std::string | arm_name | ) | [inline] |
Definition at line 92 of file arm_locations.h.
| std::string pr2_interactive_manipulation::getGraspResultInfo | ( | object_manipulation_msgs::GraspResult | result | ) |
Definition at line 154 of file interactive_manipulation_frame.cpp.
| std::vector<double> pr2_interactive_manipulation::getHandoffPosition | ( | std::string | arm_name | ) | [inline] |
Definition at line 112 of file arm_locations.h.
| std::vector< std::vector<double> > pr2_interactive_manipulation::getHandoffTrajectory | ( | std::string | arm_name | ) | [inline] |
Definition at line 128 of file arm_locations.h.
| std::string pr2_interactive_manipulation::getPlaceLocationResultInfo | ( | object_manipulation_msgs::PlaceLocationResult | result | ) |
Definition at line 176 of file interactive_manipulation_frame.cpp.
| std::vector<double> pr2_interactive_manipulation::getSideHandoffPosition | ( | std::string | arm_name | ) | [inline] |
Definition at line 152 of file arm_locations.h.
| std::vector< std::vector<double> > pr2_interactive_manipulation::getSideHandoffTrajectory | ( | std::string | arm_name | ) | [inline] |
Definition at line 166 of file arm_locations.h.
| std::vector<double> pr2_interactive_manipulation::getSidePosition | ( | std::string | arm_name | ) | [inline] |
Definition at line 32 of file arm_locations.h.
| std::vector< std::vector<double> > pr2_interactive_manipulation::getSideTrajectory | ( | std::string | arm_name | ) | [inline] |
Definition at line 64 of file arm_locations.h.
| wxString pr2_interactive_manipulation::getWxString | ( | std::string | str | ) |
Definition at line 62 of file interactive_manipulation_frontend.cpp.
| void pr2_interactive_manipulation::populateGraspOptions | ( | object_manipulation_msgs::PickupGoal & | pickup_goal, | |
| std::string | arm_name, | |||
| const IMGUIOptions & | options | |||
| ) |
Definition at line 236 of file interactive_manipulation_backend.cpp.
| void pr2_interactive_manipulation::populatePlaceOptions | ( | object_manipulation_msgs::PlaceGoal & | place_goal, | |
| std::string | arm_name, | |||
| const IMGUIOptions & | options | |||
| ) |
Definition at line 429 of file interactive_manipulation_backend.cpp.
| geometry_msgs::Pose pr2_interactive_manipulation::preTranslatePose | ( | geometry_msgs::Pose | pose_in, | |
| btVector3 | translation | |||
| ) |
Definition at line 320 of file interactive_manipulation_frame.cpp.
| geometry_msgs::Pose pr2_interactive_manipulation::translatePose | ( | geometry_msgs::Pose | pose_in, | |
| btVector3 | translation | |||
| ) |
Definition at line 307 of file interactive_manipulation_frame.cpp.
const std::string pr2_interactive_manipulation::JOINT_STATES_TOPIC = "joint_states" [static] |
Definition at line 39 of file gripper_controller.cpp.