36 #ifndef JSK_RECOGNITION_UTILS_PCL_CONVERSION_UTIL_H_ 
   37 #define JSK_RECOGNITION_UTILS_PCL_CONVERSION_UTIL_H_ 
   38 #include <pcl/point_types.h> 
   39 #include <pcl/point_cloud.h> 
   41 #include <geometry_msgs/Point32.h> 
   44 #include <pcl/range_image/range_image_planar.h> 
   45 #include <visualization_msgs/Marker.h> 
   46 #if ROS_VERSION_MINIMUM(1, 10, 0) 
   56 #include <opencv2/opencv.hpp> 
   72   template<
class FromT, 
class ToT>
 
   79   template<
class FromT, 
class ToT>
 
   86   template<
class FromT, 
class ToT>
 
   90     to.x = from.x; to.y = from.y; to.z = from.z;
 
   93   template<
class FromT, 
class ToT>
 
   97     to[0] = from[0]; to[1] = from[1]; to[2] = from[2];
 
  100   template<
class FromT, 
class ToT>
 
  104     for (
size_t i = 0; 
i < 4; 
i++) {
 
  105       for (
size_t j = 0; j < 4; j++) {
 
  106         to(
i, j) = from(
i, j);
 
  112                            Eigen::Affine3f& to);
 
  114                            Eigen::Affine3d& to);
 
  116   template <
class Po
intT>
 
  119                              pcl::PointCloud<PointT>& output_cloud)
 
  121     std::vector<double> cumulative_areas;
 
  122     double total_area = 0;
 
  124     if (input_marker.points.size() != input_marker.colors.size()){
 
  125       ROS_ERROR(
"Color and Points nums is different in markerMsgToPointCloud");
 
  130     for (
int i = 0; 
i < (int)input_marker.points.size()/3; 
i++){
 
  131       geometry_msgs::Point p0_1;
 
  132       p0_1.x = input_marker.points[
i*3].x - input_marker.points[
i*3+2].x;
 
  133       p0_1.y = input_marker.points[
i*3].y - input_marker.points[
i*3+2].y;
 
  134       p0_1.z = input_marker.points[
i*3].z - input_marker.points[
i*3+2].z;
 
  135       geometry_msgs::Point p1_2;
 
  136       p1_2.x = input_marker.points[
i*3+1].x - input_marker.points[
i*3+2].x;
 
  137       p1_2.y = input_marker.points[
i*3+1].y - input_marker.points[
i*3+2].y;
 
  138       p1_2.z = input_marker.points[
i*3+1].z - input_marker.points[
i*3+2].z;
 
  139       geometry_msgs::Point outer_product;
 
  140       outer_product.x = p0_1.y * p1_2.z - p0_1.z * p1_2.y;
 
  141       outer_product.y = p0_1.z * p1_2.x - p0_1.x * p1_2.z;
 
  142       outer_product.z = p0_1.x * p1_2.y - p0_1.y * p1_2.x;
 
  143       double tmp_triangle_area = abs(sqrt( pow(outer_product.x*1000, 2) + pow(outer_product.y*1000, 2) + pow(outer_product.z*1000, 2)))/2;
 
  144       total_area += tmp_triangle_area;
 
  145       cumulative_areas.push_back(total_area);
 
  149     for(
int i = 0; 
i < sample_nums; 
i++){
 
  150       double r = rand() * (1.0  / (RAND_MAX + 1.0)) * total_area;
 
  151       std::vector<double>::iterator low = std::lower_bound (cumulative_areas.begin (), cumulative_areas.end (), r);
 
  152       int index = int(low - cumulative_areas.begin ());
 
  156       std_msgs::ColorRGBA color;
 
  157       geometry_msgs::Point p0 = input_marker.points[index*3];
 
  158       geometry_msgs::Point p1 = input_marker.points[index*3+1];
 
  159       geometry_msgs::Point p2 = input_marker.points[index*3+2];
 
  160       std_msgs::ColorRGBA c0= input_marker.colors[index*3];
 
  161       std_msgs::ColorRGBA c1 = input_marker.colors[index*3+1];
 
  162       std_msgs::ColorRGBA c2 = input_marker.colors[index*3+2];
 
  163       r = rand() * (1.0  / (RAND_MAX + 1.0));
 
  165       geometry_msgs::Point point_on_p1_p2;
 
  166       point_on_p1_p2.x = p1.x*r + p2.x*(1.0 - r);
 
  167       point_on_p1_p2.y = p1.y*r + p2.y*(1.0 - r);
 
  168       point_on_p1_p2.z = p1.z*r + p2.z*(1.0 - r);
 
  170       color.r = c1.r*r + c2.r*(1.0 - r);
 
  171       color.g = c1.g*r + c2.g*(1.0 - r);
 
  172       color.b = c1.b*r + c2.b*(1.0 - r);
 
  174       r = sqrt(rand() * (1.0  / (RAND_MAX + 1.0)));
 
  175       geometry_msgs::Point target;
 
  176       target.x = point_on_p1_p2.x*r + p0.x*(1.0 - r);
 
  177       target.y = point_on_p1_p2.y*r + p0.y*(1.0 - r);
 
  178       target.z = point_on_p1_p2.z*r + p0.z*(1.0 - r);
 
  179       color.r = color.r*r + c0.r*(1.0 - r);
 
  180       color.g = color.g*r + c0.g*(1.0 - r);
 
  181       color.b = color.b*r + c0.b*(1.0 - r);
 
  189       output_cloud.points.push_back(
p);
 
  191     output_cloud.width = sample_nums;
 
  192     output_cloud.height = 1;
 
  197     return !std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z);
 
  200   template <
class Po
intT>
 
  203     return !std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z);
 
  210   std::vector<pcl::PointIndices::Ptr>
 
  213   std::vector<pcl::ModelCoefficients::Ptr>
 
  215     const std::vector<PCLModelCoefficientMsg>& coefficients);
 
  217   std::vector<PCLIndicesMsg>
 
  219     const std::vector<pcl::PointIndices::Ptr> cluster_indices,
 
  220     const std_msgs::Header& 
header);
 
  222   std::vector<PCLIndicesMsg>
 
  224     const std::vector<pcl::PointIndices> cluster_indices,
 
  225     const std_msgs::Header& 
header);
 
  227   std::vector<PCLModelCoefficientMsg>
 
  229     const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
 
  230     const std_msgs::Header& 
header);
 
  237   void poseMsgToEigen(
const geometry_msgs::Pose& msg, Eigen::Affine3f& eigen);
 
  238   void poseEigenToMsg(Eigen::Affine3f& eigen, geometry_msgs::Pose& msg);