Classes | |
| struct | GraspInfo |
Public Member Functions | |
| std::string | chooseArm () |
| geometry_msgs::Vector3Stamped | chooseDirection (std::string arm_name, bool grasp) |
| int | chooseObject (const std::vector< object_manipulation_msgs::GraspableObject > &objects, const std::vector< std::string > &collision_names) |
| void | detectAndProcessCollisionMap (bool take_new_map) |
| void | execute () |
| bool | getModelInfo (const household_objects_database_msgs::DatabaseModelPose &model_pose, std::string &name, std::string &all_tags) |
| PickAndPlaceKeyboardInterface (ros::NodeHandle &nh) | |
| void | printMovementOptions () |
| int | printObjects (const std::vector< object_manipulation_msgs::GraspableObject > &objects, const std::vector< std::string > &collision_names) |
| void | printOptions () |
| void | translateGripperCartesian (std::string arm_name, int axis, double dist) |
| ~PickAndPlaceKeyboardInterface () | |
Private Attributes | |
| tabletop_collision_map_processing::CollisionMapInterface | collision_map_interface_ |
| ros::ServiceClient | collision_processing_srv_ |
| ros::ServiceClient | get_model_description_srv_ |
| GraspInfo | grasp_info_left_ |
| GraspInfo | grasp_info_right_ |
| object_manipulator::MechanismInterface | mech_interface_ |
| ros::NodeHandle | nh_ |
| ros::ServiceClient | object_detection_srv_ |
| tabletop_collision_map_processing::TabletopCollisionMapProcessing::Response | objects_info_ |
| actionlib::SimpleActionClient < object_manipulation_msgs::PickupAction > | pickup_client_ |
| actionlib::SimpleActionClient < object_manipulation_msgs::PlaceAction > | place_client_ |
| ros::NodeHandle | priv_nh_ |
Definition at line 73 of file pick_and_place_keyboard_interface.cpp.
| PickAndPlaceKeyboardInterface::PickAndPlaceKeyboardInterface | ( | ros::NodeHandle & | nh | ) | [inline] |
Definition at line 101 of file pick_and_place_keyboard_interface.cpp.
| PickAndPlaceKeyboardInterface::~PickAndPlaceKeyboardInterface | ( | ) | [inline] |
Definition at line 154 of file pick_and_place_keyboard_interface.cpp.
| std::string PickAndPlaceKeyboardInterface::chooseArm | ( | ) | [inline] |
Definition at line 279 of file pick_and_place_keyboard_interface.cpp.
| geometry_msgs::Vector3Stamped PickAndPlaceKeyboardInterface::chooseDirection | ( | std::string | arm_name, | |
| bool | grasp | |||
| ) | [inline] |
Definition at line 241 of file pick_and_place_keyboard_interface.cpp.
| int PickAndPlaceKeyboardInterface::chooseObject | ( | const std::vector< object_manipulation_msgs::GraspableObject > & | objects, | |
| const std::vector< std::string > & | collision_names | |||
| ) | [inline] |
Definition at line 210 of file pick_and_place_keyboard_interface.cpp.
| void PickAndPlaceKeyboardInterface::detectAndProcessCollisionMap | ( | bool | take_new_map | ) | [inline] |
Definition at line 300 of file pick_and_place_keyboard_interface.cpp.
| void PickAndPlaceKeyboardInterface::execute | ( | ) | [inline] |
Definition at line 372 of file pick_and_place_keyboard_interface.cpp.
| bool PickAndPlaceKeyboardInterface::getModelInfo | ( | const household_objects_database_msgs::DatabaseModelPose & | model_pose, | |
| std::string & | name, | |||
| std::string & | all_tags | |||
| ) | [inline] |
Definition at line 156 of file pick_and_place_keyboard_interface.cpp.
| void PickAndPlaceKeyboardInterface::printMovementOptions | ( | ) | [inline] |
Definition at line 351 of file pick_and_place_keyboard_interface.cpp.
| int PickAndPlaceKeyboardInterface::printObjects | ( | const std::vector< object_manipulation_msgs::GraspableObject > & | objects, | |
| const std::vector< std::string > & | collision_names | |||
| ) | [inline] |
Definition at line 181 of file pick_and_place_keyboard_interface.cpp.
| void PickAndPlaceKeyboardInterface::printOptions | ( | ) | [inline] |
Definition at line 330 of file pick_and_place_keyboard_interface.cpp.
| void PickAndPlaceKeyboardInterface::translateGripperCartesian | ( | std::string | arm_name, | |
| int | axis, | |||
| double | dist | |||
| ) | [inline] |
Definition at line 359 of file pick_and_place_keyboard_interface.cpp.
tabletop_collision_map_processing::CollisionMapInterface PickAndPlaceKeyboardInterface::collision_map_interface_ [private] |
Definition at line 87 of file pick_and_place_keyboard_interface.cpp.
ros::ServiceClient PickAndPlaceKeyboardInterface::collision_processing_srv_ [private] |
Definition at line 80 of file pick_and_place_keyboard_interface.cpp.
ros::ServiceClient PickAndPlaceKeyboardInterface::get_model_description_srv_ [private] |
Definition at line 81 of file pick_and_place_keyboard_interface.cpp.
Definition at line 96 of file pick_and_place_keyboard_interface.cpp.
Definition at line 95 of file pick_and_place_keyboard_interface.cpp.
object_manipulator::MechanismInterface PickAndPlaceKeyboardInterface::mech_interface_ [private] |
Definition at line 86 of file pick_and_place_keyboard_interface.cpp.
ros::NodeHandle PickAndPlaceKeyboardInterface::nh_ [private] |
Definition at line 76 of file pick_and_place_keyboard_interface.cpp.
ros::ServiceClient PickAndPlaceKeyboardInterface::object_detection_srv_ [private] |
Definition at line 79 of file pick_and_place_keyboard_interface.cpp.
tabletop_collision_map_processing::TabletopCollisionMapProcessing::Response PickAndPlaceKeyboardInterface::objects_info_ [private] |
Definition at line 98 of file pick_and_place_keyboard_interface.cpp.
actionlib::SimpleActionClient<object_manipulation_msgs::PickupAction> PickAndPlaceKeyboardInterface::pickup_client_ [private] |
Definition at line 83 of file pick_and_place_keyboard_interface.cpp.
actionlib::SimpleActionClient<object_manipulation_msgs::PlaceAction> PickAndPlaceKeyboardInterface::place_client_ [private] |
Definition at line 84 of file pick_and_place_keyboard_interface.cpp.
ros::NodeHandle PickAndPlaceKeyboardInterface::priv_nh_ [private] |
Definition at line 77 of file pick_and_place_keyboard_interface.cpp.