Does all the work for the Interactive Object Recognition GUI. More...
#include <pr2_interactive_object_detection_backend.h>
Public Member Functions | |
InteractiveObjDetBackend () | |
~InteractiveObjDetBackend () | |
Private Member Functions | |
void | abortAction (std::string error) |
void | clearOldMarkers (std::string frame_id) |
template<class ServiceType > | |
bool | connectService (ros::ServiceClient &service_client, std::string topic) |
repeatedly try to connect to the given service | |
bool | doAutoDetection () |
call the TabletopObjectDetection service | |
bool | doAutoRecognition () |
call automatic recognition service | |
bool | doAutoSegmentation () |
call the automatic tabletop segmentation | |
bool | doDetection (bool interactive) |
do all steps for object recognition without segmentation by calling an external service | |
bool | doInteractiveRecognition () |
call a popup window, letting the user decide on the recognition results | |
bool | doInteractiveSegmentation () |
call a popup window to let the user do the segmentation | |
bool | doRecognition (bool interactive) |
do all steps for object recognition, based on segmentation | |
bool | doSegmentation (bool interactive) |
do all steps for segmentation | |
void | finishAction (std::string result) |
bool | getModelInfo (const household_objects_database_msgs::DatabaseModelPose &model_pose, std::string &name, std::string &all_tags) |
retrieve info from model database | |
bool | getModelMesh (int model_id, geometric_shapes_msgs::Shape &mesh) |
retrieve mesh from model database | |
bool | getPose (geometry_msgs::Pose &pose, std::string from_frame, std::string to_frame) |
get pose of from_frame relative to to_frame | |
bool | getSensorData (ros::Duration time_out) |
assemble all the basic sensor data needed for the detection process | |
bool | lookAtTable () |
move the robot's head so it faces the table | |
void | preemptAction () |
int | printObjects (const std::vector< object_manipulation_msgs::GraspableObject > &objects) |
model info console output | |
void | processUserCommand (const pr2_interactive_object_detection::UserCommandGoal::ConstPtr &goal) |
react to a request by the user | |
void | publishFitMarkers (const std::vector< household_objects_database_msgs::DatabaseModelPoseList > &potential_models, const tabletop_object_detector::Table &table) |
bool | publishResult (int &num_recognized) |
publish a list of graspable objects | |
void | statusFeedback (std::string status) |
bool | transformPose (geometry_msgs::PoseStamped &pose, std::string target_frame) |
modify the given given pose in-place to be relative to target_frame | |
Private Attributes | |
ros::ServiceClient | auto_obj_rec_client_ |
ros::ServiceClient | auto_seg_client_ |
sensor_msgs::CameraInfo | camera_info_ |
int | current_marker_id_ |
The current marker being published. | |
std::vector < visualization_msgs::Marker > | delete_markers_ |
stereo_msgs::DisparityImage | disparity_image_ |
ros::ServiceClient | get_model_description_client_ |
ros::ServiceClient | get_model_mesh_client_ |
sensor_msgs::Image | image_ |
ros::Publisher | marker_pub_ |
Publisher for markers. | |
object_manipulator::MechanismInterface | mech_interface_ |
double | min_marker_quality_ |
actionlib::SimpleActionClient < object_recognition_gui::ObjectRecognitionGuiAction > * | obj_rec_popup_client_ |
sensor_msgs::PointCloud2 | point_cloud_ |
ros::NodeHandle | priv_nh_ |
tabletop_object_detector::TabletopObjectRecognitionResponse | recognition_result_ |
ros::Publisher | result_publisher_ |
ros::ServiceClient | rgbd_assembler_client_ |
rgbd_assembler::RgbdAssembly | rgbd_assembler_srv_ |
std::string | robot_reference_frame_id_ |
ros::NodeHandle | root_nh_ |
tabletop_object_detector::TabletopSegmentationResponse | segmentation_result_ |
bool | segmentation_was_interactive_ |
double | table_x_ |
double | table_y_ |
double | table_z_ |
ros::ServiceClient | tabletop_detection_client_ |
tf::TransformListener | tf_listener_ |
actionlib::SimpleActionServer < pr2_interactive_object_detection::UserCommandAction > * | user_command_server_ |
Does all the work for the Interactive Object Recognition GUI.
Definition at line 55 of file pr2_interactive_object_detection_backend.h.
InteractiveObjDetBackend::InteractiveObjDetBackend | ( | ) |
Definition at line 55 of file pr2_interactive_object_detection_backend.cpp.
InteractiveObjDetBackend::~InteractiveObjDetBackend | ( | ) |
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.
void InteractiveObjDetBackend::clearOldMarkers | ( | std::string | frame_id | ) | [private] |
bool InteractiveObjDetBackend::connectService | ( | ros::ServiceClient & | service_client, | |
std::string | topic | |||
) | [inline, 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 540 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doAutoRecognition | ( | ) | [private] |
call automatic recognition service
Definition at line 465 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doAutoSegmentation | ( | ) | [private] |
call the automatic tabletop segmentation
Definition at line 287 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 584 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 339 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 230 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 501 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::doSegmentation | ( | bool | interactive | ) | [private] |
do all steps for segmentation
Definition at line 311 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
bool InteractiveObjDetBackend::getModelMesh | ( | int | model_id, | |
geometric_shapes_msgs::Shape & | mesh | |||
) | [private] |
retrieve mesh from model database
Definition at line 920 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 843 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 206 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::lookAtTable | ( | ) | [private] |
move the robot's head so it faces the table
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 968 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
void InteractiveObjDetBackend::publishFitMarkers | ( | const std::vector< household_objects_database_msgs::DatabaseModelPoseList > & | potential_models, | |
const tabletop_object_detector::Table & | table | |||
) | [private] |
Definition at line 798 of file pr2_interactive_object_detection_backend.cpp.
bool InteractiveObjDetBackend::publishResult | ( | int & | num_recognized | ) | [private] |
publish a list of graspable objects
Definition at line 618 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 874 of file pr2_interactive_object_detection_backend.cpp.
ros::ServiceClient InteractiveObjDetBackend::auto_obj_rec_client_ [private] |
Definition at line 138 of file pr2_interactive_object_detection_backend.h.
ros::ServiceClient InteractiveObjDetBackend::auto_seg_client_ [private] |
Definition at line 136 of file pr2_interactive_object_detection_backend.h.
sensor_msgs::CameraInfo InteractiveObjDetBackend::camera_info_ [private] |
Definition at line 154 of file pr2_interactive_object_detection_backend.h.
int InteractiveObjDetBackend::current_marker_id_ [private] |
The current marker being published.
Definition at line 172 of file pr2_interactive_object_detection_backend.h.
std::vector< visualization_msgs::Marker > InteractiveObjDetBackend::delete_markers_ [private] |
Definition at line 174 of file pr2_interactive_object_detection_backend.h.
stereo_msgs::DisparityImage InteractiveObjDetBackend::disparity_image_ [private] |
Definition at line 153 of file pr2_interactive_object_detection_backend.h.
ros::ServiceClient InteractiveObjDetBackend::get_model_description_client_ [private] |
Definition at line 133 of file pr2_interactive_object_detection_backend.h.
ros::ServiceClient InteractiveObjDetBackend::get_model_mesh_client_ [private] |
Definition at line 134 of file pr2_interactive_object_detection_backend.h.
sensor_msgs::Image InteractiveObjDetBackend::image_ [private] |
Definition at line 152 of file pr2_interactive_object_detection_backend.h.
ros::Publisher InteractiveObjDetBackend::marker_pub_ [private] |
Publisher for markers.
Definition at line 143 of file pr2_interactive_object_detection_backend.h.
object_manipulator::MechanismInterface InteractiveObjDetBackend::mech_interface_ [private] |
Definition at line 164 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::min_marker_quality_ [private] |
Definition at line 180 of file pr2_interactive_object_detection_backend.h.
actionlib::SimpleActionClient<object_recognition_gui::ObjectRecognitionGuiAction>* InteractiveObjDetBackend::obj_rec_popup_client_ [private] |
Definition at line 146 of file pr2_interactive_object_detection_backend.h.
sensor_msgs::PointCloud2 InteractiveObjDetBackend::point_cloud_ [private] |
Definition at line 155 of file pr2_interactive_object_detection_backend.h.
ros::NodeHandle InteractiveObjDetBackend::priv_nh_ [private] |
Definition at line 129 of file pr2_interactive_object_detection_backend.h.
tabletop_object_detector::TabletopObjectRecognitionResponse InteractiveObjDetBackend::recognition_result_ [private] |
Definition at line 161 of file pr2_interactive_object_detection_backend.h.
ros::Publisher InteractiveObjDetBackend::result_publisher_ [private] |
Definition at line 169 of file pr2_interactive_object_detection_backend.h.
ros::ServiceClient InteractiveObjDetBackend::rgbd_assembler_client_ [private] |
Definition at line 131 of file pr2_interactive_object_detection_backend.h.
rgbd_assembler::RgbdAssembly InteractiveObjDetBackend::rgbd_assembler_srv_ [private] |
Definition at line 157 of file pr2_interactive_object_detection_backend.h.
std::string InteractiveObjDetBackend::robot_reference_frame_id_ [private] |
Definition at line 182 of file pr2_interactive_object_detection_backend.h.
ros::NodeHandle InteractiveObjDetBackend::root_nh_ [private] |
Definition at line 128 of file pr2_interactive_object_detection_backend.h.
tabletop_object_detector::TabletopSegmentationResponse InteractiveObjDetBackend::segmentation_result_ [private] |
Definition at line 160 of file pr2_interactive_object_detection_backend.h.
bool InteractiveObjDetBackend::segmentation_was_interactive_ [private] |
Definition at line 177 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::table_x_ [private] |
Definition at line 184 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::table_y_ [private] |
Definition at line 185 of file pr2_interactive_object_detection_backend.h.
double InteractiveObjDetBackend::table_z_ [private] |
Definition at line 186 of file pr2_interactive_object_detection_backend.h.
ros::ServiceClient InteractiveObjDetBackend::tabletop_detection_client_ [private] |
Definition at line 140 of file pr2_interactive_object_detection_backend.h.
tf::TransformListener InteractiveObjDetBackend::tf_listener_ [private] |
Definition at line 166 of file pr2_interactive_object_detection_backend.h.
actionlib::SimpleActionServer<pr2_interactive_object_detection::UserCommandAction>* InteractiveObjDetBackend::user_command_server_ [private] |
Definition at line 149 of file pr2_interactive_object_detection_backend.h.