41 #include <sensor_msgs/PointCloud2.h> 
   43 #include <pcl/point_cloud.h> 
   50 #define deg2rad 0.01745329251994329576923690768   // (PI / 180.0) 
   53 #define rad2deg 57.29577951308232087679815481   // (180.0 / PI) 
   57                            int digits_after_decimal_point)
 
   59   std::ostringstream ss;
 
   60   ss << std::fixed << std::setprecision(digits_after_decimal_point) << val;
 
   67   return std::abs(a - b) < 1e-6
f;
 
   72   return atan2(p.y, p.x);
 
   78   std::ostringstream oss;
 
   80   for (ResolutionMap::const_iterator 
s = sector.begin(); 
s != sector.end(); ++
s)
 
   91   PointCloudT::const_iterator ret = iter;
 
   92   for (++iter  ; iter != cloud->end(); ++iter)
 
   94     if (iter->layer == ret->layer)
 
  104 PointCloudT::const_iterator 
getNextPoint(PointCloudT::const_iterator iter, 
const PointCloudT::ConstPtr cloud)
 
  106   PointCloudT::const_iterator ret = iter;
 
  108   if (iter != cloud->end())
 
  118   if (cloud->size() < 10)
 
  125   PointCloudT::const_iterator p;
 
  130   for (p = cloud->begin(); p != cloud->end(); ++p)
 
  132     PointCloudT::const_iterator p2 = 
getNextPoint(p, cloud);
 
  134     double interlaced = 1.;
 
  143     if (angleDiff > 1e-6
f)
 
  150         if (sectors.size() == 0)
 
  152           sectors.push_back(std::make_pair(
getHAngle(*p), angleDiff));
 
  157           if (
almostEqual(
double(sectors.back().second), angleDiff) == 
false)
 
  159             sectors.push_back(std::make_pair(
getHAngle(*p), angleDiff));
 
  172     for (
size_t i = 0; i < sectors.size() - 1; ++i)
 
  174       if (sectors[i].first - sectors[i + 1].first > (3.0 + 1e-6
f) * 
deg2rad &&
 
  175           !
almostEqual(sectors[i].second, sectors[i + 1].second))
 
  177         sectors_filtered.push_back(sectors[i]);
 
  181         sectors[i + 1].first = sectors[i].first;
 
  185     sectors_filtered.push_back(sectors.back());
 
  186     sectors.swap(sectors_filtered);
 
  187     sectors_filtered.clear();
 
  190   std::ostringstream oss;
 
  195 void callback(
const sensor_msgs::PointCloud2::ConstPtr& pc)
 
  198   PointCloudT::Ptr cloud = pcl::make_shared<PointCloudT>();
 
  204 int main(
int argc, 
char **argv)
 
  206   ros::init(argc, argv, 
"sick_ldmrs_print_resolution");