00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <string>
00038
00039 #include <ros/ros.h>
00040
00041 #include <sensor_msgs/PointCloud.h>
00042
00043 #include <visualization_msgs/Marker.h>
00044
00045 #include <tf/transform_listener.h>
00046
00047 #include <household_objects_database_msgs/DatabaseModelPose.h>
00048 #include <household_objects_database_msgs/DatabaseModelPoseList.h>
00049 #include <household_objects_database_msgs/GetModelMesh.h>
00050
00051 #include "tabletop_object_detector/exhaustive_fit_detector.h"
00052 #include "tabletop_object_detector/marker_generator.h"
00053 #include "tabletop_object_detector/iterative_distance_fitter.h"
00054 #include "tabletop_object_detector/Table.h"
00055 #include "tabletop_object_detector/TabletopObjectRecognition.h"
00056 #include "tabletop_object_detector/ClearExclusionsList.h"
00057 #include "tabletop_object_detector/AddModelExclusion.h"
00058 #include "tabletop_object_detector/NegateExclusions.h"
00059
00060 namespace tabletop_object_detector {
00061
00062 class TabletopObjectRecognizer
00063 {
00064 private:
00066 ros::NodeHandle nh_;
00068 ros::NodeHandle priv_nh_;
00070 ros::Subscriber cloud_new_sub_;
00072 ros::Publisher marker_pub_;
00074 ros::ServiceServer object_recognition_srv_;
00075
00077 ros::ServiceServer add_model_exclusion_srv_;
00078
00080 ros::ServiceServer clear_model_exclusions_srv_;
00082 ros::ServiceServer negate_exclusions_srv_;
00084 ros::ServiceClient get_model_mesh_srv_;
00085
00087 double min_marker_quality_;
00089 int num_markers_published_;
00091 int current_marker_id_;
00092
00094 ExhaustiveFitDetector<IterativeTranslationFitter> detector_;
00095
00097 std::string model_set_;
00098
00100 double fit_merge_threshold_;
00101
00103 tf::TransformListener listener_;
00104
00105
00106
00108 bool serviceCallback(TabletopObjectRecognition::Request &request, TabletopObjectRecognition::Response &response);
00109 bool addExclusionCB(AddModelExclusion::Request &request, AddModelExclusion::Response &response);
00110 bool clearExclusionsCB(ClearExclusionsList::Request &request, ClearExclusionsList::Response &response);
00111 bool negateExclusionsCB(NegateExclusions::Request &request, NegateExclusions::Response &response);
00112
00114 template <class PointCloudType>
00115 void objectDetection(std::vector<PointCloudType> &clusters, int num_models,
00116 const Table &table, bool perform_fit_merge,
00117 TabletopObjectRecognition::Response &response);
00118
00119
00120
00122 double fitDistance(const ModelFitInfo &m1, const ModelFitInfo &m2);
00123
00125 template <class PointCloudType>
00126 double fitClusterDistance(const ModelFitInfo &m, const PointCloudType &cluster);
00127
00129 void publishFitMarkers(
00130 const std::vector<household_objects_database_msgs::DatabaseModelPoseList> &potential_models,
00131 const Table &table);
00132
00134 void clearOldMarkers(std::string frame_id);
00135
00136 public:
00138 TabletopObjectRecognizer(ros::NodeHandle nh);
00139
00141 ~TabletopObjectRecognizer() {}
00142 };
00143
00144 TabletopObjectRecognizer::TabletopObjectRecognizer(ros::NodeHandle nh) : nh_(nh), priv_nh_("~")
00145 {
00146 num_markers_published_ = 1;
00147 current_marker_id_ = 1;
00148
00149 marker_pub_ = nh_.advertise<visualization_msgs::Marker>(nh_.resolveName("markers_out"), 10);
00150
00151 std::string get_model_mesh_srv_name;
00152 priv_nh_.param<std::string>("get_model_mesh_srv", get_model_mesh_srv_name, "get_model_mesh_srv");
00153 while ( !ros::service::waitForService(get_model_mesh_srv_name, ros::Duration(2.0)) && nh_.ok() )
00154 {
00155 ROS_INFO("Waiting for %s service to come up", get_model_mesh_srv_name.c_str());
00156 }
00157 if (!nh_.ok()) exit(0);
00158 get_model_mesh_srv_ = nh_.serviceClient<household_objects_database_msgs::GetModelMesh>
00159 (get_model_mesh_srv_name, true);
00160
00161 priv_nh_.param<std::string>("model_set", model_set_, "");
00162 detector_.loadDatabaseModels(model_set_);
00163
00164 object_recognition_srv_ = nh_.advertiseService(nh_.resolveName("object_recognition_srv"),
00165 &TabletopObjectRecognizer::serviceCallback, this);
00166 clear_model_exclusions_srv_ = priv_nh_.advertiseService("clear_exclusions_srv",
00167 &TabletopObjectRecognizer::clearExclusionsCB, this);
00168 add_model_exclusion_srv_ = priv_nh_.advertiseService("add_exclusion_srv",
00169 &TabletopObjectRecognizer::addExclusionCB, this);
00170 negate_exclusions_srv_ = priv_nh_.advertiseService("negate_exclusions_srv",
00171 &TabletopObjectRecognizer::negateExclusionsCB, this);
00172
00173
00174 priv_nh_.param<double>("fit_merge_threshold", fit_merge_threshold_, 0.05);
00175 priv_nh_.param<double>("min_marker_quality", min_marker_quality_, 0.003);
00176 }
00177
00178 bool TabletopObjectRecognizer::clearExclusionsCB(ClearExclusionsList::Request &request,
00179 ClearExclusionsList::Response &response)
00180 {
00181 ROS_INFO("Clearing exclusions list");
00182 detector_.clearExclusionList();
00183 return true;
00184 }
00185
00186 bool TabletopObjectRecognizer::addExclusionCB(AddModelExclusion::Request &request,
00187 AddModelExclusion::Response &response)
00188 {
00189 ROS_INFO("Adding %d to exclusions list", request.model_id);
00190 detector_.addModelToExclusionList(request.model_id);
00191 return true;
00192 }
00193
00194 bool TabletopObjectRecognizer::negateExclusionsCB(NegateExclusions::Request &request,
00195 NegateExclusions::Response &response)
00196 {
00197 ROS_INFO("Setting exclusions negation to %s", request.negate ? "true" : "false");
00198 detector_.setNegateExclusions(request.negate);
00199 return true;
00200 }
00201
00204 bool TabletopObjectRecognizer::serviceCallback(TabletopObjectRecognition::Request &request,
00205 TabletopObjectRecognition::Response &response)
00206 {
00207
00208 tf::Transform table_trans;
00209 tf::poseMsgToTF(request.table.pose.pose, table_trans);
00210 tf::StampedTransform table_trans_stamped(table_trans, request.table.pose.header.stamp,
00211 request.table.pose.header.frame_id, "table_frame");
00212 tf::TransformListener listener;
00213 listener.setTransform(table_trans_stamped);
00214 for (size_t i = 0; i < request.clusters.size (); ++i)
00215 {
00216 if (request.clusters[i].header.frame_id != request.table.pose.header.frame_id)
00217 {
00218 ROS_ERROR("Recognition node requires all clusters to be in the same frame as the table");
00219 return false;
00220 }
00221 request.clusters[i].header.stamp = request.table.pose.header.stamp;
00222 try
00223 {
00224 listener.transformPointCloud("table_frame", request.clusters[i], request.clusters[i]);
00225 }
00226 catch (tf::TransformException ex)
00227 {
00228 ROS_ERROR("Recognition node failed to transform cluster from frame %s into table frame; Exception: %s",
00229 request.clusters[i].header.frame_id.c_str(), ex.what());
00230 return false;
00231 }
00232 }
00233 ROS_INFO("Clusters converted to table frame");
00234
00235
00236 objectDetection<sensor_msgs::PointCloud>(request.clusters, request.num_models, request.table, request.perform_fit_merge, response);
00237
00238 publishFitMarkers(response.models, request.table);
00239 clearOldMarkers(request.table.pose.header.frame_id);
00240
00241 return true;
00242 }
00243
00246 template <class PointCloudType>
00247 void TabletopObjectRecognizer::objectDetection(std::vector<PointCloudType> &clusters,
00248 int num_models,
00249 const Table &table,
00250 bool perform_fit_merge,
00251 TabletopObjectRecognition::Response &response)
00252 {
00253
00254 ROS_INFO("Fitting models to clusters");
00255 std::vector< std::vector<ModelFitInfo> > raw_fit_results;
00256 response.cluster_model_indices.resize( clusters.size(), -1 );
00257 for (size_t i=0; i<clusters.size(); i++)
00258 {
00259 raw_fit_results.push_back( detector_.fitBestModels<PointCloudType>(clusters[i], std::max(1,num_models)) );
00260 response.cluster_model_indices[i] = i;
00261 }
00262 ROS_INFO("Raw fit results computed");
00263
00264
00265 if (perform_fit_merge)
00266 {
00267 size_t i=0;
00268 while (i < clusters.size())
00269 {
00270
00271 if (response.cluster_model_indices[i] != (int)i || raw_fit_results.at(i).empty())
00272 {
00273 i++;
00274 continue;
00275 }
00276
00277 size_t j;
00278 for (j=i+1; j<clusters.size(); j++)
00279 {
00280
00281 if (response.cluster_model_indices[j] != (int)j) continue;
00282
00283 if (raw_fit_results.at(j).empty())
00284 {
00285 if ( fitClusterDistance<PointCloudType>( raw_fit_results.at(i).at(0),
00286 clusters.at(j) ) < fit_merge_threshold_ ) break;
00287 else continue;
00288 }
00289
00290 if ( fitDistance(raw_fit_results.at(i).at(0), raw_fit_results.at(j).at(0)) < fit_merge_threshold_) break;
00291 }
00292 if (j<clusters.size())
00293 {
00294 ROS_INFO("Post-fit merging of clusters %u and %u", (unsigned int) i, (unsigned int) j);
00295
00296 clusters[i].points.insert( clusters[i].points.end(), clusters[j].points.begin(), clusters[j].points.end() );
00297
00298 raw_fit_results.at(j).clear();
00299
00300 response.cluster_model_indices[j] = i;
00301
00302 raw_fit_results.at(i) = detector_.fitBestModels(clusters[i], std::max(1,num_models));
00303 }
00304 else
00305 {
00306 i++;
00307 }
00308 }
00309 }
00310 ROS_INFO("Post-fit merge completed");
00311
00312
00313 for (size_t i=0; i<raw_fit_results.size(); i++)
00314 {
00315 if (response.cluster_model_indices[i] != (int)i)
00316 {
00317 int ind = response.cluster_model_indices[i];
00318 ROS_ASSERT( ind < (int)i);
00319 response.cluster_model_indices[i] = response.cluster_model_indices[ind];
00320 ROS_INFO(" - has been merged with fit for cluster %d", ind);
00321 }
00322 }
00323 ROS_INFO("Clustered indices arranges");
00324
00325 tf::Transform table_trans;
00326 tf::poseMsgToTF(table.pose.pose, table_trans);
00327 for (size_t i=0; i<raw_fit_results.size(); i++)
00328 {
00329 household_objects_database_msgs::DatabaseModelPoseList model_potential_fit_list;
00330
00331 for (size_t j=0; j < raw_fit_results[i].size(); j++)
00332 {
00333
00334 tf::Transform model_trans;
00335 tf::poseMsgToTF(raw_fit_results[i][j].getPose(), model_trans);
00336 model_trans = table_trans * model_trans;
00337 geometry_msgs::Pose model_pose;
00338 tf::poseTFToMsg(model_trans, model_pose);
00339
00340 household_objects_database_msgs::DatabaseModelPose pose_msg;
00341 pose_msg.model_id = raw_fit_results[i][j].getModelId();
00342 pose_msg.pose.header = table.pose.header;
00343 pose_msg.pose.pose = model_pose;
00344 pose_msg.confidence = raw_fit_results[i][j].getScore();
00345
00346 model_potential_fit_list.model_list.push_back(pose_msg);
00347 }
00348 response.models.push_back(model_potential_fit_list);
00349 }
00350 ROS_INFO("Results ready");
00351
00352 }
00353
00354 void TabletopObjectRecognizer::publishFitMarkers(
00355 const std::vector<household_objects_database_msgs::DatabaseModelPoseList> &potential_models,
00356 const Table &table)
00357 {
00358 for (size_t i=0; i<potential_models.size(); i++)
00359 {
00360 const std::vector<household_objects_database_msgs::DatabaseModelPose> models = potential_models[i].model_list;
00361 for (size_t j=0; j<models.size(); j++)
00362 {
00363 if (models[j].confidence > min_marker_quality_) break;
00364 household_objects_database_msgs::GetModelMesh get_mesh;
00365 get_mesh.request.model_id = models[j].model_id;
00366 if ( !get_model_mesh_srv_.call(get_mesh) ||
00367 get_mesh.response.return_code.code != get_mesh.response.return_code.SUCCESS )
00368 {
00369 ROS_ERROR("tabletop_object_detector: failed to call database get mesh service for marker display");
00370 }
00371 else
00372 {
00373 double rank = ((double)j) / std::max( (int)(models.size())-1, 1 );
00374 visualization_msgs::Marker fitMarker = MarkerGenerator::getFitMarker(get_mesh.response.mesh, rank);
00375 fitMarker.header = table.pose.header;
00376 fitMarker.pose = models[j].pose.pose;
00377 fitMarker.ns = "tabletop_node_model_" + boost::lexical_cast<std::string>(j);
00378 fitMarker.id = current_marker_id_++;
00379 marker_pub_.publish(fitMarker);
00380 }
00381 }
00382 }
00383 }
00384
00385 void TabletopObjectRecognizer::clearOldMarkers(std::string frame_id)
00386 {
00387 for (int id=current_marker_id_; id < num_markers_published_; id++)
00388 {
00389 visualization_msgs::Marker delete_marker;
00390 delete_marker.header.stamp = ros::Time::now();
00391 delete_marker.header.frame_id = frame_id;
00392 delete_marker.id = id;
00393 delete_marker.action = visualization_msgs::Marker::DELETE;
00394
00395 for (size_t j=0; j<10; j++)
00396 {
00397 delete_marker.ns = "tabletop_node_model_" + boost::lexical_cast<std::string>(j);
00398 marker_pub_.publish(delete_marker);
00399 }
00400 }
00401 num_markers_published_ = current_marker_id_;
00402 current_marker_id_ = 0;
00403 }
00404
00405 double TabletopObjectRecognizer::fitDistance(const ModelFitInfo &m1, const ModelFitInfo &m2)
00406 {
00407 double dx = m1.getPose().position.x - m2.getPose().position.x;
00408 double dy = m1.getPose().position.y - m2.getPose().position.y;
00409 double d = dx*dx + dy*dy;
00410 return sqrt(d);
00411 }
00412
00413 template <class PointCloudType>
00414 double TabletopObjectRecognizer::fitClusterDistance(const ModelFitInfo &m, const PointCloudType &cluster)
00415 {
00416 double dist = 100.0 * 100.0;
00417 double mx = m.getPose().position.x;
00418 double my = m.getPose().position.x;
00419 for (size_t i=0; i<cluster.points.size(); i++)
00420 {
00421 double dx = cluster.points[i].x - mx;
00422 double dy = cluster.points[i].y - my;
00423 double d = dx*dx + dy*dy;
00424 dist = std::min(d, dist);
00425 }
00426 return sqrt(dist);
00427 }
00428
00429 }
00430
00431 int main(int argc, char **argv)
00432 {
00433 ros::init(argc, argv, "tabletop_object_recognition");
00434 ros::NodeHandle nh;
00435
00436 tabletop_object_detector::TabletopObjectRecognizer node(nh);
00437 ros::spin();
00438 return 0;
00439 }