41 void hsv2rgb(
const float h,
const float s,
const float v,
float& r,
float& g,
float& b)
44 float hprime = h/60.0;
45 float x = c * (1.0 - fabs(fmodf(hprime, 2.0
f) - 1));
51 }
else if (hprime < 2) {
53 }
else if (hprime < 3) {
55 }
else if (hprime < 4) {
57 }
else if (hprime < 5) {
59 }
else if (hprime < 6) {
69 std::vector<pcl::PCLPointField> fields;
70 pcl::getFields(cloud, fields);
71 size_t rgb_field_index;
72 for (rgb_field_index = 0; rgb_field_index < fields.size(); ++rgb_field_index)
74 if (fields[rgb_field_index].name ==
"rgb" ||
75 fields[rgb_field_index].name ==
"rgba")
80 hsv2rgb(hue, 0.8 , 1.0 , r, g, b);
82 for (
size_t j = 0; j < cloud.points.size(); ++j)
84 pcl::PointXYZRGB &p = cloud.points[j];
85 unsigned char* pt_rgb = (
unsigned char*) &p;
86 pt_rgb += fields[rgb_field_index].offset;
87 (*pt_rgb) = (
unsigned char) (r * 255);
88 (*(pt_rgb+1)) = (
unsigned char) (g * 255);
89 (*(pt_rgb+2)) = (
unsigned char) (b * 255);
95 Eigen::Vector4f pp(point);
97 Eigen::Vector4f m(plane->values[0], plane->values[1], plane->values[2], plane->values[3]);