Skip to content

Commit d8b6a54

Browse files
arjo129iche033
andauthored
Reintroduce pointcloud render without Float_V message (#755)
🦟 Bug fix [This bug](#494 (comment)) ## Summary Re-introduce point cloud rendering without the Float_V message. <img width="1198" height="996" alt="Screenshot From 2026-03-17 11-49-46" src="https://github.com/user-attachments/assets/fe538b5b-d93a-429b-9900-3b13345dece1" /> I tested it with the following program: ```C++ #include <iostream> #include <cmath> #include <thread> #include <chrono> #include <gz/msgs/pointcloud_packed.pb.h> #include <gz/msgs/PointCloudPackedUtils.hh> #include <gz/transport/Node.hh> int main(int argc, char** argv) { // Create a transport node. gz::transport::Node node; // Define the topic to publish on. std::string topic = "/sphere_points"; // Create a publisher for PointCloudPacked messages. auto pub = node.Advertise<gz::msgs::PointCloudPacked>(topic); if (!pub) { std::cerr << "Error advertising topic [" << topic << "]" << std::endl; return -1; } // Sphere parameters double radius = 1.0; int num_theta = 20; int num_phi = 40; // Prepare the message gz::msgs::PointCloudPacked msg; // Initialize header msg.mutable_header()->mutable_stamp()->set_sec(0); msg.mutable_header()->mutable_stamp()->set_nsec(0); // Initialize PointCloudPacked gz::msgs::InitPointCloudPacked(msg, "frame_id", false, {{"xyz", gz::msgs::PointCloudPacked::Field::FLOAT32}}); int num_points = (num_theta + 1) * num_phi; msg.set_width(num_points); msg.set_height(1); msg.set_is_dense(true); msg.mutable_data()->resize(num_points * msg.point_step()); gz::msgs::PointCloudPackedIterator<float> iterX(msg, "x"); gz::msgs::PointCloudPackedIterator<float> iterY(msg, "y"); gz::msgs::PointCloudPackedIterator<float> iterZ(msg, "z"); const double PI = std::acos(-1.0); for (int i = 0; i <= num_theta; ++i) { double theta = PI * i / num_theta; for (int j = 0; j < num_phi; ++j) { double phi = 2.0 * PI * j / num_phi; double x = radius * std::sin(theta) * std::cos(phi); double y = radius * std::sin(theta) * std::sin(phi); double z = radius * std::cos(theta); *iterX = static_cast<float>(x); *iterY = static_cast<float>(y); *iterZ = static_cast<float>(z); ++iterX; ++iterY; ++iterZ; } } std::cout << "Publishing a sphere with " << num_points << " points on topic [" << topic << "]" << std::endl; // Publish the message in a loop while (true) { if (!pub.Publish(msg)) { std::cerr << "Failed to publish message" << std::endl; } std::this_thread::sleep_for(std::chrono::milliseconds(1000)); } return 0; } ``` TODO: Color support: I think we should not implement the color rendering support here, rather perhaps we should have some PointCloud representation in `gz-math`. For now there is rudimentary support for colors in this PR. --------- Signed-off-by: Arjo Chakravarty <arjoc@intrinsic.ai> Signed-off-by: Arjo Chakravarty <arjo129@gmail.com> Co-authored-by: Ian Chen <ichen@openrobotics.org> Co-authored-by: Ian Chen <iche@google.com>
1 parent 63203f5 commit d8b6a54

File tree

1 file changed

+109
-23
lines changed

1 file changed

+109
-23
lines changed

src/plugins/point_cloud/PointCloud.cc

Lines changed: 109 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
2121
#include "gz/msgs/pointcloud_packed.pb.h"
2222

2323
#include <algorithm>
24+
#include <cstdint>
25+
#include <gz/msgs/details/pointcloud_packed.pb.h>
2426
#include <gz/utils/ImplPtr.hh>
2527
#include <limits>
2628
#include <string>
@@ -96,6 +98,11 @@ class PointCloud::Implementation
9698

9799
/// \brief True if showing, changeable at runtime
98100
public: bool showing{true};
101+
102+
/// \brief Sometimes we may just want to have a pointcloud
103+
/// Without a float field. This is triggered when we
104+
/// set a scalar float topic to subscribe to.
105+
public: bool hasFloatTopic{false};
99106
};
100107

101108
/////////////////////////////////////////////////
@@ -182,6 +189,7 @@ void PointCloud::OnPointCloudTopic(const QString &_pointCloudTopic)
182189
void PointCloud::OnFloatVTopic(const QString &_floatVTopic)
183190
{
184191
std::lock_guard<std::recursive_mutex> lock(this->dataPtr->mutex);
192+
185193
// Unsubscribe from previous choice
186194
if (!this->dataPtr->floatVTopic.empty() &&
187195
!this->dataPtr->node.Unsubscribe(this->dataPtr->floatVTopic))
@@ -208,6 +216,7 @@ void PointCloud::OnFloatVTopic(const QString &_floatVTopic)
208216
return;
209217
}
210218
gzmsg << "Subscribed to " << this->dataPtr->floatVTopic << std::endl;
219+
this->dataPtr->hasFloatTopic = true;
211220
}
212221

213222
//////////////////////////////////////////////////
@@ -411,30 +420,107 @@ void PointCloud::Implementation::PublishMarkers()
411420
gzwarn << "Mal-formatted pointcloud" << std::endl;
412421
}
413422

