3838#include < config_utilities/printing.h>
3939#include < config_utilities/validation.h>
4040#include < hydra/common/global_info.h>
41+ #include < hydra_visualizer/drawing.h>
42+ #include < kimera_pgmo/mesh_delta.h>
4143
4244namespace hydra {
45+ namespace {
46+
47+ static const auto registration =
48+ config::RegistrationWithConfig<MeshSegmenter::Sink,
49+ ObjectVisualizer,
50+ ObjectVisualizer::Config>(" ObjectVisualizer" );
51+
52+ }
4353
4454using visualization_msgs::msg::Marker;
4555
@@ -50,25 +60,44 @@ void declare_config(ObjectVisualizer::Config& config) {
5060 field (config.point_scale , " point_scale" );
5161 field (config.point_alpha , " point_alpha" );
5262 field (config.use_spheres , " use_spheres" );
63+ field (config.bounding_box_scale , " bounding_box_scale" );
64+ field (config.colormap , " colormap" );
5365}
5466
5567ObjectVisualizer::ObjectVisualizer (const Config& config)
5668 : config(config::checkValid(config)),
5769 nh_ (ianvs::NodeHandle::this_node(config.module_ns)),
58- pubs_(nh_) {}
70+ pubs_(nh_),
71+ colormap_(config.colormap) {}
5972
6073std::string ObjectVisualizer::printInfo () const { return config::toString (config); }
6174
75+ struct DeltaPointAdaptor : spark_dsg::BoundingBox::PointAdaptor {
76+ DeltaPointAdaptor (const kimera_pgmo::MeshDelta& delta,
77+ const std::vector<size_t >& indices)
78+ : delta(delta), indices(indices) {}
79+
80+ size_t size () const override { return indices.size (); }
81+
82+ Eigen::Vector3f get (size_t index) const override {
83+ return delta.getVertex (indices.at (index)).pos ;
84+ }
85+ const kimera_pgmo::MeshDelta& delta;
86+ const std::vector<size_t >& indices;
87+ };
88+
6289void ObjectVisualizer::call (uint64_t timestamp_ns,
6390 const kimera_pgmo::MeshDelta& delta,
64- const std::vector< size_t >& active ,
65- const LabelIndices& label_indices ) const {
91+ const LabelIndices& label_indices ,
92+ const MeshSegmenter::LabelClusters& clusters ) const {
6693 pubs_.publish (" active_vertices" , [&]() {
6794 auto msg = std::make_unique<Marker>();
6895 msg->header .stamp = rclcpp::Time (timestamp_ns);
6996 msg->header .frame_id = GlobalInfo::instance ().getFrames ().odom ;
7097 msg->ns = " active_vertices" ;
7198 msg->id = 0 ;
99+ std::vector<size_t > active (delta.getNumActiveVertices ());
100+ std::iota (active.begin (), active.end (), delta.getNumArchivedVertices ());
72101 fillMarkerFromCloud (delta, active, *msg);
73102 return msg;
74103 });
@@ -85,6 +114,27 @@ void ObjectVisualizer::call(uint64_t timestamp_ns,
85114 return msg;
86115 });
87116 }
117+
118+ pubs_.publish (" object_clusters" , [&]() {
119+ auto msg = std::make_unique<Marker>();
120+ msg->header .stamp = rclcpp::Time (timestamp_ns);
121+ msg->header .frame_id = GlobalInfo::instance ().getFrames ().odom ;
122+ msg->type = Marker::LINE_LIST;
123+ msg->action = Marker::ADD;
124+ msg->ns = " object_clusters" ;
125+ msg->id = 0 ;
126+ msg->scale .x = config.bounding_box_scale ;
127+ for (const auto & [label, label_clusters] : clusters) {
128+ const auto color = visualizer::makeColorMsg (colormap_ (label));
129+ for (const auto & cluster : label_clusters) {
130+ const DeltaPointAdaptor adaptor (delta, cluster.indices );
131+ const spark_dsg::BoundingBox bbox (adaptor);
132+ visualizer::drawBoundingBox (bbox, color, *msg);
133+ }
134+ }
135+
136+ return msg;
137+ });
88138}
89139
90140void ObjectVisualizer::fillMarkerFromCloud (const kimera_pgmo::MeshDelta& delta,
@@ -101,15 +151,15 @@ void ObjectVisualizer::fillMarkerFromCloud(const kimera_pgmo::MeshDelta& delta,
101151 msg.points .reserve (indices.size ());
102152 msg.colors .reserve (indices.size ());
103153 for (const auto idx : indices) {
104- const auto & p = delta.vertex_updates -> at (idx);
154+ const auto & p = delta.getVertex (idx);
105155 auto & point = msg.points .emplace_back ();
106- point.x = p.x ;
107- point.y = p.y ;
108- point.z = p.z ;
156+ point.x = p.pos . x () ;
157+ point.y = p.pos . y () ;
158+ point.z = p.pos . z () ;
109159 auto & color = msg.colors .emplace_back ();
110- color.r = p.r / 255 .0f ;
111- color.g = p.g / 255 .0f ;
112- color.b = p.b / 255 .0f ;
160+ color.r = p.traits . color [ 0 ] / 255 .0f ;
161+ color.g = p.traits . color [ 1 ] / 255 .0f ;
162+ color.b = p.traits . color [ 2 ] / 255 .0f ;
113163 color.a = config.point_alpha ;
114164 }
115165}
0 commit comments