#include <interactive_manipulation_backend.h>
Classes | |
struct | GraspInfo |
Public Member Functions | |
InteractiveManipulationBackend () | |
~InteractiveManipulationBackend () | |
Private Member Functions | |
void | actionCallback (const IMGUIGoalConstPtr &goal) |
void | armMotion (int arm_selection_choice, int arm_action_choice, int arm_planner_choice, bool collision, object_manipulation_msgs::ManipulationResult &result) |
int | callGripperClickPickup (std::string arm_name, std::vector< object_manipulation_msgs::Grasp > &grasps) |
void | collisionReset (int reset_choice) |
GraspInfo * | getGraspInfo (std::string arm_name) |
void | graspableObjectsCallback (const pr2_interactive_object_detection::GraspableObjectListConstPtr &objects) |
bool | interruptRequested () |
void | lookAtTable () |
int | modelObject (IMGUIOptions options) |
void | moveGripper (IMGUIOptions options) |
int | pickupObject (const IMGUIOptions &options, object_manipulation_msgs::GraspableObject object=object_manipulation_msgs::GraspableObject()) |
int | placeObject (const IMGUIOptions &options) |
bool | processCollisionMapForPickup (const IMGUIOptions &options, object_manipulation_msgs::PickupGoal &goal) |
void | setStatusLabel (std::string text) |
void | takeMap () |
Private Attributes | |
std::string | action_name_ |
actionlib::SimpleActionServer < IMGUIAction > * | action_server_ |
tabletop_collision_map_processing::CollisionMapInterface | collision_map_interface_ |
std::string | create_model_action_name_ |
actionlib::SimpleActionClient < pr2_create_object_model::ModelObjectInHandAction > * | create_model_client_ |
ros::ServiceClient | get_model_description_srv_ |
GraspInfo | grasp_info_left_ |
GraspInfo | grasp_info_right_ |
std::string | grasp_planning_service_name_ |
ros::ServiceClient | grasp_planning_srv_ |
std::vector < object_manipulation_msgs::GraspableObject > | graspable_objects_ |
ros::Subscriber | graspable_objects_sub_ |
GripperController | gripper_controller_ |
object_manipulator::MechanismInterface | mech_interface_ |
bool | new_object_list_ |
sensor_msgs::PointCloud2 | object_model_left_ |
sensor_msgs::PointCloud2 | object_model_right_ |
std::string | pickup_action_name_ |
actionlib::SimpleActionClient < object_manipulation_msgs::PickupAction > * | pickup_client_ |
std::string | place_action_name_ |
actionlib::SimpleActionClient < object_manipulation_msgs::PlaceAction > * | place_client_ |
std::string | place_planning_service_name_ |
ros::ServiceClient | place_planning_srv_ |
ros::NodeHandle | priv_nh_ |
pr2_interactive_object_detection::GraspableObjectListConstPtr | received_objects_ |
boost::mutex | received_objects_mutex_ |
ros::NodeHandle | root_nh_ |
Definition at line 52 of file interactive_manipulation_backend.h.
pr2_interactive_manipulation::InteractiveManipulationBackend::InteractiveManipulationBackend | ( | ) |
Definition at line 120 of file interactive_manipulation_backend.cpp.
pr2_interactive_manipulation::InteractiveManipulationBackend::~InteractiveManipulationBackend | ( | ) |
Definition at line 157 of file interactive_manipulation_backend.cpp.
void pr2_interactive_manipulation::InteractiveManipulationBackend::actionCallback | ( | const IMGUIGoalConstPtr & | goal | ) | [private] |
Definition at line 162 of file interactive_manipulation_backend.cpp.
void pr2_interactive_manipulation::InteractiveManipulationBackend::armMotion | ( | int | arm_selection_choice, | |
int | arm_action_choice, | |||
int | arm_planner_choice, | |||
bool | collision, | |||
object_manipulation_msgs::ManipulationResult & | result | |||
) | [private] |
int pr2_interactive_manipulation::InteractiveManipulationBackend::callGripperClickPickup | ( | std::string | arm_name, | |
std::vector< object_manipulation_msgs::Grasp > & | grasps | |||
) | [private] |
Definition at line 897 of file interactive_manipulation_backend.cpp.
void pr2_interactive_manipulation::InteractiveManipulationBackend::collisionReset | ( | int | reset_choice | ) | [private] |
Definition at line 616 of file interactive_manipulation_backend.cpp.
GraspInfo* pr2_interactive_manipulation::InteractiveManipulationBackend::getGraspInfo | ( | std::string | arm_name | ) | [inline, private] |
Definition at line 98 of file interactive_manipulation_backend.h.
void pr2_interactive_manipulation::InteractiveManipulationBackend::graspableObjectsCallback | ( | const pr2_interactive_object_detection::GraspableObjectListConstPtr & | objects | ) | [private] |
Definition at line 213 of file interactive_manipulation_backend.cpp.
bool pr2_interactive_manipulation::InteractiveManipulationBackend::interruptRequested | ( | ) | [private] |
Definition at line 231 of file interactive_manipulation_backend.cpp.
void pr2_interactive_manipulation::InteractiveManipulationBackend::lookAtTable | ( | ) | [private] |
Definition at line 779 of file interactive_manipulation_backend.cpp.
int pr2_interactive_manipulation::InteractiveManipulationBackend::modelObject | ( | IMGUIOptions | options | ) | [private] |
Definition at line 817 of file interactive_manipulation_backend.cpp.
void pr2_interactive_manipulation::InteractiveManipulationBackend::moveGripper | ( | IMGUIOptions | options | ) | [private] |
Definition at line 804 of file interactive_manipulation_backend.cpp.
int pr2_interactive_manipulation::InteractiveManipulationBackend::pickupObject | ( | const IMGUIOptions & | options, | |
object_manipulation_msgs::GraspableObject | object = object_manipulation_msgs::GraspableObject() | |||
) | [private] |
Definition at line 325 of file interactive_manipulation_backend.cpp.
int pr2_interactive_manipulation::InteractiveManipulationBackend::placeObject | ( | const IMGUIOptions & | options | ) | [private] |
Definition at line 456 of file interactive_manipulation_backend.cpp.
bool pr2_interactive_manipulation::InteractiveManipulationBackend::processCollisionMapForPickup | ( | const IMGUIOptions & | options, | |
object_manipulation_msgs::PickupGoal & | goal | |||
) | [private] |
Definition at line 263 of file interactive_manipulation_backend.cpp.
void pr2_interactive_manipulation::InteractiveManipulationBackend::setStatusLabel | ( | std::string | text | ) | [private] |
Definition at line 220 of file interactive_manipulation_backend.cpp.
void pr2_interactive_manipulation::InteractiveManipulationBackend::takeMap | ( | ) | [private] |
Definition at line 581 of file interactive_manipulation_backend.cpp.
std::string pr2_interactive_manipulation::InteractiveManipulationBackend::action_name_ [private] |
Definition at line 154 of file interactive_manipulation_backend.h.
actionlib::SimpleActionServer<IMGUIAction>* pr2_interactive_manipulation::InteractiveManipulationBackend::action_server_ [private] |
Definition at line 141 of file interactive_manipulation_backend.h.
tabletop_collision_map_processing::CollisionMapInterface pr2_interactive_manipulation::InteractiveManipulationBackend::collision_map_interface_ [private] |
Definition at line 156 of file interactive_manipulation_backend.h.
std::string pr2_interactive_manipulation::InteractiveManipulationBackend::create_model_action_name_ [private] |
Definition at line 153 of file interactive_manipulation_backend.h.
actionlib::SimpleActionClient<pr2_create_object_model::ModelObjectInHandAction>* pr2_interactive_manipulation::InteractiveManipulationBackend::create_model_client_ [private] |
Definition at line 163 of file interactive_manipulation_backend.h.
ros::ServiceClient pr2_interactive_manipulation::InteractiveManipulationBackend::get_model_description_srv_ [private] |
Definition at line 139 of file interactive_manipulation_backend.h.
Definition at line 175 of file interactive_manipulation_backend.h.
Definition at line 174 of file interactive_manipulation_backend.h.
std::string pr2_interactive_manipulation::InteractiveManipulationBackend::grasp_planning_service_name_ [private] |
Definition at line 149 of file interactive_manipulation_backend.h.
ros::ServiceClient pr2_interactive_manipulation::InteractiveManipulationBackend::grasp_planning_srv_ [private] |
Definition at line 137 of file interactive_manipulation_backend.h.
std::vector<object_manipulation_msgs::GraspableObject> pr2_interactive_manipulation::InteractiveManipulationBackend::graspable_objects_ [private] |
Definition at line 165 of file interactive_manipulation_backend.h.
ros::Subscriber pr2_interactive_manipulation::InteractiveManipulationBackend::graspable_objects_sub_ [private] |
Definition at line 140 of file interactive_manipulation_backend.h.
GripperController pr2_interactive_manipulation::InteractiveManipulationBackend::gripper_controller_ [private] |
Definition at line 147 of file interactive_manipulation_backend.h.
object_manipulator::MechanismInterface pr2_interactive_manipulation::InteractiveManipulationBackend::mech_interface_ [private] |
Definition at line 158 of file interactive_manipulation_backend.h.
Definition at line 170 of file interactive_manipulation_backend.h.
sensor_msgs::PointCloud2 pr2_interactive_manipulation::InteractiveManipulationBackend::object_model_left_ [private] |
Definition at line 177 of file interactive_manipulation_backend.h.
sensor_msgs::PointCloud2 pr2_interactive_manipulation::InteractiveManipulationBackend::object_model_right_ [private] |
Definition at line 178 of file interactive_manipulation_backend.h.
std::string pr2_interactive_manipulation::InteractiveManipulationBackend::pickup_action_name_ [private] |
Definition at line 151 of file interactive_manipulation_backend.h.
actionlib::SimpleActionClient<object_manipulation_msgs::PickupAction>* pr2_interactive_manipulation::InteractiveManipulationBackend::pickup_client_ [private] |
Definition at line 160 of file interactive_manipulation_backend.h.
std::string pr2_interactive_manipulation::InteractiveManipulationBackend::place_action_name_ [private] |
Definition at line 152 of file interactive_manipulation_backend.h.
actionlib::SimpleActionClient<object_manipulation_msgs::PlaceAction>* pr2_interactive_manipulation::InteractiveManipulationBackend::place_client_ [private] |
Definition at line 161 of file interactive_manipulation_backend.h.
std::string pr2_interactive_manipulation::InteractiveManipulationBackend::place_planning_service_name_ [private] |
Definition at line 150 of file interactive_manipulation_backend.h.
ros::ServiceClient pr2_interactive_manipulation::InteractiveManipulationBackend::place_planning_srv_ [private] |
Definition at line 138 of file interactive_manipulation_backend.h.
ros::NodeHandle pr2_interactive_manipulation::InteractiveManipulationBackend::priv_nh_ [private] |
Definition at line 145 of file interactive_manipulation_backend.h.
pr2_interactive_object_detection::GraspableObjectListConstPtr pr2_interactive_manipulation::InteractiveManipulationBackend::received_objects_ [private] |
Definition at line 167 of file interactive_manipulation_backend.h.
boost::mutex pr2_interactive_manipulation::InteractiveManipulationBackend::received_objects_mutex_ [private] |
Definition at line 168 of file interactive_manipulation_backend.h.
ros::NodeHandle pr2_interactive_manipulation::InteractiveManipulationBackend::root_nh_ [private] |
Definition at line 143 of file interactive_manipulation_backend.h.