414-
for (; ptIdx < std::min<int>(this->floatVMsg.data().size(), num_points);
415-
++iterX, ++iterY, ++iterZ, ++ptIdx)
423+
if (this->hasFloatTopic)
424+
{
425+
for (; ptIdx < std::min<int>(this->floatVMsg.data().size(), num_points);
426+
++iterX, ++iterY, ++iterZ, ++ptIdx)
427+
{
428+
// Value from float vector, if available. Otherwise publish all data as
429+
// zeroes.
430+
float dataVal = this->floatVMsg.data(ptIdx);
431+
432+
// Don't visualize NaN
433+
if (std::isnan(dataVal))
434+
continue;
435+
436+
auto ratio = floatRange > 0 ?
437+
(dataVal - this->minFloatV) / floatRange : 0.0f;
438+
gz:: math::Color color{
439+
minC.R() + (maxC.R() - minC.R()) * ratio,
440+
minC.G() + (maxC.G() - minC.G()) * ratio,
441+
minC.B() + (maxC.B() - minC.B()) * ratio
442+
};
443+
444+
gz::msgs::Set(marker.add_materials()->mutable_diffuse(), color);
445+
gz::msgs::Set(marker.add_point(), gz::math::Vector3d(
446+
*iterX,
447+
*iterY,
448+
*iterZ));
449+
}
450+
}
451+
else
416452
{
417-
// Value from float vector, if available. Otherwise publish all data as
418-
// zeroes.
419-
float dataVal = this->floatVMsg.data(ptIdx);
420-
421-
// Don't visualize NaN
422-
if (std::isnan(dataVal))
423-
continue;
424-
425-
auto ratio = floatRange > 0 ?
426-
(dataVal - this->minFloatV) / floatRange : 0.0f;
427-
gz:: math::Color color{
428-
minC.R() + (maxC.R() - minC.R()) * ratio,
429-
minC.G() + (maxC.G() - minC.G()) * ratio,
430-
minC.B() + (maxC.B() - minC.B()) * ratio
431-
};
432-
433-
gz::msgs::Set(marker.add_materials()->mutable_diffuse(), color);
434-
gz::msgs::Set(marker.add_point(), gz::math::Vector3d(
435-
*iterX,
436-
*iterY,
437-
*iterZ));
453+
// Fall back to coloring using the point cloud (if possible)
454+
// Else fall back to a default color
455+
std::string r_detected, g_detected, b_detected;
456+
for (auto field : this->pointCloudMsg.field())
457+
{
458+
if (field.name() == "r" || field.name() == "red")
459+
{
460+
if (field.datatype() != msgs::PointCloudPacked::Field::UINT8)
461+
{
462+
gzwarn << "Only 256 bit color supported" << std::endl;
463+
continue;
464+
}
465+
r_detected = field.name();
466+
}
467+
468+
if (field.name() == "g" || field.name() == "green")
469+
{
470+
if (field.datatype() != msgs::PointCloudPacked::Field::UINT8)
471+
{
472+
gzwarn << "Only 256 bit color supported" << std::endl;
473+
continue;
474+
}
475+
g_detected = field.name();
476+
}
477+
478+
if (field.name() == "b" || field.name() == "blue")
479+
{
480+
if (field.datatype() != msgs::PointCloudPacked::Field::UINT8)
481+
{
482+
gzwarn << "Only 256 bit color supported" << std::endl;
483+
continue;
484+
}
485+
b_detected = field.name();
486+
}
487+
}
488+
489+
if (r_detected.empty() || g_detected.empty() || b_detected.empty())
490+
{
491+
gzerr << "Using default color" << std::endl;
492+
// Color fields unavailable just set the color based on our max color
493+
for (std::size_t i = 0; i < num_points; ++iterX, ++iterY, ++iterZ, ++i)
494+
{
495+
gz::msgs::Set(marker.add_materials()->mutable_diffuse(), minC);
496+
gz::msgs::Set(marker.add_point(), gz::math::Vector3d(
497+
*iterX,
498+
*iterY,
499+
*iterZ));
500+
}
501+
}
502+
else
503+
{
504+
gz::msgs::PointCloudPackedIterator<uint8_t>
505+
iterR(this->pointCloudMsg, r_detected);
506+
gz::msgs::PointCloudPackedIterator<uint8_t>
507+
iterG(this->pointCloudMsg, g_detected);
508+
gz::msgs::PointCloudPackedIterator<uint8_t>
509+
iterB(this->pointCloudMsg, b_detected);
510+
for (std::size_t i = 0; i < num_points;
511+
++iterX, ++iterY, ++iterZ, ++i, ++iterR, ++iterG, ++iterB)
512+
{
513+
gz::msgs::Set(marker.add_materials()->mutable_diffuse(), math::Color(
514+
static_cast<float>(*iterR)/255.0,
515+
static_cast<float>(*iterG)/255.0,
516+
static_cast<float>(*iterB)/255.0
517+
));
518+
gz::msgs::Set(marker.add_point(), gz::math::Vector3d(
519+
*iterX,
520+
*iterY,
521+
*iterZ));
522+
}
523+
}
438524
}
439525

440526
this->node.Request("/marker", marker);

0 commit comments

Comments
 (0)