36 #define BOOST_PARAMETER_MAX_ARITY 7 
   41 using octomap_msgs::Octomap;
 
   47     DiagnosticNodelet(
"OctomapServerContact"),
 
   48     m_octreeContact(
NULL),
 
   49     m_publishUnknownSpace(false),
 
   50     m_publishFrontierSpace(false),
 
   51     m_offsetVisualizeUnknown(0),
 
   52     m_maxRangeProximity(0.05),
 
   53     m_occupancyMinX(-
std::numeric_limits<double>::
max()),
 
   54     m_occupancyMaxX(
std::numeric_limits<double>::
max()),
 
   55     m_occupancyMinY(-
std::numeric_limits<double>::
max()),
 
   56     m_occupancyMaxY(
std::numeric_limits<double>::
max()),
 
   57     m_useContactSurface(true)
 
   64       ROS_ERROR(
"Could not convert OcTreeContact from OcTree");
 
   83     privateNh.
param(
"color_unknown/r", 
r, 0.5);
 
   84     privateNh.
param(
"color_unknown/g", 
g, 0.5);
 
   85     privateNh.
param(
"color_unknown/b", 
b, 0.7);
 
   86     privateNh.
param(
"color_unknown/a", 
a, 1.0);
 
   91     privateNh.
param(
"color_frontier/r", 
r, 1.0);
 
   92     privateNh.
param(
"color_frontier/g", 
g, 0.0);
 
   93     privateNh.
param(
"color_frontier/b", 
b, 0.0);
 
   94     privateNh.
param(
"color_frontier/a", 
a, 1.0);
 
  122     double defaultPadding, defaultScale;
 
  123     privateNh.
param<
double>(
"self_see_defaultPadding", defaultPadding, .01);
 
  124     privateNh.
param<
double>(
"self_see_defaultScale", defaultScale, 1.0);
 
  125     std::vector<robot_self_filter::LinkInfo> 
