Skip to content

Commit 8f3b7e3

Browse files
Feature/refactor delta (#50)
* fix trait usage in mesh adapter * fix object visualizer * fix frontend delta publishing * fix missing includes from forward declares * add active bounding boxes for objects to rviz
1 parent f95e3c7 commit 8f3b7e3

6 files changed

Lines changed: 106 additions & 49 deletions

File tree

hydra_ros/include/hydra_ros/frontend/object_visualizer.h

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -34,8 +34,8 @@
3434
* -------------------------------------------------------------------------- */
3535
#pragma once
3636
#include <hydra/frontend/mesh_segmenter.h>
37+
#include <hydra_visualizer/color/colormap_utilities.h>
3738
#include <ianvs/lazy_publisher_group.h>
38-
#include <kimera_pgmo/mesh_delta.h>
3939

4040
#include <visualization_msgs/msg/marker.hpp>
4141

@@ -48,6 +48,8 @@ class ObjectVisualizer : public MeshSegmenter::Sink {
4848
double point_scale = 0.1;
4949
double point_alpha = 0.7;
5050
bool use_spheres = false;
51+
double bounding_box_scale = 0.1;
52+
visualizer::CategoricalColormap::Config colormap;
5153
} const config;
5254

5355
explicit ObjectVisualizer(const Config& config);
@@ -58,8 +60,8 @@ class ObjectVisualizer : public MeshSegmenter::Sink {
5860

5961
void call(uint64_t timestamp_ns,
6062
const kimera_pgmo::MeshDelta& delta,
61-
const std::vector<size_t>& active,
62-
const LabelIndices& label_indices) const override;
63+
const LabelIndices& label_indices,
64+
const MeshSegmenter::LabelClusters& clusters) const override;
6365

6466
protected:
6567
void fillMarkerFromCloud(const kimera_pgmo::MeshDelta& delta,
@@ -70,10 +72,7 @@ class ObjectVisualizer : public MeshSegmenter::Sink {
7072
ianvs::NodeHandle nh_;
7173
ianvs::RosPublisherGroup<visualization_msgs::msg::Marker> pubs_;
7274

73-
private:
74-
inline static const auto registration_ =
75-
config::RegistrationWithConfig<MeshSegmenter::Sink, ObjectVisualizer, Config>(
76-
"ObjectVisualizer");
75+
const visualizer::CategoricalColormap colormap_;
7776
};
7877

7978
void declare_config(ObjectVisualizer::Config& conf);

hydra_ros/include/hydra_ros/frontend/ros_frontend_publisher.h

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -34,12 +34,11 @@
3434
* -------------------------------------------------------------------------- */
3535
#pragma once
3636
#include <hydra/frontend/graph_builder.h>
37-
#include <kimera_pgmo_ros/conversion/mesh_delta.h>
3837
#include <pose_graph_tools_ros/conversions.h>
3938

4039
#include <map>
41-
#include <queue>
4240

41+
#include <kimera_pgmo_msgs/msg/mesh_delta.hpp>
4342
#include <kimera_pgmo_msgs/srv/mesh_delta_query.hpp>
4443

4544
#include "hydra_ros/utils/dsg_streaming_interface.h"
@@ -49,6 +48,9 @@ namespace hydra {
4948
class RosFrontendPublisher : public GraphBuilder::Sink {
5049
public:
5150
using MeshDeltaSrv = kimera_pgmo_msgs::srv::MeshDeltaQuery;
51+
using MeshDeltaRequest = kimera_pgmo_msgs::srv::MeshDeltaQuery::Request::SharedPtr;
52+
using MeshDeltaResponse = kimera_pgmo_msgs::srv::MeshDeltaQuery::Response::SharedPtr;
53+
using MeshDeltaMsg = kimera_pgmo_msgs::msg::MeshDelta;
5254

5355
struct Config {
5456
//! @brief Configuration for dsg publisher
@@ -65,16 +67,14 @@ class RosFrontendPublisher : public GraphBuilder::Sink {
6567
std::string printInfo() const override { return "RosFrontendPublisher"; }
6668

6769
protected:
68-
void processMeshDeltaQuery(const MeshDeltaSrv::Request::SharedPtr req,
69-
MeshDeltaSrv::Response::SharedPtr resp);
70+
void processMeshDeltaQuery(const MeshDeltaRequest req, MeshDeltaResponse resp);
7071

7172
std::unique_ptr<DsgSender> dsg_sender_;
72-
mutable std::map<uint16_t, kimera_pgmo::MeshDelta::Ptr> stored_delta_;
73-
7473
pose_graph_tools::PoseGraphPublisher mesh_graph_pub_;
75-
kimera_pgmo::PgmoMeshDeltaPublisher mesh_update_pub_;
74+
rclcpp::Publisher<MeshDeltaMsg>::SharedPtr mesh_update_pub_;
7675
rclcpp::Service<MeshDeltaSrv>::SharedPtr mesh_delta_server_;
77-
rclcpp::TypeAdapter<kimera_pgmo::MeshDelta, kimera_pgmo_msgs::msg::MeshDelta>
78-
mesh_delta_converter_;
76+
77+
mutable std::map<uint16_t, MeshDeltaMsg::SharedPtr> stored_delta_;
7978
};
79+
8080
} // namespace hydra

hydra_ros/launch/datasets/uhumans2.launch.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,3 +38,8 @@ launch:
3838
- {name: map_frame, value: map}
3939
- {name: lcd_config_path, value: $(find-pkg-share hydra)/config/lcd/uhumans2.yaml}
4040
- {name: extra_yaml, value: $(if $(var use_gt_semantics) $(var extra_yaml_gt) $(var extra_yaml_no_gt))}
41+
- node:
42+
pkg: tf2_ros
43+
name: world_to_map
44+
exec: static_transform_publisher
45+
args: --frame-id world --child-frame-id map

hydra_ros/src/frontend/object_visualizer.cpp

Lines changed: 60 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,18 @@
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

4244
namespace hydra {
45+
namespace {
46+
47+
static const auto registration =
48+
config::RegistrationWithConfig<MeshSegmenter::Sink,
49+
ObjectVisualizer,
50+
ObjectVisualizer::Config>("ObjectVisualizer");
51+
52+
}
4353

4454
using 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

5567
ObjectVisualizer::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

6073
std::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+
6289
void 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

90140
void 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
}

hydra_ros/src/frontend/ros_frontend_publisher.cpp

Lines changed: 23 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,11 @@
3939
#include <config_utilities/printing.h>
4040
#include <config_utilities/validation.h>
4141
#include <hydra/common/global_info.h>
42+
#include <kimera_pgmo/mesh_delta.h>
43+
#include <kimera_pgmo_ros/conversion/mesh_delta.h>
4244

4345
namespace hydra {
4446

45-
using kimera_pgmo::MeshDeltaTypeAdapter;
4647
using pose_graph_tools::PoseGraphTypeAdapter;
4748
using BaseInterface = rclcpp::node_interfaces::NodeBaseInterface;
4849
using rclcpp::CallbackGroupType;
@@ -66,7 +67,8 @@ void declare_config(RosFrontendPublisher::Config& config) {
6667
}
6768

6869
RosFrontendPublisher::RosFrontendPublisher(ianvs::NodeHandle nh)
69-
: config(config::checkValid(get_config())) {
70+
: config(config::checkValid(get_config())),
71+
dsg_sender_(new DsgSender(config.dsg_sender, nh)) {
7072
auto group = nh.as<BaseInterface>()->create_callback_group(
7173
CallbackGroupType::MutuallyExclusive);
7274
mesh_delta_server_ =
@@ -75,46 +77,48 @@ RosFrontendPublisher::RosFrontendPublisher(ianvs::NodeHandle nh)
7577
this,
7678
rclcpp::ServicesQoS(),
7779
group);
78-
dsg_sender_ = std::make_unique<DsgSender>(config.dsg_sender, nh);
79-
mesh_graph_pub_ = nh.create_publisher<PoseGraphTypeAdapter>(
80-
"mesh_graph_incremental", rclcpp::QoS(100).transient_local());
81-
mesh_update_pub_ = nh.create_publisher<MeshDeltaTypeAdapter>(
82-
"full_mesh_update", rclcpp::QoS(100).transient_local());
80+
81+
const auto qos = rclcpp::QoS(100).transient_local();
82+
mesh_graph_pub_ =
83+
nh.create_publisher<PoseGraphTypeAdapter>("mesh_graph_incremental", qos);
84+
mesh_update_pub_ = nh.create_publisher<MeshDeltaMsg>("full_mesh_update", qos);
8385
}
8486

8587
void RosFrontendPublisher::call(uint64_t timestamp_ns,
8688
const DynamicSceneGraph& graph,
8789
const BackendInput& backend_input) const {
8890
// TODO(nathan) make sure pgmo stamps the deformation graph
8991
mesh_graph_pub_->publish(backend_input.deformation_graph);
92+
9093
if (backend_input.mesh_update) {
9194
backend_input.mesh_update->timestamp_ns = timestamp_ns;
92-
mesh_update_pub_->publish(*backend_input.mesh_update);
93-
stored_delta_.insert(
94-
{backend_input.mesh_update->sequence_number, backend_input.mesh_update});
95-
if (config.mesh_delta_queue_size > 0 &&
96-
stored_delta_.size() > static_cast<size_t>(config.mesh_delta_queue_size)) {
95+
auto delta_msg = std::make_shared<MeshDeltaMsg>();
96+
kimera_pgmo::conversions::to_ros(*backend_input.mesh_update, *delta_msg);
97+
mesh_update_pub_->publish(*delta_msg);
98+
99+
stored_delta_.insert({backend_input.mesh_update->info.sequence_number, delta_msg});
100+
if (config.mesh_delta_queue_size &&
101+
stored_delta_.size() > config.mesh_delta_queue_size) {
97102
stored_delta_.erase(stored_delta_.begin());
98103
}
99104
}
100105

101106
dsg_sender_->sendGraph(graph, rclcpp::Time(timestamp_ns));
102107
}
103108

104-
void RosFrontendPublisher::processMeshDeltaQuery(
105-
const MeshDeltaSrv::Request::SharedPtr req,
106-
MeshDeltaSrv::Response::SharedPtr resp) {
107-
LOG(INFO) << "Received request for " << req->sequence_numbers.size()
108-
<< " mesh deltas...";
109+
void RosFrontendPublisher::processMeshDeltaQuery(const MeshDeltaRequest req,
110+
MeshDeltaResponse resp) {
111+
LOG(INFO) << "Received request for " << req->sequence_numbers.size() << " deltas...";
109112
for (const auto& seq : req->sequence_numbers) {
110113
auto& msg = resp->deltas.emplace_back();
111-
// Check TypeAdater documentation TODO(Yun)
112114
if (!stored_delta_.count(seq)) {
113115
LOG(ERROR) << "Mesh delta sequence " << seq << " not found";
114116
continue;
115117
}
116-
mesh_delta_converter_.convert_to_ros_message(*stored_delta_.at(seq), msg);
118+
119+
msg = *stored_delta_.at(seq);
117120
}
121+
118122
LOG(INFO) << "Responding with " << resp->deltas.size() << " deltas...";
119123
}
120124

hydra_visualizer/src/drawing.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -648,12 +648,11 @@ kimera_pgmo_msgs::msg::Mesh makeMeshMsg(const std_msgs::msg::Header& header,
648648

649649
MeshColorAdapter adapter(mesh, coloring);
650650
msg.vertices.resize(mesh.points.size());
651-
msg.vertex_colors.resize(mesh.points.size());
652651
for (size_t i = 0; i < mesh.points.size(); ++i) {
653652
auto& vertex = msg.vertices[i];
654-
tf2::convert(mesh.points[i].cast<double>().eval(), vertex);
655-
auto& color = msg.vertex_colors[i];
656-
color = visualizer::makeColorMsg(adapter.getVertexColor(i));
653+
tf2::convert(mesh.points[i].cast<double>().eval(), vertex.pos);
654+
vertex.has_color = true;
655+
vertex.color = visualizer::makeColorMsg(adapter.getVertexColor(i));
657656
}
658657

659658
msg.triangles.resize(mesh.faces.size());

0 commit comments

Comments
 (0)