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
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047 #include "octomap_pa/octree_stamped_native_node.h"
00048
00049
00050 #include <parameter_pa/parameter_pa_ros.h>
00051
00052
00053 #include <string>
00054
00055
00056 int main(int argc, char **argv) {
00057
00058 ros::init(argc, argv, "octree_stamped_native_node");
00059 cOctreeStampedNativeNode octomap;
00060
00061 ros::spin();
00062
00063 return 0;
00064 }
00065
00066
00067 cOctreeStampedNativeNode::cOctreeStampedNativeNode() :
00068 cOctreeStampedNativeRos(0.1), tf_listener_(ros::Duration(20), true) {
00069
00070 cParameterPaRos paramloader;
00071
00072 paramloader.load("~/output_frame", rosparams_base_.output_frame_);
00073
00074
00075 double temp;
00076 temp = 0.1 ;
00077 paramloader.load("~/map_resolution" , temp); setResolution (temp);
00078 temp = 0.5 ;
00079 paramloader.load("~/map_prob_threshold", temp); setOccupancyThres (temp);
00080 temp = 0.12;
00081 paramloader.load("~/map_clamp_min" , temp); setClampingThresMin(temp);
00082 temp = 0.97;
00083 paramloader.load("~/map_clamp_max" , temp); setClampingThresMax(temp);
00084
00085
00086 paramloader.load("~/map_prob_hit" , addparams_.map_prob_hit_ );
00087 paramloader.load("~/map_prob_miss" , addparams_.map_prob_miss_ );
00088 paramloader.load("~/pcd_voxel_active" , addparams_.pcd_voxel_active_ );
00089 paramloader.load("~/pcd_voxel_explicit", addparams_.pcd_voxel_explicit_);
00090 paramloader.load("~/pcd_voxel_explicit_relative_resolution",
00091 addparams_.pcd_voxel_explicit_relative_resolution_);
00092 paramloader.load("~/pcd_explicit_transform",
00093 addparams_.pcd_explicit_transform_);
00094
00095
00096 paramloader.load("~/degrading_time" , rosparams_.degrading_time_);
00097 paramloader.load("~/auto_degrading" , rosparams_.auto_degrading_);
00098 paramloader.load("~/auto_degrading_intervall",
00099 rosparams_.auto_degrading_intervall_);
00100
00101
00102 paramloader.loadTopic("~/topic_in_cloud" ,
00103 nodeparams_.topic_in_cloud_ );
00104 paramloader.loadTopic("~/topic_in_cloud_old",
00105 nodeparams_.topic_in_cloud_old_);
00106 paramloader.loadTopic("~/topic_in_laser" ,
00107 nodeparams_.topic_in_laser_ );
00108
00109
00110 paramloader.loadTopic("~/topic_out_octomap" ,
00111 nodeparams_.topic_out_octomap_);
00112 paramloader.loadTopic("~/topic_out_octomap_full" ,
00113 nodeparams_.topic_out_octomap_full_);
00114 paramloader.loadTopic("~/topic_out_cloud_free" ,
00115 nodeparams_.topic_out_cloud_free_);
00116 paramloader.loadTopic("~/topic_out_cloud_occupied",
00117 nodeparams_.topic_out_cloud_occupied_);
00118
00119
00120
00121 if (nodeparams_.topic_in_cloud_ != "") {
00122 sub_cloud_ = nh_.subscribe<sensor_msgs::PointCloud2>(
00123 nodeparams_.topic_in_cloud_, 10,
00124 &cOctreeStampedNativeNode::addPointcloudCallbackSub, this);
00125 }
00126
00127
00128 if (nodeparams_.topic_in_cloud_old_ != "") {
00129 sub_cloud_old_ = nh_.subscribe<sensor_msgs::PointCloud>(
00130 nodeparams_.topic_in_cloud_old_, 10,
00131 &cOctreeStampedNativeNode::addPointcloudOldCallbackSub, this);
00132 }
00133
00134 if (nodeparams_.topic_in_laser_ != "") {
00135 sub_laser_ = nh_.subscribe<sensor_msgs::LaserScan>(
00136 nodeparams_.topic_in_laser_, 10,
00137 &cOctreeStampedNativeNode::addLaserCallbackSub, this);
00138 }
00139
00140
00141
00142 pub_octomap_ = nh_.advertise<octomap_msgs::Octomap>(
00143 nodeparams_.topic_out_octomap_, 10, true);
00144
00145 pub_octomap_full_ = nh_.advertise<octomap_msgs::Octomap>(
00146 nodeparams_.topic_out_octomap_full_, 10, true);
00147
00148
00149 pub_cloud_free_ = nh_.advertise<sensor_msgs::PointCloud2>(
00150 nodeparams_.topic_out_cloud_free_, 10, true);
00151
00152 pub_cloud_occupied_ = nh_.advertise<sensor_msgs::PointCloud2>(
00153 nodeparams_.topic_out_cloud_occupied_, 10, true);
00154
00155 std::string str_service("~/");
00156 str_service = paramloader.resolveRessourcename(str_service);
00157
00158 srv_clear_ = nh_.advertiseService(str_service + "clear",
00159 &cOctreeStampedNativeNode::clearCallbackSrv, this);
00160
00161 srv_getsize_ = nh_.advertiseService(str_service + "getsize",
00162 &cOctreeStampedNativeNode::getSizeCallbackSrv, this);
00163
00164 srv_save_ = nh_.advertiseService(str_service + "save",
00165 &cOctreeStampedNativeNode::saveCallbackSrv, this);
00166
00167 srv_load_ = nh_.advertiseService(str_service + "load",
00168 &cOctreeStampedNativeNode::loadCallbackSrv, this);
00169
00170
00171 count_cloud_ = 0;
00172 count_cloud_old_ = 0;
00173 count_laser_ = 0;
00174 }
00175
00176
00177 cOctreeStampedNativeNode::~cOctreeStampedNativeNode() {
00178
00179 }
00180
00181
00182 void cOctreeStampedNativeNode::publishOctomap() {
00183
00184 if (pub_octomap_.getNumSubscribers() > 0) {
00185 pub_octomap_.publish(getOctomap());
00186 }
00187 if (pub_octomap_full_.getNumSubscribers() > 0) {
00188 pub_octomap_.publish(getOctomapFull());
00189 }
00190
00191 if (pub_cloud_occupied_.getNumSubscribers() > 0) {
00192 pub_cloud_occupied_.publish(getOctomapPcd());
00193 }
00194 if (pub_cloud_free_.getNumSubscribers() > 0) {
00195 pub_cloud_free_.publish(getOctomapPcdFree());
00196 }
00197 }
00198
00199
00200 void cOctreeStampedNativeNode::addPointcloudCallbackSub(
00201 const sensor_msgs::PointCloud2ConstPtr &msg) {
00202
00203 if (!updateTime(msg->header.stamp)) {
00204 tf_listener_.clear();
00205 return;
00206 }
00207
00208 tf::StampedTransform transform;
00209
00210 try {
00211 tf_listener_.waitForTransform(rosparams_base_.output_frame_,
00212 msg->header.frame_id, msg->header.stamp, ros::Duration(0.2));
00213 tf_listener_.lookupTransform(rosparams_base_.output_frame_,
00214 msg->header.frame_id, msg->header.stamp, transform);
00215 } catch (tf::TransformException &ex){
00216 ROS_WARN("%s",ex.what());
00217 return;
00218 }
00219
00220 if (addCloud(msg, addparams_, transform)) {
00221 count_cloud_++;
00222 checkDegrading();
00223 publishOctomap();
00224 }
00225 }
00226
00227
00228 void cOctreeStampedNativeNode::addPointcloudOldCallbackSub(
00229 const sensor_msgs::PointCloudConstPtr &msg) {
00230
00231 if (!updateTime(msg->header.stamp)) {
00232 tf_listener_.clear();
00233 return;
00234 }
00235
00236 tf::StampedTransform transform;
00237
00238 try {
00239 tf_listener_.waitForTransform(rosparams_base_.output_frame_,
00240 msg->header.frame_id, msg->header.stamp, ros::Duration(0.2));
00241 tf_listener_.lookupTransform(rosparams_base_.output_frame_,
00242 msg->header.frame_id, msg->header.stamp, transform);
00243 } catch (tf::TransformException &ex){
00244 ROS_WARN("%s",ex.what());
00245 return;
00246 }
00247
00248 if (addCloud(msg, addparams_, transform)) {
00249 count_cloud_old_++;
00250 checkDegrading();
00251 publishOctomap();
00252 }
00253 }
00254
00255
00256 void cOctreeStampedNativeNode::addLaserCallbackSub(
00257 const sensor_msgs::LaserScanConstPtr &msg) {
00258
00259 if (!updateTime(msg->header.stamp)) {
00260 tf_listener_.clear();
00261 return;
00262 }
00263
00264 tf::StampedTransform transform;
00265
00266 try {
00267 tf_listener_.waitForTransform(rosparams_base_.output_frame_,
00268 msg->header.frame_id, msg->header.stamp, ros::Duration(0.2));
00269 tf_listener_.lookupTransform(rosparams_base_.output_frame_,
00270 msg->header.frame_id, msg->header.stamp, transform);
00271 } catch (tf::TransformException &ex){
00272 ROS_WARN("%s",ex.what());
00273 return;
00274 }
00275
00276 updateTime(msg->header.stamp);
00277 if (addCloud(msg, addparams_, transform)) {
00278 count_laser_++;
00279 checkDegrading();
00280 publishOctomap();
00281 }
00282 }
00283
00284
00285
00286 bool cOctreeStampedNativeNode::clearCallbackSrv(std_srvs::Empty::Request &req,
00287 std_srvs::Empty::Response &res) {
00288
00289 ROS_INFO("cOctreeStampedNativeNode::clear()");
00290
00291 count_cloud_ = 0;
00292 count_cloud_old_ = 0;
00293 count_laser_ = 0;
00294
00295 clear();
00296 tf_listener_.clear();
00297
00298 return true;
00299 }
00300
00301
00302 bool cOctreeStampedNativeNode::getSizeCallbackSrv (
00303 octomap_pa::OctomapPaGetSize::Request &req,
00304 octomap_pa::OctomapPaGetSize::Response &res) {
00305
00306 ROS_INFO("cOctreeStampedNativeNode::getsize()");
00307
00308 res.size = size();
00309 res.memoryusage = (int64_t) memoryUsage();
00310
00311 res.count_cloud = count_cloud_ ;
00312 res.count_cloud_old = count_cloud_old_;
00313 res.count_laser = count_laser_ ;
00314
00315 return true;
00316 }
00317
00318
00319 bool cOctreeStampedNativeNode::saveCallbackSrv(
00320 octomap_pa::OctomapPaFileName::Request &req,
00321 octomap_pa::OctomapPaFileName::Response &res) {
00322
00323 ROS_INFO_STREAM("cOctreeStampedNativeNode::save(" << req.filename << ")");
00324
00325 std::string filename;
00326 filename = req.filename;
00327 cParameterPaRos par;
00328 par.replaceFindpack(filename);
00329
00330
00331 res.ok = this->write(filename);
00332
00333 return res.ok;
00334 }
00335
00336
00337 bool cOctreeStampedNativeNode::loadCallbackSrv(
00338 octomap_pa::OctomapPaFileName::Request &req,
00339 octomap_pa::OctomapPaFileName::Response &res) {
00340
00341 ROS_INFO_STREAM("cOctreeStampedNativeNode::load(" << req.filename << ")");
00342
00343 std::string filename;
00344 filename = req.filename;
00345 cParameterPaRos par;
00346 par.replaceFindpack(filename);
00347
00348
00349 res.ok = readFull(filename);
00350
00351 if (res.ok) { publishOctomap(); }
00352 return res.ok;
00353 }