Skip to content

Commit 7530b36

Browse files
stefanbuettnerStefan Buettner
authored andcommitted
Fix default alpha values for and ASCII writer for point clouds
This includes: - Save RGB as integer for all point types. - Change default alpha value to 255. - Adjust tests to new alpha values. - Print rgb values as ints in streaming operators.
1 parent 14d7e10 commit 7530b36

File tree

5 files changed

+96
-29
lines changed

5 files changed

+96
-29
lines changed

common/include/pcl/impl/point_types.hpp

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -339,7 +339,8 @@ namespace pcl
339339

340340
inline RGB ()
341341
{
342-
r = g = b = a = 0;
342+
r = g = b = 0;
343+
a = 255;
343344
}
344345

345346
friend std::ostream& operator << (std::ostream& os, const RGB& p);
@@ -614,7 +615,8 @@ namespace pcl
614615
{
615616
x = y = z = 0.0f;
616617
data[3] = 1.0f;
617-
r = g = b = a = 0;
618+
r = g = b = 0;
619+
a = 255;
618620
}
619621
inline PointXYZRGB (uint8_t _r, uint8_t _g, uint8_t _b)
620622
{
@@ -623,7 +625,7 @@ namespace pcl
623625
r = _r;
624626
g = _g;
625627
b = _b;
626-
a = 0;
628+
a = 255;
627629
}
628630

629631
friend std::ostream& operator << (std::ostream& os, const PointXYZRGB& p);
@@ -646,7 +648,7 @@ namespace pcl
646648
x = y = z = 0.0f;
647649
data[3] = 1.0f;
648650
r = g = b = 0;
649-
a = 0;
651+
a = 255;
650652
label = 255;
651653
}
652654
inline PointXYZRGBL (uint8_t _r, uint8_t _g, uint8_t _b, uint32_t _label)
@@ -656,7 +658,7 @@ namespace pcl
656658
r = _r;
657659
g = _g;
658660
b = _b;
659-
a = 0;
661+
a = 255;
660662
label = _label;
661663
}
662664

@@ -934,7 +936,8 @@ namespace pcl
934936
{
935937
x = y = z = 0.0f;
936938
data[3] = 1.0f;
937-
r = g = b = a = 0;
939+
r = g = b = 0;
940+
a = 255;
938941
normal_x = normal_y = normal_z = data_n[3] = 0.0f;
939942
curvature = 0;
940943
}
@@ -1587,7 +1590,8 @@ namespace pcl
15871590
x = y = z = 0.0f;
15881591
data[3] = 1.0f;
15891592
normal_x = normal_y = normal_z = data_n[3] = 0.0f;
1590-
rgba = 0;
1593+
r = g = b = 0;
1594+
a = 255;
15911595
radius = confidence = curvature = 0.0f;
15921596
}
15931597

common/src/point_types.cpp

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,11 @@ namespace pcl
115115
std::ostream&
116116
operator << (std::ostream& os, const PointXYZRGBL& p)
117117
{
118-
os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.r << "," << p.g << "," << p.b << " - " << p.label << ")";
118+
os << "(" << p.x << "," << p.y << "," << p.z << " - "
119+
<< static_cast<int>(p.r) << ","
120+
<< static_cast<int>(p.g) << ","
121+
<< static_cast<int>(p.b) << " - "
122+
<< p.label << ")";
119123
return (os);
120124
}
121125

@@ -178,7 +182,11 @@ namespace pcl
178182
std::ostream&
179183
operator << (std::ostream& os, const PointXYZRGBNormal& p)
180184
{
181-
os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.rgb << " - " << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << " - " << p.r << ", " << p.g << ", " << p.b << " - " << p.curvature << ")";
185+
os << "(" << p.x << "," << p.y << "," << p.z << " - "<< p.rgb << " - " << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << " - "
186+
<< static_cast<int>(p.r) << ", "
187+
<< static_cast<int>(p.g) << ", "
188+
<< static_cast<int>(p.b) << " - "
189+
<< p.curvature << ")";
182190
return (os);
183191
}
184192

@@ -408,14 +416,13 @@ namespace pcl
408416
std::ostream&
409417
operator << (std::ostream& os, const PointSurfel& p)
410418
{
411-
const unsigned char* rgba_ptr = reinterpret_cast<const unsigned char*>(&p.rgba);
412419
os <<
413420
"(" << p.x << "," << p.y << "," << p.z << " - " <<
414421
p.normal_x << "," << p.normal_y << "," << p.normal_z << " - "
415-
<< static_cast<int>(*rgba_ptr) << ","
416-
<< static_cast<int>(*(rgba_ptr+1)) << ","
417-
<< static_cast<int>(*(rgba_ptr+2)) << ","
418-
<< static_cast<int>(*(rgba_ptr+3)) << " - " <<
422+
<< static_cast<int>(p.r) << ","
423+
<< static_cast<int>(p.g) << ","
424+
<< static_cast<int>(p.b) << ","
425+
<< static_cast<int>(p.a) << " - " <<
419426
p.radius << " - " << p.confidence << " - " << p.curvature << ")";
420427
return (os);
421428
}

io/include/pcl/io/impl/pcd_io.hpp