links;
 
  127     if (!privateNh.
hasParam(
"self_see_links")) {
 
  128       ROS_WARN(
"No links specified for self filtering.");
 
  132       privateNh.
getParam(
"self_see_links", sslVals);
 
  134         ROS_WARN(
"Self see links need to be an array");
 
  137         if (sslVals.
size() == 0) {
 
  138           ROS_WARN(
"No values in self see links array");
 
  141           for (
int i = 0; 
i < sslVals.
size(); 
i++) {
 
  144               ROS_WARN(
"Self see links entry %d is not a structure.  Stopping processing of self see links",
i);
 
  147             if (!sslVals[
i].hasMember(
"name")) {
 
  148               ROS_WARN(
"Self see links entry %d has no name.  Stopping processing of self see links",
i);
 
  151             li.
name = std::string(sslVals[
i][
"name"]);
 
  152             if (!sslVals[
i].hasMember(
"padding")) {
 
  153               ROS_DEBUG(
"Self see links entry %d has no padding.  Assuming default padding of %g",
i,defaultPadding);
 
  159             if (!sslVals[
i].hasMember(
"scale")) {
 
  160               ROS_DEBUG(
"Self see links entry %d has no scale.  Assuming default scale of %g",
i,defaultScale);
 
  161               li.
scale = defaultScale;
 
  164               li.
scale = sslVals[
i][
"scale"];
 
  189       ROS_ERROR_STREAM( 
"Transform error of sensor data: " << 
ex.what() << 
", quitting callback");
 
  193     Eigen::Matrix4f sensorToWorld;
 
  197     pcl::transformPointCloud(pc, pc, sensorToWorld);
 
  199     pc.header = pc.header;
 
  204     ROS_DEBUG(
"Pointcloud insertion in OctomapServer done (%zu pts, %f sec)", pc.size(), total_elapsed);
 
  210     point3d sensorOrigin = pointTfToOctomap(sensorOriginTf);
 
  218 #ifdef COLOR_OCTOMAP_SERVER 
  219     unsigned char* colors = 
new unsigned char[3];
 
  223     KeySet free_cells, occupied_cells;
 
  226     for (PCLPointCloud::const_iterator it = pc.begin(); it != pc.end(); ++it) {
 
  238           occupied_cells.insert(key);
 
  243 #ifdef COLOR_OCTOMAP_SERVER // NB: Only read and interpret color if it's an occupied node 
  244           const int rgb = *
reinterpret_cast<const int*
>(&(it->rgb)); 
 
  245           colors[0] = ((
rgb >> 16) & 0xff);
 
  246           colors[1] = ((
rgb >> 8) & 0xff);
 
  247           colors[2] = (
rgb & 0xff);
 
  248           m_octree->averageNodeColor(it->x, it->y, it->z, colors[0], colors[1], colors[2]);
 
  268     for(KeySet::iterator it = free_cells.begin(), 
end=free_cells.end(); it!= 
end; ++it){
 
  269       if (occupied_cells.find(*it) == occupied_cells.end()){
 
  275     for (KeySet::iterator it = occupied_cells.begin(), 
end=occupied_cells.end(); it!= 
end; it++) {
 
  306 #ifdef COLOR_OCTOMAP_SERVER 
  316     std::vector<jsk_recognition_msgs::ContactSensor> 
datas = 
msg->datas;
 
  320       std_msgs::Header tmpHeader;
 
  322       tmpHeader.stamp = 
msg->header.stamp;
 
  335     unsigned int steps[3];
 
  337     for (
int i = 0; 
i < 3; ++
i) {
 
  338       diff[
i] = pmax(
i) - pmin(
i);
 
  345       std::vector< std::vector<bool> > containFlag(
datas.size(), std::vector<bool>(8));
 
  347       for (
unsigned int x = 0; 
x < steps[0]; ++
x) {
 
  349         for (
unsigned int y = 0; 
y < steps[1]; ++
y) {
 
  351           for (
unsigned int z = 0; 
z < steps[2]; ++
z) {
 
  357             for (
int i = 0; 
i < 2; 
i++) {
 
  359               for (
int j = 0; j < 2; j++) {
 
  361                 for (
int k = 0; 
k < 2; 
k++) {
 
  363                   vertex = 
p + vertexOffset;
 
  366                   for (
int l=0; 
l<
datas.size(); 
l++) {
 
  369                       containFlag[
l][
i+j*2+
k*4] = 
true;
 
  372                       containFlag[
l][
i+j*2+
k*4] = 
false;
 
  382             std::vector<bool> containFlagLinkSum(8, 
false);
 
  383             std::vector<bool> containFlagVerticesSum(
datas.size(), 
false);
 
  384             std::vector<bool> containFlagVerticesProd(
datas.size(), 
true);
 
  385             bool insideFlag = 
false;
 
  386             bool surfaceFlag = 
false;
 
  387             for (
int l = 0; 
l < 
datas.size(); 
l++) {
 
  388               for (
int i = 0; 
i < 8; 
i++) {
 
  389                 if (containFlag[
l][
i]) {
 
  390                   containFlagLinkSum[
i] = 
true;
 
  391                   containFlagVerticesSum[
l] = 
true;
 
  394                   containFlagVerticesProd[
l] = 
false;
 
  398             insideFlag = (std::find(containFlagLinkSum.begin(), containFlagLinkSum.end(), 
false) == containFlagLinkSum.end()); 
 
  399             for (
int l = 0; 
l < 
datas.size(); 
l++) {
 
  400               if (containFlagVerticesSum[
l] && !(containFlagVerticesProd[
l]) ) {
 
  413             else if (surfaceFlag) { 
 
  428 #pragma omp parallel for 
  429       for (
unsigned int cnt = 0; cnt < steps[0] * steps[1] * steps[2]; ++cnt) {
 
  434           id[0] = cnt / (steps[1] * steps[2]);
 
  435           id[1] = (cnt % (steps[1] * steps[2])) / steps[2];
 
  436           id[2] = (cnt % (steps[1] * steps[2])) % steps[2];
 
  442         vertex = 
p + vertexOffset;
 
  444         for (
int l=0; 
l<
datas.size(); 
l++) {
 
  470     if (octomapSize <= 1) {
 
  471       ROS_WARN(
"Nothing to publish, octree is empty");
 
  485     visualization_msgs::MarkerArray freeNodesVis;
 
  489     geometry_msgs::Pose 
pose;
 
  493     visualization_msgs::MarkerArray occupiedNodesVis;
 
  498     pcl::PointCloud<pcl::PointXYZ> pclCloud;
 
  514         double x = it.getX();
 
  515         double y = it.getY();
 
  516         double z = it.getZ();
 
  518           double size = it.getSize();
 
  519           double x = it.getX();
 
  520           double y = it.getY();
 
  524             ROS_DEBUG(
"Ignoring single speckle at (%f,%f,%f)", 
x, 
y, 
z);
 
  534           if (publishMarkerArray) {
 
  535             unsigned idx = it.getDepth();
 
  536             assert(idx < occupiedNodesVis.markers.size());
 
  538             geometry_msgs::Point cubeCenter;
 
  543             occupiedNodesVis.markers[idx].points.push_back(cubeCenter);
 
  545               double minX, minY, minZ, maxX, maxY, maxZ;
 
  550               occupiedNodesVis.markers[idx].colors.push_back(
heightMapColor(h));
 
  555           if (publishPointCloud) {
 
  556             pclCloud.push_back(pcl::PointXYZ(
x, 
y, 
z));
 
  561         double x = it.getX();
 
  562         double y = it.getY();
 
  563         double z = it.getZ();
 
  570             double x = it.getX();
 
  571             double y = it.getY();
 
  574             if (publishFreeMarkerArray) {
 
  575               unsigned idx = it.getDepth();
 
  576               assert(idx < freeNodesVis.markers.size());
 
  578               geometry_msgs::Point cubeCenter;
 
  583               freeNodesVis.markers[idx].points.push_back(cubeCenter);
 
  594     if (publishMarkerArray) {
 
  595       for (
unsigned i = 0; 
i < occupiedNodesVis.markers.size(); ++
i) {
 
  599         occupiedNodesVis.markers[
i].header.stamp = rostime;
 
  601         occupiedNodesVis.markers[
i].id = 
i;
 
  602         occupiedNodesVis.markers[
i].type = visualization_msgs::Marker::CUBE_LIST;
 
  603         occupiedNodesVis.markers[
i].scale.x = 
size;
 
  604         occupiedNodesVis.markers[
i].scale.y = 
size;
 
  605         occupiedNodesVis.markers[
i].scale.z = 
size;
 
  606         occupiedNodesVis.markers[
i].color = 
m_color;
 
  609         if (occupiedNodesVis.markers[
i].points.size() > 0) {
 
  610           occupiedNodesVis.markers[
i].action = visualization_msgs::Marker::ADD;
 
  613           occupiedNodesVis.markers[
i].action = visualization_msgs::Marker::DELETE;
 
  622     if (publishFreeMarkerArray) {
 
  623       for (
unsigned i = 0; 
i < freeNodesVis.markers.size(); ++
i) {
 
  627         freeNodesVis.markers[
i].header.stamp = rostime;
 
  629         freeNodesVis.markers[
i].id = 
i;
 
  630         freeNodesVis.markers[
i].type = visualization_msgs::Marker::CUBE_LIST;
 
  631         freeNodesVis.markers[
i].scale.x = 
size;
 
  632         freeNodesVis.markers[
i].scale.y = 
size;
 
  633         freeNodesVis.markers[
i].scale.z = 
size;
 
  637         if (freeNodesVis.markers[
i].points.size() > 0) {
 
  638           freeNodesVis.markers[
i].action = visualization_msgs::Marker::ADD;
 
  641           freeNodesVis.markers[
i].action = visualization_msgs::Marker::DELETE;
 
  650     if (publishUnknownMarkerArray) {
 
  651       visualization_msgs::MarkerArray unknownNodesVis;
 
  652       unknownNodesVis.markers.resize(1);
 
  660       pcl::PointCloud<pcl::PointXYZ> unknownCloud;
 
  662       for (point3d_list::iterator it = unknownLeaves.begin(); it != unknownLeaves.end(); it++) {
 
  666         unknownCloud.push_back(pcl::PointXYZ(
x, 
y, 
z));
 
  668         geometry_msgs::Point cubeCenter;
 
  673           double minX, minY, minZ, maxX, maxY, maxZ;
 
  679         unknownNodesVis.markers[0].points.push_back(cubeCenter);
 
  684       unknownNodesVis.markers[0].header.stamp = rostime;
 
  686       unknownNodesVis.markers[0].id = 0;
 
  687       unknownNodesVis.markers[0].type = visualization_msgs::Marker::CUBE_LIST;
 
  688       unknownNodesVis.markers[0].scale.x = 
size;
 
  689       unknownNodesVis.markers[0].scale.y = 
size;
 
  690       unknownNodesVis.markers[0].scale.z = 
size;
 
  693       if (unknownNodesVis.markers[0].points.size() > 0) {
 
  694         unknownNodesVis.markers[0].action = visualization_msgs::Marker::ADD;
 
  697         unknownNodesVis.markers[0].action = visualization_msgs::Marker::DELETE;
 
  702       sensor_msgs::PointCloud2 unknownRosCloud;
 
  705       unknownRosCloud.header.stamp = rostime;
 
  709       if (publishFrontierMarkerArray) {
 
  710         visualization_msgs::MarkerArray frontierNodesVis;
 
  711         frontierNodesVis.markers.resize(1);
 
  712         pcl::PointCloud<pcl::PointXYZ> frontierCloud;
 
  718         std::vector< std::vector< std::vector<int> > > check_unknown(x_num, std::vector< std::vector<int> >(y_num, std::vector<int>(z_num)));
 
  719         std::vector< std::vector< std::vector<int> > > check_occupied(x_num, std::vector< std::vector<int> >(y_num, std::vector<int>(z_num)));
 
  720         std::vector< std::vector< std::vector<int> > > check_frontier(x_num, std::vector< std::vector<int> >(y_num, std::vector<int>(z_num)));
 
  722         for (
int i = 0; 
i < x_num; 
i++) {
 
  723           for (
int j = 0; j < y_num; j++) {
 
  724             for (
int k = 0; 
k < z_num; 
k++) {
 
  725               check_unknown[
i][j][
k] = 0;
 
  726               check_occupied[
i][j][
k] = 0;
 
  727               check_frontier[
i][j][
k] = 0;
 
  733         for (point3d_list::iterator it_unknown = unknownLeaves.begin();
 
  734              it_unknown != unknownLeaves.end();
 
  737           double x_unknown = it_unknown->x();
 
  738           double y_unknown = it_unknown->y();
 
  739           double z_unknown = it_unknown->z();
 
  743           check_unknown[x_index][y_index][z_index] = 1;
 
  747         for (
int idx = 0; idx < occupiedNodesVis.markers.size(); idx++) {
 
  748           double size_occupied = occupiedNodesVis.markers[idx].scale.x;
 
  749           for (
int id = 0; 
id < occupiedNodesVis.markers[idx].points.size(); 
id++) {
 
  750             double x_occupied = occupiedNodesVis.markers[idx].points[id].x;
 
  751             double y_occupied = occupiedNodesVis.markers[idx].points[id].y;
 
  752             double z_occupied = occupiedNodesVis.markers[idx].points[id].z;
 
  756             for (
int i = x_min_index; 
i < x_min_index + int(size_occupied/
resolution); 
i++) {
 
  757               for (
int j = y_min_index; j < y_min_index + int(size_occupied/
resolution); j++) {
 
  758                 for (
int k = z_min_index; 
k < z_min_index + int(size_occupied/
resolution); 
k++) {
 
  759                   check_occupied[
i][j][
k] = 1;
 
  769         geometry_msgs::Point cubeCenter;
 
  770         for (
int i = 0; 
i < x_num; 
i++) {
 
  771           for (
int j = 0; j < y_num; j++) {
 
  772             for (
int k = 0; 
k < z_num-1; 
k++) {
 
  773               for (
int l = -1; 
l <= 1; 
l++) {
 
  774                 if ( 
i+
l < 0 || x_num <= 
i+
l ) 
continue;
 
  775                 for (
int m = -1; 
m <= 1; 
m++) {
 
  776                   if ( j+
m < 0 || y_num <= j+
m ) 
continue;
 
  777                   for (
int n = -1; 
n <= 1; 
n++) {
 
  778                     if (  
k+
n < 0 || z_num <= 
k+
n ) 
continue;
 
  779                     if (
l == 0 && 
m == 0 && 
n== 0) 
continue;
 
  780                     if (check_unknown[
i+
l][j+
m][
k+
n] == 1 && check_unknown[
i][j][
k] == 0 && check_occupied[
i][j][
k] == 0 && check_frontier[
i][j][
k] == 0) {
 
  781                       check_frontier[
i][j][
k] = 1;
 
  786                         double minX, minY, minZ, maxX, maxY, maxZ;
 
  792                       frontierNodesVis.markers[0].points.push_back(cubeCenter);
 
  804         frontierNodesVis.markers[0].header.stamp = rostime;
 
  806         frontierNodesVis.markers[0].id = 0;
 
  807         frontierNodesVis.markers[0].type = visualization_msgs::Marker::CUBE_LIST;
 
  808         frontierNodesVis.markers[0].scale.x = 
size;
 
  809         frontierNodesVis.markers[0].scale.y = 
size;
 
  810         frontierNodesVis.markers[0].scale.z = 
size;
 
  813         if (frontierNodesVis.markers[0].points.size() > 0) {
 
  814           frontierNodesVis.markers[0].action = visualization_msgs::Marker::ADD;
 
  817           frontierNodesVis.markers[0].action = visualization_msgs::Marker::DELETE;
 
  823         sensor_msgs::PointCloud2 frontierRosCloud;
 
  826         frontierRosCloud.header.stamp = rostime;
 
  832     if (publishPointCloud) {
 
  833       sensor_msgs::PointCloud2 
cloud;
 
  836       cloud.header.stamp = rostime;
 
  840     if (publishBinaryMap) {
 
  844     if (publishFullMap) {
 
  849     ROS_DEBUG(
"Map publishing in OctomapServer took %f sec", totalElapsed);
 
  854     DiagnosticNodelet::onInit();