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
00037 #include <ros/ros.h>
00038 #include <std_srvs/Empty.h>
00039 #include <sensor_msgs/PointCloud.h>
00040 #include <mapping_msgs/CollisionMap.h>
00041 #include <tf/transform_listener.h>
00042 #include <tf/message_filter.h>
00043 #include <message_filters/subscriber.h>
00044
00045 #include <boost/thread/mutex.hpp>
00046 #include <boost/bind.hpp>
00047 #include <vector>
00048 #include <algorithm>
00049 #include <set>
00050 #include <iterator>
00051 #include <cstdlib>
00052 #include <collision_environment_msgs/MakeStaticCollisionMapAction.h>
00053 #include <actionlib/server/simple_action_server.h>
00054
00055 #include <collision_environment_msgs/SetCloudSettings.h>
00056 #include <collision_environment_msgs/GetCloudSettings.h>
00057
00058
00059 struct CloudInfo
00060 {
00061 CloudInfo(): cloud_name_(""), frame_subsample_(1.0),
00062 point_subsample_(1.0), sensor_frame_(""), counter_(0),
00063 dynamic_buffer_size_(1), static_buffer_size_(1),
00064 dynamic_buffer_duration_(0), static_buffer_duration_(0),
00065 dynamic_publish_(true), static_publish_(true),
00066 dynamic_until_static_publish_(true)
00067 {
00068 };
00069 std::string cloud_name_;
00070 int frame_subsample_;
00071 int point_subsample_;
00072 std::string sensor_frame_;
00073 unsigned int counter_;
00074
00075 unsigned int dynamic_buffer_size_, static_buffer_size_;
00076 ros::Duration dynamic_buffer_duration_, static_buffer_duration_;
00077
00078
00079
00080
00081
00082
00083
00084 bool dynamic_publish_, static_publish_, dynamic_until_static_publish_;
00085 };
00086
00087 class CollisionMapperOcc
00088 {
00089 public:
00090
00091 CollisionMapperOcc(void): root_handle_(""), making_static_collision_map_(false), disregard_first_message_(false)
00092 {
00093 static_map_goal_ = NULL;
00094
00095 ros::NodeHandle priv("~");
00096
00097
00098 priv.param<std::string>("fixed_frame", fixedFrame_, "odom");
00099
00100
00101 priv.param<std::string>("robot_frame", robotFrame_, "base_link");
00102
00103
00104 priv.param<double>("dimension_x", bi_.dimensionX, 1.0);
00105 priv.param<double>("dimension_y", bi_.dimensionY, 1.5);
00106 priv.param<double>("dimension_z", bi_.dimensionZ, 2.0);
00107
00108
00109 priv.param<double>("origin_x", bi_.originX, 1.1);
00110 priv.param<double>("origin_y", bi_.originY, 0.0);
00111 priv.param<double>("origin_z", bi_.originZ, 0.0);
00112
00113
00114
00115
00116
00117 priv.param<double>("resolution", bi_.resolution, 0.015);
00118
00119 ROS_INFO("Maintaining occlusion map in frame '%s', with origin at (%f, %f, %f) and dimension (%f, %f, %f), resolution of %f; "
00120 "sensor is in frame '%s', fixed fame is '%s'.",
00121 robotFrame_.c_str(), bi_.originX, bi_.originY, bi_.originZ, bi_.dimensionX, bi_.dimensionY, bi_.dimensionZ,
00122 bi_.resolution, bi_.sensor_frame.c_str(), fixedFrame_.c_str());
00123
00124 priv.param<bool>("publish_occlusion", publishOcclusion_, false);
00125 priv.param<bool>("publish_static_over_dynamic_map", publish_over_dynamic_map_, false);
00126
00127
00128
00129 bi_.real_minX = -bi_.dimensionX + bi_.originX;
00130 bi_.real_maxX = bi_.dimensionX + bi_.originX;
00131 bi_.real_minY = -bi_.dimensionY + bi_.originY;
00132 bi_.real_maxY = bi_.dimensionY + bi_.originY;
00133 bi_.real_minZ = -bi_.dimensionZ + bi_.originZ;
00134 bi_.real_maxZ = bi_.dimensionZ + bi_.originZ;
00135
00136
00137
00138
00139 cmapPublisher_ = root_handle_.advertise<mapping_msgs::CollisionMap>("collision_map_occ", 1, true);
00140 cmapUpdPublisher_ = root_handle_.advertise<mapping_msgs::CollisionMap>("collision_map_occ_update", 1);
00141 static_map_publisher_ = root_handle_.advertise<mapping_msgs::CollisionMap>("collision_map_occ_static", 1);
00142
00143 if(!priv.hasParam("cloud_sources")) {
00144 ROS_WARN("No links specified for self filtering.");
00145 } else {
00146 XmlRpc::XmlRpcValue cloud_vals;
00147 priv.getParam("cloud_sources", cloud_vals);
00148
00149 if(cloud_vals.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00150 ROS_WARN("Cloud sources needs to be an array");
00151 } else {
00152 for(int i = 0; i < cloud_vals.size(); i++) {
00153 CloudInfo cps;
00154 if(cloud_vals[i].getType() != XmlRpc::XmlRpcValue::TypeStruct) {
00155 ROS_WARN("Cloud source entry %d is not a structure. Stopping processing of cloud sources",i);
00156 break;
00157 }
00158 if(!cloud_vals[i].hasMember("name")) {
00159 ROS_WARN("Cloud sources entry %d has no name. Stopping processing of cloud sources",i);
00160 break;
00161 }
00162 if(!cloud_vals[i].hasMember("sensor_frame")) {
00163 ROS_WARN("Cloud sources entry %d has no sensor_frame. Stopping processing of cloud sources",i);
00164 break;
00165 }
00166 cps.cloud_name_ = std::string(cloud_vals[i]["name"]);
00167 cps.sensor_frame_ = std::string(cloud_vals[i]["sensor_frame"]);
00168 if(!cloud_vals[i].hasMember("frame_subsample")) {
00169 ROS_DEBUG("Cloud sources entry %d has no frame subsample. Assuming default subsample of %g",i,1.0);
00170 cps.frame_subsample_ = 1.0;;
00171 } else {
00172 cps.frame_subsample_ = cloud_vals[i]["frame_subsample"];
00173 }
00174 if(!cloud_vals[i].hasMember("point_subsample")) {
00175 cps.point_subsample_ = 1.0;;
00176 } else {
00177 cps.point_subsample_ = cloud_vals[i]["point_subsample"];
00178 }
00179
00180 if(cloud_vals[i].hasMember("dynamic_buffer_size"))
00181 cps.dynamic_buffer_size_ = static_cast<unsigned int>(int(cloud_vals[i]["dynamic_buffer_size"]));
00182
00183 if(cloud_vals[i].hasMember("static_buffer_size"))
00184 cps.static_buffer_size_ = static_cast<unsigned int>(int(cloud_vals[i]["static_buffer_size"]));
00185
00186 if(cloud_vals[i].hasMember("dynamic_buffer_duration"))
00187 cps.dynamic_buffer_duration_ = ros::Duration(int(cloud_vals[i]["dynamic_buffer_duration"]));
00188
00189 if(cloud_vals[i].hasMember("static_buffer_duration"))
00190 cps.static_buffer_duration_ = ros::Duration(int(cloud_vals[i]["static_buffer_duration"]));
00191
00192 if(cloud_vals[i].hasMember("dynamic_publish"))
00193 cps.dynamic_publish_ = cloud_vals[i]["dynamic_publish"];
00194
00195 if(cloud_vals[i].hasMember("static_publish"))
00196 cps.static_publish_ = cloud_vals[i]["static_publish"];
00197
00198 if(cloud_vals[i].hasMember("dynamic_until_static_publish")) {
00199 cps.dynamic_until_static_publish_ = cloud_vals[i]["dynamic_until_static_publish"];
00200 }
00201
00202 if(cloud_source_map_.find(cps.cloud_name_) != cloud_source_map_.end()) {
00203 ROS_WARN_STREAM("Already have a cloud defined with name " << cps.cloud_name_);
00204 } else {
00205 cloud_source_map_[cps.cloud_name_] = cps;
00206 mn_cloud_tf_sub_vector_.push_back(new message_filters::Subscriber<sensor_msgs::PointCloud>(root_handle_, cps.cloud_name_, 1));
00207 mn_cloud_tf_fil_vector_.push_back(new tf::MessageFilter<sensor_msgs::PointCloud>(*(mn_cloud_tf_sub_vector_.back()), tf_, "", 1));
00208 mn_cloud_tf_fil_vector_.back()->registerCallback(boost::bind(&CollisionMapperOcc::cloudCallback, this, _1, cps.cloud_name_));
00209
00210
00211
00212
00213 static_map_published_[cps.cloud_name_] = false;
00214 ROS_INFO_STREAM("Source name " << cps.cloud_name_);
00215 }
00216 }
00217 }
00218 }
00219
00220
00221
00222
00223
00224
00225 std::vector<std::string> frames;
00226
00227 if (std::find(frames.begin(), frames.end(), robotFrame_) == frames.end()) {
00228 frames.push_back(robotFrame_);
00229 }
00230 for(unsigned int i = 0; i < mn_cloud_tf_fil_vector_.size(); i++) {
00231 mn_cloud_tf_fil_vector_[i]->setTargetFrames(frames);
00232 }
00233
00234 resetService_ = priv.advertiseService("reset", &CollisionMapperOcc::reset, this);
00235
00236 action_server_.reset(new actionlib::SimpleActionServer<collision_environment_msgs::MakeStaticCollisionMapAction>(root_handle_, "make_static_collision_map",
00237 boost::bind(&CollisionMapperOcc::makeStaticCollisionMap, this, _1)));
00238 set_settings_server_ = root_handle_.advertiseService<collision_environment_msgs::SetCloudSettings::Request,collision_environment_msgs::SetCloudSettings::Response>("set_collision_map_cloud_settings", boost::bind(&CollisionMapperOcc::setCloudSettings, this, _1, _2));
00239
00240 get_settings_server_ = root_handle_.advertiseService<collision_environment_msgs::GetCloudSettings::Request,collision_environment_msgs::GetCloudSettings::Response>("get_collision_map_cloud_settings", boost::bind(&CollisionMapperOcc::getCloudSettings, this, _1, _2));
00241
00242 }
00243
00244 ~CollisionMapperOcc(void)
00245 {
00246
00247 for(std::map<std::string, std::list<StampedCMap*> >::iterator it = currentMaps_.begin(); it != currentMaps_.end(); it++)
00248 {
00249 for(std::list<StampedCMap*>::iterator itbuff = it->second.begin(); itbuff != it->second.end(); itbuff++)
00250 {
00251 delete (*itbuff);
00252 }
00253 }
00254
00255 for(std::map<std::string, StampedCMap*>::iterator it = tempMaps_.begin();
00256 it != tempMaps_.end();
00257 it++) {
00258 delete it->second;
00259 }
00260
00261 for(unsigned int i = 0; i < mn_cloud_tf_sub_vector_.size(); i++) {
00262 delete mn_cloud_tf_sub_vector_[i];
00263 }
00264 for(unsigned int i = 0; i < mn_cloud_tf_fil_vector_.size(); i++) {
00265 delete mn_cloud_tf_fil_vector_[i];
00266 }
00267
00268 if(static_map_goal_) delete static_map_goal_;
00269
00270 }
00271
00272 void run(void)
00273 {
00274
00275
00276
00277 ros::spin();
00278 }
00279
00280 private:
00281
00282 struct CollisionPoint
00283 {
00284 CollisionPoint(void) {}
00285 CollisionPoint(int _x, int _y, int _z) : x(_x), y(_y), z(_z) {}
00286
00287 int x, y, z;
00288 };
00289
00290
00291 struct CollisionPointOrder
00292 {
00293 bool operator()(const CollisionPoint &a, const CollisionPoint &b) const
00294 {
00295 if (a.x < b.x)
00296 return true;
00297 if (a.x > b.x)
00298 return false;
00299 if (a.y < b.y)
00300 return true;
00301 if (a.y > b.y)
00302 return false;
00303 return a.z < b.z;
00304 }
00305 };
00306
00307 typedef std::set<CollisionPoint, CollisionPointOrder> CMap;
00308
00309 struct StampedCMap
00310 {
00311 std::string frame_id;
00312 ros::Time stamp;
00313 CMap cmap;
00314 };
00315
00316
00317
00318
00319 struct BoxInfo
00320 {
00321 double dimensionX, dimensionY, dimensionZ;
00322 double originX, originY, originZ;
00323 std::string sensor_frame;
00324 double resolution;
00325 double real_minX, real_minY, real_minZ;
00326 double real_maxX, real_maxY, real_maxZ;
00327 };
00328
00329 bool getCloudSettings(collision_environment_msgs::GetCloudSettings::Request &req, collision_environment_msgs::GetCloudSettings::Response &res )
00330 {
00331 if(cloud_source_map_.find(req.cloud_name) != cloud_source_map_.end())
00332 {
00333 CloudInfo settings = cloud_source_map_[req.cloud_name];
00334
00335 res.settings.cloud_name = settings.cloud_name_;
00336
00337 res.settings.dynamic_publish = (settings.dynamic_publish_) ? int(res.settings.INCLUDE) : int(res.settings.EXCLUDE);
00338 res.settings.static_publish = (settings.static_publish_) ? int(res.settings.INCLUDE) : int(res.settings.EXCLUDE);
00339
00340 res.value = res.SUCCESS;
00341
00342 }
00343 else
00344 {
00345 res.value = res.NAME_NONEXISTANT;
00346 }
00347
00348 return true;
00349 }
00350
00351
00352 bool setCloudSettings(collision_environment_msgs::SetCloudSettings::Request &req, collision_environment_msgs::SetCloudSettings::Response &res )
00353 {
00354 if(cloud_source_map_.find(req.settings.cloud_name) != cloud_source_map_.end())
00355 {
00356 CloudInfo settings = cloud_source_map_[req.settings.cloud_name];
00357
00358 if(req.settings.dynamic_publish)
00359 {
00360 if(req.settings.dynamic_publish == req.settings.INCLUDE)
00361 {
00362 settings.dynamic_publish_ = true;
00363 }
00364 else
00365 {
00366 settings.dynamic_publish_ = false;
00367 }
00368 }
00369
00370 if(req.settings.static_publish)
00371 {
00372 if(req.settings.static_publish == req.settings.INCLUDE)
00373 {
00374 settings.static_publish_ = true;
00375 }
00376 else
00377 {
00378 settings.static_publish_ = false;
00379 }
00380 }
00381
00382
00383 if(!settings.dynamic_publish_)
00384 {
00385 std::map<std::string, std::list<StampedCMap*> >::iterator it = currentMaps_.find(settings.cloud_name_+"_dynamic");
00386 if(it != currentMaps_.end())
00387 {
00388 for(std::list<StampedCMap*>::iterator itbuff = it->second.begin(); itbuff != it->second.end(); itbuff++)
00389 {
00390 delete (*itbuff);
00391 }
00392
00393 it->second.clear();
00394
00395 }
00396 }
00397
00398 if(!settings.static_publish_)
00399 {
00400 std::map<std::string, std::list<StampedCMap*> >::iterator it = currentMaps_.find(settings.cloud_name_+"_static");
00401 if(it != currentMaps_.end())
00402 {
00403 for(std::list<StampedCMap*>::iterator itbuff = it->second.begin(); itbuff != it->second.end(); itbuff++)
00404 {
00405 delete (*itbuff);
00406 }
00407
00408 it->second.clear();
00409
00410 }
00411 }
00412
00413 cloud_source_map_[req.settings.cloud_name] = settings;
00414
00415 res.value = res.SUCCESS;
00416
00417 ROS_DEBUG_STREAM("Changed settings for " << req.settings.cloud_name);
00418 ROS_DEBUG_STREAM(" Publish dynamic: " << ((settings.dynamic_publish_) ? "true" : "false"));
00419 ROS_DEBUG_STREAM(" Publish static: " << ((settings.static_publish_) ? "true" : "false"));
00420 ROS_DEBUG_STREAM("Other settings: ");
00421 ROS_DEBUG_STREAM(" Frame subsample: " << settings.frame_subsample_);
00422 ROS_DEBUG_STREAM(" Point subsample: " << settings.point_subsample_);
00423 ROS_DEBUG_STREAM(" Dynamic buffer size: " << settings.dynamic_buffer_size_);
00424 ROS_DEBUG_STREAM(" Dynamic buffer duration: " << settings.dynamic_buffer_duration_);
00425 ROS_DEBUG_STREAM(" Static buffer size: " << settings.static_buffer_size_);
00426 ROS_DEBUG_STREAM(" Static buffer duration: " << settings.static_buffer_duration_);
00427
00428 }
00429
00430 else
00431 {
00432 res.value = res.NAME_NONEXISTANT;
00433 }
00434
00435 return true;
00436 }
00437
00438
00439 void cloudIncrementalCallback(const sensor_msgs::PointCloudConstPtr &cloud)
00440 {
00441 if (!mapProcessing_.try_lock())
00442 return;
00443
00444 ros::WallTime tm = ros::WallTime::now();
00445
00446 ROS_DEBUG("Got pointcloud update that is %f seconds old", (ros::Time::now() - cloud->header.stamp).toSec());
00447
00448 sensor_msgs::PointCloud out;
00449
00450
00451
00452
00453
00454
00455
00456
00457
00458
00459
00460 tf_.transformPointCloud(robotFrame_, *cloud, out);
00461
00462
00463 CMap obstacles;
00464 constructCollisionMap(out, obstacles);
00465
00466 CMap diff;
00467
00468
00469 mapProcessing_.unlock();
00470
00471 if (!diff.empty())
00472 publishCollisionMap(diff, out.header.frame_id, out.header.stamp, cmapUpdPublisher_);
00473 }
00474
00475 void subsampleCloudPoints(const sensor_msgs::PointCloud &msg, sensor_msgs::PointCloud& myMsg, int subsampleNum) {
00476 myMsg.points.clear();
00477 myMsg.header = msg.header;
00478
00479
00480 for(int i = 0; i < (int)msg.points.size(); i += subsampleNum) {
00481 myMsg.points.push_back(msg.points[i]);
00482
00483
00484
00485 }
00486 }
00487
00488 void updateBuffer(std::list<StampedCMap*> &buffer, const unsigned int buffer_size, const ros::Duration buffer_duration, const std::string sensor_frame)
00489 {
00490 if(buffer_size > 1)
00491 {
00492 while(buffer.size() > buffer_size)
00493 {
00494 ROS_DEBUG_STREAM("Deleting old map in frame " << sensor_frame << " total buffer size: " << buffer.size());
00495 delete buffer.back();
00496 buffer.pop_back();
00497 }
00498 }
00499
00500 if(buffer_duration > ros::Duration(0))
00501 {
00502 ros::Time min_time = buffer.front()->stamp - buffer_duration;
00503
00504 while(buffer.back()->stamp < min_time)
00505 {
00506 ROS_DEBUG_STREAM("Deleting old map in frame " << sensor_frame << " which is too old by: " << min_time - buffer.back()->stamp << " seconds" );
00507 delete buffer.back();
00508 buffer.pop_back();
00509 }
00510 }
00511
00512
00513 if(buffer_size <= 1 && buffer_duration <= ros::Duration(0))
00514 {
00515 ROS_DEBUG_STREAM("Keeping only most recent map in frame " << sensor_frame );
00516 while(buffer.size() > 1)
00517 {
00518 delete buffer.back();
00519 buffer.pop_back();
00520 }
00521 }
00522
00523 }
00524
00525 void composeMapUnion(std::map<std::string, std::list<StampedCMap*> > &maps, CMap &uni)
00526 {
00527
00528 for(std::map<std::string, std::list<StampedCMap*> >::iterator it = maps.begin(); it != maps.end(); it++)
00529 {
00530 int processed = 0;
00531 for(std::list<StampedCMap*>::iterator itbuff = it->second.begin(); itbuff != it->second.end(); itbuff++)
00532 {
00533 set_union(uni.begin(), uni.end(), (*itbuff)->cmap.begin(), (*itbuff)->cmap.end(), std::inserter(uni, uni.begin()), CollisionPointOrder());
00534 processed++;
00535 }
00536
00537 ROS_DEBUG_STREAM("The buffer for sensor frame " << it->first << " had " << processed << " maps");
00538 }
00539
00540 }
00541
00542 void cloudCallback(const sensor_msgs::PointCloudConstPtr &cloud, const std::string topic_name)
00543 {
00544 CloudInfo settings = cloud_source_map_[topic_name];
00545
00546 if(!making_static_collision_map_ && !settings.dynamic_publish_ && (!settings.dynamic_until_static_publish_ || static_map_published_[topic_name])) {
00547 return;
00548 }
00549
00550
00551
00552
00553
00554 ros::WallTime tm = ros::WallTime::now();
00555
00556 sensor_msgs::PointCloud subCloud;
00557
00558 ROS_DEBUG("Got pointcloud that is %f seconds old", (ros::Time::now() - cloud->header.stamp).toSec());
00559 ROS_DEBUG("Received %u data points.",(unsigned int)(*cloud).points.size ());
00560 subsampleCloudPoints(*cloud, subCloud, settings.point_subsample_);
00561 ROS_DEBUG("After subsampling we have %u data points.",(unsigned int)subCloud.points.size ());
00562
00563
00564 boost::recursive_mutex::scoped_lock lock(mapProcessing_);
00565
00566 CMap obstacles;
00567
00568 sensor_msgs::PointCloud transCloud;
00569
00570 tf_.transformPointCloud(robotFrame_, subCloud, transCloud);
00571
00572
00573
00574
00575 constructCollisionMap(transCloud, obstacles);
00576
00577 if(making_static_collision_map_ && topic_name == static_map_goal_->cloud_source) {
00578 if(disregard_first_message_) {
00579 disregard_first_message_ = false;
00580 } else {
00581
00582 std::string map_name = topic_name+"_static_temp";
00583 StampedCMap* static_map;
00584 if(tempMaps_.find(map_name) != tempMaps_.end()) {
00585 static_map = tempMaps_[map_name];
00586 } else {
00587 static_map = new StampedCMap();
00588 static_map->frame_id = transCloud.header.frame_id;
00589 static_map->stamp = transCloud.header.stamp;
00590 tempMaps_[map_name] = static_map;
00591 }
00592 updateMap(&static_map->cmap, obstacles, transCloud.header.frame_id, transCloud.header.stamp, settings.sensor_frame_, settings.cloud_name_);
00593 if(++cloud_count_ == static_map_goal_->number_of_clouds) {
00594
00595 ROS_DEBUG("Publishing static map");
00596 publishCollisionMap(static_map->cmap, transCloud.header.frame_id, transCloud.header.stamp, static_map_publisher_);
00597
00598 if(!settings.static_publish_)
00599 {
00600 delete static_map;
00601 }
00602 else
00603 {
00604 ROS_DEBUG("Saving static map for inclusion in future dynamic maps");
00605 currentMaps_[topic_name+"_static"].push_front(static_map);
00606
00607 updateBuffer(currentMaps_[topic_name+"_static"], settings.static_buffer_size_, settings.static_buffer_duration_, topic_name+"_static");
00608
00609 if(settings.dynamic_until_static_publish_) {
00610
00611 std::list<StampedCMap*>& dyn_list = currentMaps_[topic_name+"_dynamic"];
00612 for(std::list<StampedCMap*>::iterator it = dyn_list.begin(); it != dyn_list.end(); it++) {
00613 delete (*it);
00614 }
00615 currentMaps_.erase(topic_name+"_dynamic");
00616 }
00617
00618 CMap uni;
00619 composeMapUnion(currentMaps_, uni);
00620
00621 publishCollisionMap(uni, transCloud.header.frame_id, transCloud.header.stamp, cmapPublisher_);
00622 }
00623
00624 tempMaps_.erase(map_name);
00625 making_static_collision_map_ = false;
00626 static_map_published_[topic_name] = true;
00627 }
00628 }
00629 }
00630
00631 if(settings.dynamic_publish_ || (settings.dynamic_until_static_publish_ && !static_map_published_[topic_name]))
00632 {
00633
00634 StampedCMap* current_map;
00635
00636
00637 if(settings.dynamic_buffer_size_ == 1 && currentMaps_.find(topic_name+"_dynamic") != currentMaps_.end()) {
00638 current_map = currentMaps_[topic_name+"_dynamic"].front();
00639
00640
00641
00642
00643
00644
00645
00646
00647 } else {
00648 current_map = new StampedCMap();
00649 current_map->frame_id = transCloud.header.frame_id;
00650 current_map->stamp = transCloud.header.stamp;
00651 currentMaps_[topic_name+"_dynamic"].push_front(current_map);
00652 }
00653
00654
00655 updateMap(¤t_map->cmap, obstacles, transCloud.header.frame_id, transCloud.header.stamp, settings.sensor_frame_, settings.cloud_name_);
00656 updateBuffer(currentMaps_[topic_name+"_dynamic"], settings.dynamic_buffer_size_, settings.dynamic_buffer_duration_, topic_name+"_dynamic");
00657
00658 CMap uni;
00659 composeMapUnion(currentMaps_, uni);
00660
00661 publishCollisionMap(uni, transCloud.header.frame_id, transCloud.header.stamp, cmapPublisher_);
00662
00663 }
00664
00665 double sec = (ros::WallTime::now() - tm).toSec();
00666 ROS_DEBUG("Updated collision map took %g seconds",sec);
00667
00668 }
00669
00670
00671
00672 void updateMap(CMap* currentMap, CMap &obstacles,
00673 std::string &frame_id,
00674 ros::Time &stamp,
00675 std::string to_frame_id,
00676 std::string cloud_name)
00677 {
00678 if (currentMap->empty())
00679 {
00680 *currentMap = obstacles;
00681 }
00682 else
00683 {
00684 CMap diff;
00685
00686
00687 set_difference(currentMap->begin(), currentMap->end(), obstacles.begin(), obstacles.end(),
00688 std::inserter(diff, diff.begin()), CollisionPointOrder());
00689
00690
00691 *currentMap = obstacles;
00692
00693
00694
00695
00696
00697
00698 int n = diff.size();
00699 std::vector<CollisionPoint> pts(n);
00700 std::copy(diff.begin(), diff.end(), pts.begin());
00701
00702
00703
00704
00705
00706
00707
00708
00709
00710
00711
00712
00713
00714
00715
00716
00717
00718
00719
00720
00721
00722
00723
00724
00725
00726
00727
00728
00729
00730
00731
00732
00733
00734
00735
00736
00737
00738
00739
00740
00741
00742
00743
00744
00745
00746
00747 }
00748 }
00749
00750 bool reset(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
00751 {
00752 boost::recursive_mutex::scoped_lock lock(mapProcessing_);
00753
00754 for(std::map<std::string, std::list<StampedCMap*> >::iterator it = currentMaps_.begin(); it != currentMaps_.end(); it++)
00755 {
00756 for(std::list<StampedCMap*>::iterator itbuff = it->second.begin(); itbuff != it->second.end(); itbuff++)
00757 {
00758 delete (*itbuff);
00759 }
00760 }
00761
00762 for(std::map<std::string, StampedCMap*>::iterator it = tempMaps_.begin();
00763 it != tempMaps_.end();
00764 it++) {
00765 delete it->second;
00766 }
00767
00768 currentMaps_.clear();
00769 tempMaps_.clear();
00770
00771 CMap uni;
00772 composeMapUnion(currentMaps_, uni);
00773
00774 publishCollisionMap(uni, robotFrame_, ros::Time::now(), cmapPublisher_);
00775
00776 return true;
00777 }
00778
00779 bool transformMap(CMap &map,
00780 const std::string &from_frame_id,
00781 const ros::Time &from_stamp,
00782 const std::string &to_frame_id,
00783 const ros::Time &to_stamp)
00784 {
00785 tf::StampedTransform transf;
00786 std::string err;
00787 ros::Time tm;
00788 ROS_DEBUG("Transforming old map");
00789 ROS_DEBUG_STREAM("From id: " << from_frame_id <<" at time " << from_stamp << " to id: " << to_frame_id << " at time " << to_stamp);
00790 if(from_frame_id == to_frame_id)
00791 {
00792 if(from_frame_id == fixedFrame_)
00793 {
00794 ROS_DEBUG("Nothing to transform, returning");
00795 return true;
00796 }
00797 try {
00798 tf_.lookupTransform(to_frame_id, to_stamp, from_frame_id, from_stamp, fixedFrame_, transf);
00799 ROS_DEBUG("Got transform!");
00800 } catch(...) {
00801 ROS_WARN("Unable to transform previous collision map into new frame");
00802 return false;
00803 }
00804 }
00805 else if (tf_.getLatestCommonTime(to_frame_id, from_frame_id, tm, &err) == tf::NO_ERROR) {
00806 try {
00807 tf_.lookupTransform(to_frame_id, tm, from_frame_id, tm, fixedFrame_, transf);
00808 } catch(...) {
00809 ROS_WARN("Unable to transform previous collision map into new frame");
00810 return false;
00811 }
00812 } else {
00813 ROS_WARN_STREAM("No common time between " << to_frame_id << " and " << from_frame_id);
00814 }
00815
00816 float disp = transf.getOrigin().length();
00817 float angle = transf.getRotation().getAngle();
00818
00819 ROS_DEBUG_STREAM("Old frame displaced by " << disp << " and angle " << angle << " to get new frame");
00820
00821
00822
00823 const int n = map.size();
00824 std::vector<CollisionPoint> pts(n);
00825 std::copy(map.begin(), map.end(), pts.begin());
00826 map.clear();
00827
00828
00829 for (int i = 0 ; i < n ; ++i)
00830 {
00831 btVector3 p(((double)pts[i].x - 0.5) * bi_.resolution + bi_.originX,
00832 ((double)pts[i].y - 0.5) * bi_.resolution + bi_.originY,
00833 ((double)pts[i].z - 0.5) * bi_.resolution + bi_.originZ);
00834 p = transf * p;
00835 if (p.x() > bi_.real_minX && p.x() < bi_.real_maxX && p.y() > bi_.real_minY && p.y() < bi_.real_maxY && p.z() > bi_.real_minZ && p.z() < bi_.real_maxZ)
00836 {
00837 CollisionPoint c((int)(0.5 + (p.x() - bi_.originX) / bi_.resolution),
00838 (int)(0.5 + (p.y() - bi_.originY) / bi_.resolution),
00839 (int)(0.5 + (p.z() - bi_.originZ) / bi_.resolution));
00840
00841 {
00842 map.insert(c);
00843 }
00844
00845 }
00846 }
00847
00848 return true;
00849
00850 }
00851
00853 void constructCollisionMap(const sensor_msgs::PointCloud &cloud, CMap &map)
00854 {
00855 const unsigned int n = cloud.points.size();
00856 CollisionPoint c;
00857
00858 for (unsigned int i = 0 ; i < n ; ++i)
00859 {
00860 const geometry_msgs::Point32 &p = cloud.points[i];
00861 if (p.x > bi_.real_minX && p.x < bi_.real_maxX && p.y > bi_.real_minY && p.y < bi_.real_maxY && p.z > bi_.real_minZ && p.z < bi_.real_maxZ)
00862 {
00863 c.x = (int)(0.5 + (p.x - bi_.originX) / bi_.resolution);
00864 c.y = (int)(0.5 + (p.y - bi_.originY) / bi_.resolution);
00865 c.z = (int)(0.5 + (p.z - bi_.originZ) / bi_.resolution);
00866 map.insert(c);
00867 }
00868 }
00869 }
00870
00871 void publishCollisionMap(const CMap &map,
00872 const std::string &frame_id,
00873 const ros::Time &stamp,
00874 ros::Publisher &pub) const
00875 {
00876 mapping_msgs::CollisionMap cmap;
00877 cmap.header.frame_id = frame_id;
00878 cmap.header.stamp = stamp;
00879 const unsigned int ms = map.size();
00880
00881 for (CMap::const_iterator it = map.begin() ; it != map.end() ; ++it)
00882 {
00883 const CollisionPoint &cp = *it;
00884 mapping_msgs::OrientedBoundingBox box;
00885 box.extents.x = box.extents.y = box.extents.z = bi_.resolution;
00886 box.axis.x = box.axis.y = 0.0; box.axis.z = 1.0;
00887 box.angle = 0.0;
00888 box.center.x = cp.x * bi_.resolution + bi_.originX;
00889 box.center.y = cp.y * bi_.resolution + bi_.originY;
00890 box.center.z = cp.z * bi_.resolution + bi_.originZ;
00891 cmap.boxes.push_back(box);
00892 }
00893 pub.publish(cmap);
00894
00895 ROS_DEBUG("Published collision map with %u boxes", ms);
00896 }
00897
00898 void makeStaticCollisionMap(const collision_environment_msgs::MakeStaticCollisionMapGoalConstPtr& goal) {
00899
00900 if(cloud_source_map_.find(goal->cloud_source) == cloud_source_map_.end())
00901 {
00902 ROS_ERROR_STREAM("Could not make static map for source: "<<goal->cloud_source);
00903 ROS_ERROR_STREAM("Currently making maps from the following sources:");
00904
00905 for(std::map<std::string,CloudInfo>::iterator it = cloud_source_map_.begin();
00906 it != cloud_source_map_.end();
00907 it++)
00908 {
00909 ROS_ERROR_STREAM(it->first);
00910 }
00911 action_server_->setAborted();
00912 return;
00913 }
00914
00915 static_map_goal_ = new collision_environment_msgs::MakeStaticCollisionMapGoal(*goal);
00916 cloud_count_ = 0;
00917 making_static_collision_map_ = true;
00918 disregard_first_message_ = true;
00919
00920 ros::Rate r(10);
00921 while(making_static_collision_map_) {
00922 if(action_server_->isPreemptRequested()) {
00923 making_static_collision_map_ = false;
00924
00925 std::string map_name = static_map_goal_->cloud_source + "_static_temp";
00926 if(tempMaps_.find(map_name) != tempMaps_.end())
00927 {
00928 delete tempMaps_[map_name];
00929 tempMaps_.erase(map_name);
00930 }
00931
00932 break;
00933 }
00934 r.sleep();
00935 }
00936
00937 if(publish_over_dynamic_map_)
00938 {
00939
00940 for(std::map<std::string,CloudInfo>::iterator it = cloud_source_map_.begin();
00941 it != cloud_source_map_.end();
00942 it++)
00943 {
00944 it->second.dynamic_publish_ = false;
00945 }
00946 }
00947
00948 delete static_map_goal_;
00949 if(action_server_->isPreemptRequested()) {
00950 action_server_->setPreempted();
00951 } else {
00952 action_server_->setSucceeded();
00953 }
00954 }
00955
00956 boost::recursive_mutex mapProcessing_;
00957
00958 tf::TransformListener tf_;
00959
00960
00961 std::vector<message_filters::Subscriber<sensor_msgs::PointCloud>* > mn_cloud_tf_sub_vector_;
00962 std::vector<tf::MessageFilter<sensor_msgs::PointCloud>* > mn_cloud_tf_fil_vector_;
00963
00964 ros::NodeHandle root_handle_;
00965 ros::Publisher cmapPublisher_;
00966 ros::Publisher cmapUpdPublisher_;
00967 ros::Publisher static_map_publisher_;
00968 std::map<std::string, ros::Publisher> occPublisherMap_;
00969 ros::ServiceServer resetService_;
00970 bool publishOcclusion_;
00971
00972 collision_environment_msgs::MakeStaticCollisionMapGoal *static_map_goal_;
00973 bool making_static_collision_map_;
00974 bool publish_over_dynamic_map_;
00975 bool disregard_first_message_;
00976 int cloud_count_;
00977
00978
00979 std::map<std::string, std::list<StampedCMap*> > currentMaps_;
00980 std::map<std::string, StampedCMap*> tempMaps_;
00981
00982 BoxInfo bi_;
00983 std::string fixedFrame_;
00984 std::string robotFrame_;
00985
00986 std::map<std::string,CloudInfo> cloud_source_map_;
00987 std::map<std::string,bool> static_map_published_;
00988 boost::shared_ptr<actionlib::SimpleActionServer<collision_environment_msgs::MakeStaticCollisionMapAction> > action_server_;
00989
00990 ros::ServiceServer get_settings_server_;
00991 ros::ServiceServer set_settings_server_;
00992
00993
00994
00995 };
00996
00997 void spinThread()
00998 {
00999 ros::spin();
01000 }
01001
01002 int main (int argc, char** argv)
01003 {
01004 ros::init(argc, argv, "collision_map_self_occ");
01005
01006 boost::thread spin_thread(&spinThread);
01007
01008 CollisionMapperOcc cm;
01009
01010 while(ros::ok()) {
01011 ros::Duration(0.1).sleep();
01012 }
01013
01014 ros::shutdown();
01015 spin_thread.join();
01016
01017 return 0;
01018 }