Lines changed: 49 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,10 @@ pcl::PCDWriter::generateHeader (const pcl::PointCloud<PointT> &cloud, const int
9191
// Add the regular dimension
9292
field_names << " " << fields[i].name;
9393
field_sizes << " " << pcl::getFieldSize (fields[i].datatype);
94-
field_types << " " << pcl::getFieldType (fields[i].datatype);
94+
if ("rgb" == fields[i].name)
95+
field_types << " " << "U";
96+
else
97+
field_types << " " << pcl::getFieldType (fields[i].datatype);
9598
int count = abs (static_cast<int> (fields[i].count));
9699
if (count == 0) count = 1; // check for 0 counts (coming from older converter code)
97100
field_counts << " " << count;
@@ -576,12 +579,30 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<
576579
}
577580
case pcl::PCLPointField::FLOAT32:
578581
{
579-
float value;
580-
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (float), sizeof (float));
581-
if (pcl_isnan (value))
582-
stream << "nan";
582+
/*
583+
* Despite the float type, store the rgb field as uint32
584+
* because several fully opaque color values are mapped to
585+
* nan.
586+
*/
587+
if ("rgb" == fields[d].name)
588+
{
589+
uint32_t value;
590+
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (float), sizeof (float));
591+
if (pcl_isnan (value))
592+
stream << "nan";
593+
else
594+
stream << boost::numeric_cast<uint32_t>(value);
595+
break;
596+
}
583597
else
584-
stream << boost::numeric_cast<float>(value);
598+
{
599+
float value;
600+
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (float), sizeof (float));
601+
if (pcl_isnan (value))
602+
stream << "nan";
603+
else
604+
stream << boost::numeric_cast<float>(value);
605+
}
585606
break;
586607
}
587608
case pcl::PCLPointField::FLOAT64:
@@ -877,12 +898,29 @@ pcl::PCDWriter::writeASCII (const std::string &file_name,
877898
}
878899
case pcl::PCLPointField::FLOAT32:
879900
{
880-
float value;
881-
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (float), sizeof (float));
882-
if (pcl_isnan (value))
883-
stream << "nan";
901+
/*
902+
* Despite the float type, store the rgb field as uint32
903+
* because several fully opaque color values are mapped to
904+
* nan.
905+
*/
906+
if ("rgb" == fields[i].name)
907+
{
908+
uint32_t value;
909+
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (float), sizeof (float));
910+
if (pcl_isnan (value))
911+
stream << "nan";
912+
else
913+
stream << boost::numeric_cast<uint32_t>(value);
914+
}
884915
else
885-
stream << boost::numeric_cast<float>(value);
916+
{
917+
float value;
918+
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[indices[i]]) + fields[d].offset + c * sizeof (float), sizeof (float));
919+
if (pcl_isnan (value))
920+
stream << "nan";
921+
else
922+
stream << boost::numeric_cast<float>(value);
923+
}
886924
break;
887925
}
888926
case pcl::PCLPointField::FLOAT64:

io/src/pcd_io.cpp

Lines changed: 21 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1105,11 +1105,21 @@ pcl::PCDWriter::generateHeaderASCII (const pcl::PCLPointCloud2 &cloud,
11051105
{
11061106
// Ignore invalid padded dimensions that are inherited from binary data
11071107
if (cloud.fields[d].name != "_")
1108-
stream << pcl::getFieldType (cloud.fields[d].datatype) << " ";
1108+
{
1109+
if (cloud.fields[d].name == "rgb")
1110+
stream << "U ";
1111+
else
1112+
stream << pcl::getFieldType (cloud.fields[d].datatype) << " ";
1113+
}
11091114
}
11101115
// Ignore invalid padded dimensions that are inherited from binary data
11111116
if (cloud.fields[cloud.fields.size () - 1].name != "_")
1112-
stream << pcl::getFieldType (cloud.fields[cloud.fields.size () - 1].datatype);
1117+
{
1118+
if (cloud.fields[cloud.fields.size () - 1].name == "rgb")
1119+
stream << "U";
1120+
else
1121+
stream << pcl::getFieldType (cloud.fields[cloud.fields.size () - 1].datatype);
1122+
}
11131123

11141124
// Remove trailing spaces
11151125
result = stream.str ();
@@ -1370,7 +1380,15 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PCLPointClo
13701380
}
13711381
case pcl::PCLPointField::FLOAT32:
13721382
{
1373-
copyValueString<pcl::traits::asType<pcl::PCLPointField::FLOAT32>::type>(cloud, i, point_size, d, c, stream);
1383+
/*
1384+
* Despite the float type, store the rgb field as uint32
1385+
* because several fully opaque color values are mapped to
1386+
* nan.
1387+
*/
1388+
if ("rgb" == cloud.fields[d].name)
1389+
copyValueString<pcl::traits::asType<pcl::PCLPointField::UINT32>::type>(cloud, i, point_size, d, c, stream);
1390+
else
1391+
copyValueString<pcl::traits::asType<pcl::PCLPointField::FLOAT32>::type>(cloud, i, point_size, d, c, stream);
13741392
break;
13751393
}
13761394
case pcl::PCLPointField::FLOAT64:

test/common/test_common.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -413,7 +413,7 @@ TEST (PCL, CopyIfFieldExists)
413413
pcl::for_each_type<FieldList> (CopyIfFieldExists<PointXYZRGBNormal, float> (p, "rgb", is_rgb, rgb_val));
414414
EXPECT_EQ (is_rgb, true);
415415
int rgb = *reinterpret_cast<int*>(&rgb_val);
416-
EXPECT_EQ (rgb, 8339710); // alpha is 0
416+
EXPECT_EQ (rgb, 0xff7f40fe); // alpha is 255
417417
pcl::for_each_type<FieldList> (CopyIfFieldExists<PointXYZRGBNormal, float> (p, "normal_x", is_normal_x, normal_x_val));
418418
EXPECT_EQ (is_normal_x, true);
419419
EXPECT_EQ (normal_x_val, 1.0);

0 commit comments

Comments
 (0)