$search
00001 /* 00002 * plane_tracker.cc 00003 * Mac Mason <mmason@willowgarage.com> 00004 * 00005 * Fundamentally, this is a gadget for tracking a set of planes. The basic 00006 * operation is "listen for planes, and integrate them into the set". However, 00007 * we do this in a slightly goofy manner. We provide a service, which takes in 00008 * a set of planes ("integrate these") and returns a new set of planes ("once 00009 * integrated, those planes are now these planes"). The idea is for the 00010 * segmenter to find some planes, ship them over, and get back the planes it 00011 * should really be working with. 00012 * 00013 * At the moment, this just sends back all of the planes each time; that's a 00014 * fairly small number. 00015 */ 00016 00017 #include <vector> 00018 #include <boost/scoped_ptr.hpp> 00019 #include <boost/foreach.hpp> 00020 #define foreach BOOST_FOREACH 00021 #include "ros/ros.h" 00022 #include "tf/transform_listener.h" 00023 #include "pcl16/point_types.h" 00024 #include "pcl16_ros/point_cloud.h" 00025 #include "visualization_msgs/Marker.h" 00026 #include "semanticmodel/detailedplane.hh" 00027 #include "semanticmodel/PlaneExchange.h" 00028 #include "semanticmodel/Planes.h" 00029 #include "mongo_ros/message_collection.h" 00030 #include "semanticmodel/GetCollectionNamespace.h" 00031 00032 namespace mr=mongo_ros; 00033 namespace vm=visualization_msgs; 00034 00035 typedef pcl16::PointXYZRGB Point; 00036 typedef pcl16::PointCloud<Point> PointCloud; 00037 00038 namespace semanticmodel 00039 { 00040 00041 class Node 00042 { 00043 public: 00044 00045 void visualize(const ros::WallTimerEvent& e = ros::WallTimerEvent()); 00046 void publishPlanes(); 00047 bool mergePlanes(); 00048 void savePlanesToDB(); 00049 bool planeSrvCB(PlaneExchange::Request& req, PlaneExchange::Response& resp); 00050 void dropSmallAreaPolygons(double min_area); 00051 00052 Node(); 00053 ~Node(); 00054 00055 private: 00056 00057 ros::NodeHandle nh; 00058 ros::NodeHandle p_nh; 00059 00060 // I/O 00061 ros::ServiceServer merge_srv; 00062 00063 // Push our visualization messages. 00064 ros::Publisher vis_pub; 00065 00066 // Push one cloud containing all of the plane points. 00067 ros::Publisher all_planes_pub; 00068 00069 // The planes themselves. 00070 std::vector<DetailedPlane::Ptr> planes; 00071 00072 // We need to be able to transform between frames in DetailedPlane. This 00073 // needs to be a pointer so that we don't get get a NodeHandle before 00074 // ros::init. 00075 boost::scoped_ptr<tf::TransformListener> listener; 00076 00077 // Interface to db 00078 typedef mr::MessageCollection<Planes> PlaneCollection; 00079 boost::scoped_ptr<PlaneCollection> plane_coll; 00080 00081 // How many planes have been saved to the db so far 00082 unsigned num_saved_planes; 00083 00084 // Timer to visualize. Make it a WallTimer so it'll run even if a 00085 // bag is paused. 00086 ros::WallTimer visualize_timer; 00087 }; 00088 00089 // Send out our visualization message. 00090 void Node::visualize(const ros::WallTimerEvent& e) 00091 { 00092 if (planes.size() == 0) 00093 return; 00094 00095 visualization_msgs::Marker marker; 00096 marker.header.frame_id = planes[0]->cloud->header.frame_id; 00097 marker.header.stamp = planes[0]->cloud->header.stamp; 00098 00099 marker.id = 0; 00100 marker.ns = "planes"; 00101 marker.type = visualization_msgs::Marker::LINE_LIST; 00102 marker.action = visualization_msgs::Marker::ADD; 00103 marker.scale.x = 0.01; 00104 marker.color.r = marker.color.g = marker.color.b = marker.color.a = 1.0; 00105 00106 foreach(DetailedPlane::Ptr plane, planes) 00107 { 00108 size_t n = plane->hull->points.size(); 00109 for (size_t i = 0 ; i < n ; ++i) 00110 { 00111 size_t j; 00112 if (i > 0) 00113 j = i - 1; 00114 else 00115 j = n - 1; 00116 00117 marker.points.push_back(geometry_msgs::Point()); 00118 marker.points.back().x = plane->hull->points[j].x; 00119 marker.points.back().y = plane->hull->points[j].y; 00120 marker.points.back().z = plane->hull->points[j].z; 00121 00122 marker.points.push_back(geometry_msgs::Point()); 00123 marker.points.back().x = plane->hull->points[i].x; 00124 marker.points.back().y = plane->hull->points[i].y; 00125 marker.points.back().z = plane->hull->points[i].z; 00126 00127 marker.colors.push_back(plane->color); 00128 marker.colors.push_back(plane->color); 00129 } 00130 } 00131 vis_pub.publish(marker); 00132 } 00133 00134 // Push a message of all of our plane points. 00135 void Node::publishPlanes() 00136 { 00137 if (planes.size() == 0) 00138 return; 00139 00140 PointCloud::Ptr all(new PointCloud()); 00141 all->header.frame_id = planes[0]->cloud->header.frame_id; 00142 foreach(DetailedPlane::Ptr plane, planes) 00143 { 00144 *all += *plane->cloud; 00145 } 00146 all_planes_pub.publish(all); 00147 } 00148 00149 // This works like our object-merging algorithm from the object tracker. 00150 // Basically, here's the plan: the plane-to-be-merged is the last element of 00151 // planes. We check for things we need to merge; if we merge something, we put 00152 // it at the back, and return true. Otherwise, we return false. See 00153 // plane_srv_cb for how to use this. 00154 bool Node::mergePlanes() 00155 { 00156 // Skip the last one. 00157 for (size_t i = 0 ; i < planes.size() - 1 ; ++i) 00158 { 00159 if (planes[i]->overlaps(*planes.back())) 00160 { 00161 planes[i]->mergeFrom(*planes.back()); 00162 // Our new one has been absorbed. 00163 planes.pop_back(); 00164 // Restore our invariant. 00165 std::swap(planes[i], planes.back()); 00166 return true; 00167 } 00168 } 00169 return false; 00170 } 00171 00172 Plane convertToMsg (DetailedPlane::Ptr dp) 00173 { 00174 return dp->toPlaneMsg(); 00175 } 00176 00177 void Node::savePlanesToDB () 00178 { 00179 // First get the existing set so we can delete it later 00180 typedef mr::MessageWithMetadata<Planes>::ConstPtr PlanesPtr; 00181 std::vector<PlanesPtr> existing = plane_coll->pullAllResults(mr::Query()); 00182 00183 // Next, generate a ros message for the current set and save it 00184 Planes planes_msg; 00185 transform(planes.begin(), planes.end(), back_inserter(planes_msg.planes), 00186 convertToMsg); 00187 plane_coll->insert(planes_msg); 00188 00189 // Remove the old one if necessary 00190 if (existing.size()>0) 00191 { 00192 ROS_ASSERT(existing.size()==1); 00193 plane_coll->removeMessages(existing[0]->metadata); 00194 } 00195 } 00196 00197 bool Node::planeSrvCB(PlaneExchange::Request& req, 00198 PlaneExchange::Response& res) 00199 { 00200 ROS_DEBUG_NAMED("plane_tracker", 00201 "Received plane update request with %zu planes", 00202 req.in_planes.planes.size()); 00203 // Here's the copy. We do a push_back because our merging algorithm assumes 00204 // the plane-to-be-merged is at the back. 00205 foreach(Plane& p, req.in_planes.planes) 00206 { 00207 planes.push_back( 00208 DetailedPlane::Ptr(new DetailedPlane(p, listener.get()))); 00209 // Merge them together. 00210 while (mergePlanes()); 00211 } 00212 00213 ROS_DEBUG_NAMED("plane_tracker", "After merging, have %zu planes", 00214 planes.size()); 00215 00216 // Now, do some culling. 00217 dropSmallAreaPolygons(0.10); 00218 00219 ROS_DEBUG_NAMED("plane_tracker", "After dropping small planes, %zu are left", 00220 planes.size()); 00221 00222 res.out_planes.planes.resize(planes.size()); 00223 for (size_t i = 0 ; i < planes.size() ; ++i) 00224 { 00225 planes[i]->toHullAndEquationPlaneMsg(res.out_planes.planes[i]); 00226 } 00227 00228 visualize(); 00229 publishPlanes(); 00230 savePlanesToDB(); 00231 00232 ROS_DEBUG_NAMED("plane_tracker", "Plane update complete; now have %zu planes", 00233 planes.size()); 00234 return true; 00235 } 00236 00237 void Node::dropSmallAreaPolygons(double min_area) 00238 { 00239 std::vector<DetailedPlane::Ptr> bigplanes; 00240 for (size_t i = 0 ; i < planes.size() ; ++i) 00241 { 00242 if (planes[i]->area() >= min_area) 00243 bigplanes.push_back(planes[i]); 00244 } 00245 std::swap(planes, bigplanes); 00246 } 00247 00248 Node::Node () : 00249 p_nh("~"), num_saved_planes(0) 00250 { 00251 // Ok, to figure out which collection to store the planes in, we have 00252 // to call a service 00253 ROS_INFO_STREAM("Waiting for service get_db_name"); 00254 GetCollectionNamespace coll_ns_srv; 00255 ros::service::waitForService("get_collection_namespace"); 00256 ros::service::call("get_collection_namespace", coll_ns_srv); 00257 const std::string cname = coll_ns_srv.response.collection_namespace+"_planes"; 00258 ROS_INFO_STREAM ("Db for plane tracker is " << coll_ns_srv.response.db_name 00259 << "/" << cname); 00260 plane_coll.reset(new PlaneCollection(coll_ns_srv.response.db_name, cname)); 00261 00262 listener.reset(new tf::TransformListener(ros::Duration(600))); 00263 merge_srv = p_nh.advertiseService("plane_srv", &Node::planeSrvCB, this); 00264 vis_pub = p_nh.advertise<vm::Marker>("/visualization_marker", 100); 00265 00266 all_planes_pub = p_nh.advertise<PointCloud>("all_planes", 100, true); 00267 00268 visualize_timer = 00269 nh.createWallTimer(ros::WallDuration(1.0), &Node::visualize, this); 00270 ROS_INFO ("Plane tracker initialized"); 00271 } 00272 00273 Node::~Node () 00274 { 00275 } 00276 00277 } // namespace 00278 00279 int main(int argc, char** argv) 00280 { 00281 ros::init(argc, argv, "filter"); 00282 semanticmodel::Node node; 00283 ros::spin(); 00284 return 0; 00285 }