Does all the work for the Interactive Object Recognition GUI. More...
#include <pr2_interactive_object_detection_backend.h>
Does all the work for the Interactive Object Recognition GUI.
Definition at line 58 of file pr2_interactive_object_detection_backend.h.
Definition at line 55 of file pr2_interactive_object_detection_backend.cpp.
Definition at line 97 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::abortAction | ( | std::string | error | ) | [private] |
Definition at line 160 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::addTableToCollisionMap | ( | tabletop_object_detector::Table | table | ) | [private] |
add the segmented table to the collision map
Definition at line 1022 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::clearOldMarkers | ( | std::string | frame_id | ) | [private] |
bool InteractiveObjDetBackend::connectService | ( | ros::ServiceClient & | service_client, |
std::string | topic | ||
) | [private] |
repeatedly try to connect to the given service
Definition at line 105 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doAutoDetection | ( | ) | [private] |
call the TabletopObjectDetection service
Definition at line 524 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doAutoRecognition | ( | ) | [private] |
call automatic recognition service
Definition at line 449 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doAutoSegmentation | ( | ) | [private] |
call the automatic tabletop segmentation
Definition at line 268 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doDetection | ( | bool | interactive | ) | [private] |
do all steps for object recognition without segmentation by calling an external service
Definition at line 579 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doInteractiveRecognition | ( | ) | [private] |
call a popup window, letting the user decide on the recognition results
Definition at line 323 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doInteractiveSegmentation | ( | ) | [private] |
call a popup window to let the user do the segmentation
Definition at line 211 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doRecognition | ( | bool | interactive | ) | [private] |
do all steps for object recognition, based on segmentation
Definition at line 485 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doSegmentation | ( | bool | interactive | ) | [private] |
do all steps for segmentation
Definition at line 292 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::finishAction | ( | std::string | result | ) | [private] |
Definition at line 167 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::getModelInfo | ( | const household_objects_database_msgs::DatabaseModelPose & | model_pose, |
std::string & | name, | ||
std::string & | all_tags | ||
) | [private] |
retrieve info from model database
Definition at line 968 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::getModelMesh | ( | int | model_id, |
arm_navigation_msgs::Shape & | mesh | ||
) | [private] |
retrieve mesh from model database
Definition at line 946 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::getPose | ( | geometry_msgs::Pose & | pose, |
std::string | from_frame, | ||
std::string | to_frame | ||
) | [private] |
get pose of from_frame relative to to_frame
Definition at line 869 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::getSensorData | ( | ros::Duration | time_out | ) | [private] |
assemble all the basic sensor data needed for the detection process
Definition at line 186 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::preemptAction | ( | ) | [private] |
Definition at line 179 of file pr2_interactive_object_detection_backend.cpp.
int InteractiveObjDetBackend::printObjects | ( | const std::vector< object_manipulation_msgs::GraspableObject > & | objects | ) | [private] |
model info console output
Definition at line 994 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::processUserCommand | ( | const pr2_interactive_object_detection::UserCommandGoal::ConstPtr & | goal | ) | [private] |
react to a request by the user
Definition at line 124 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::publishFitMarkers | ( | const std::vector< household_objects_database_msgs::DatabaseModelPoseList > & | potential_models, |
const tabletop_object_detector::Table & | table | ||
) | [private] |
Definition at line 817 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::publishResult | ( | int & | num_recognized | ) | [private] |
publish a list of graspable objects
Definition at line 613 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::resetMarkers | ( | ) | [private] |
delete fit markers and publish an empty result (kills interactive markers)
Definition at line 793 of file pr2_interactive_object_detection_backend.cpp.
void InteractiveObjDetBackend::statusFeedback | ( | std::string | status | ) | [private] |
Definition at line 152 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::transformPose | ( | geometry_msgs::PoseStamped & | pose, |
std::string | target_frame | ||
) | [private] |
modify the given given pose in-place to be relative to target_frame
Definition at line 900 of file pr2_interactive_object_detection_backend.cpp.
Definition at line 147 of file pr2_interactive_object_detection_backend.h.
Definition at line 145 of file pr2_interactive_object_detection_backend.h.
sensor_msgs::CameraInfo InteractiveObjDetBackend::camera_info_ [private] |
Definition at line 163 of file pr2_interactive_object_detection_backend.h.
tabletop_collision_map_processing::CollisionMapInterface InteractiveObjDetBackend::collision_map_interface_ [private] |
Definition at line 178 of file pr2_interactive_object_detection_backend.h.
int InteractiveObjDetBackend::current_marker_id_ [private] |
The current marker being published.
Definition at line 181 of file pr2_interactive_object_detection_backend.h.
std::vector< visualization_msgs::Marker > InteractiveObjDetBackend::delete_markers_ [private] |
Definition at line 183 of file pr2_interactive_object_detection_backend.h.
stereo_msgs::DisparityImage InteractiveObjDetBackend::disparity_image_ [private] |
Definition at line 162 of file pr2_interactive_object_detection_backend.h.
Definition at line 142 of file pr2_interactive_object_detection_backend.h.
Definition at line 143 of file pr2_interactive_object_detection_backend.h.
sensor_msgs::Image InteractiveObjDetBackend::image_ [private] |
Definition at line 161 of file pr2_interactive_object_detection_backend.h.
Publisher for markers.
Definition at line 152 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::min_marker_quality_ [private] |
Definition at line 189 of file pr2_interactive_object_detection_backend.h.
actionlib::SimpleActionClient<object_recognition_gui::ObjectRecognitionGuiAction>* InteractiveObjDetBackend::obj_rec_popup_client_ [private] |
Definition at line 155 of file pr2_interactive_object_detection_backend.h.
sensor_msgs::PointCloud2 InteractiveObjDetBackend::point_cloud_ [private] |
Definition at line 164 of file pr2_interactive_object_detection_backend.h.
Definition at line 138 of file pr2_interactive_object_detection_backend.h.
tabletop_object_detector::TabletopObjectRecognitionResponse InteractiveObjDetBackend::recognition_result_ [private] |
Definition at line 170 of file pr2_interactive_object_detection_backend.h.
Definition at line 175 of file pr2_interactive_object_detection_backend.h.
Definition at line 140 of file pr2_interactive_object_detection_backend.h.
Definition at line 166 of file pr2_interactive_object_detection_backend.h.
std::string InteractiveObjDetBackend::robot_reference_frame_id_ [private] |
Definition at line 191 of file pr2_interactive_object_detection_backend.h.
Definition at line 137 of file pr2_interactive_object_detection_backend.h.
tabletop_object_detector::TabletopSegmentationResponse InteractiveObjDetBackend::segmentation_result_ [private] |
Definition at line 169 of file pr2_interactive_object_detection_backend.h.
Definition at line 186 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::table_x_ [private] |
Definition at line 193 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::table_y_ [private] |
Definition at line 194 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::table_z_ [private] |
Definition at line 195 of file pr2_interactive_object_detection_backend.h.
Definition at line 149 of file pr2_interactive_object_detection_backend.h.
Definition at line 172 of file pr2_interactive_object_detection_backend.h.
actionlib::SimpleActionServer<pr2_interactive_object_detection::UserCommandAction>* InteractiveObjDetBackend::user_command_server_ [private] |
Definition at line 158 of file pr2_interactive_object_detection_backend.h.