Skip to content

Commit af4414a

Browse files
committed
astro place subscriber
1 parent d0c155f commit af4414a

File tree

7 files changed

+260
-46
lines changed

7 files changed

+260
-46
lines changed

hydra_ros/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@ add_library(
4949
src/input/ros_data_receiver.cpp
5050
src/input/ros_input_module.cpp
5151
src/input/ros_sensors.cpp
52+
src/places/astro_traversability_estimator.cpp
5253
src/odometry/ros_pose_graph_tracker.cpp
5354
src/openset/ros_embedding_group.cpp
5455
src/utils/bow_subscriber.cpp
Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,80 @@
1+
/* -----------------------------------------------------------------------------
2+
* Copyright 2022 Massachusetts Institute of Technology.
3+
* All Rights Reserved
4+
*
5+
* Redistribution and use in source and binary forms, with or without
6+
* modification, are permitted provided that the following conditions are met:
7+
*
8+
* 1. Redistributions of source code must retain the above copyright notice,
9+
* this list of conditions and the following disclaimer.
10+
*
11+
* 2. Redistributions in binary form must reproduce the above copyright notice,
12+
* this list of conditions and the following disclaimer in the documentation
13+
* and/or other materials provided with the distribution.
14+
*
15+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
16+
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17+
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
19+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
20+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
21+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
22+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
23+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
24+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25+
*
26+
* Research was sponsored by the United States Air Force Research Laboratory and
27+
* the United States Air Force Artificial Intelligence Accelerator and was
28+
* accomplished under Cooperative Agreement Number FA8750-19-2-1000. The views
29+
* and conclusions contained in this document are those of the authors and should
30+
* not be interpreted as representing the official policies, either expressed or
31+
* implied, of the United States Air Force or the U.S. Government. The U.S.
32+
* Government is authorized to reproduce and distribute reprints for Government
33+
* purposes notwithstanding any copyright notation herein.
34+
* -------------------------------------------------------------------------- */
35+
#pragma once
36+
37+
#include <hydra/places/traversability_estimator.h>
38+
39+
#include <mutex>
40+
41+
#include <nav_msgs/msg/occupancy_grid.hpp>
42+
#include <rclcpp/rclcpp.hpp>
43+
44+
namespace hydra::places {
45+
46+
/**
47+
* @brief Takes in an external traversability map from astro.
48+
*/
49+
class AstroTraversabilityEstimator : public TraversabilityEstimator {
50+
public:
51+
struct Config {
52+
//! @brief The height above the robot body to consider for traversability in meters.
53+
std::string input_topic = "/local_cost_map";
54+
unsigned int queue_size = 1;
55+
} const config;
56+
57+
using State = spark_dsg::TraversabilityState;
58+
59+
AstroTraversabilityEstimator(const Config& config);
60+
~AstroTraversabilityEstimator() override = default;
61+
62+
void updateTraversability(const ActiveWindowOutput& msg,
63+
const kimera_pgmo::MeshDelta& /* mesh_delta */,
64+
const spark_dsg::DynamicSceneGraph& /* graph */) override;
65+
66+
void callback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
67+
68+
const TraversabilityLayer& getTraversabilityLayer() const override;
69+
70+
protected:
71+
rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr sub_;
72+
mutable std::mutex mutex_;
73+
74+
protected:
75+
State occupancyToTraversability(int8_t occupancy) const;
76+
};
77+
78+
void declare_config(AstroTraversabilityEstimator::Config& config);
79+
80+
} // namespace hydra::places
Lines changed: 151 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,151 @@
1+
/* -----------------------------------------------------------------------------
2+
* Copyright 2022 Massachusetts Institute of Technology.
3+
* All Rights Reserved
4+
*
5+
* Redistribution and use in source and binary forms, with or without
6+
* modification, are permitted provided that the following conditions are met:
7+
*
8+
* 1. Redistributions of source code must retain the above copyright notice,
9+
* this list of conditions and the following disclaimer.
10+
*
11+
* 2. Redistributions in binary form must reproduce the above copyright notice,
12+
* this list of conditions and the following disclaimer in the documentation
13+
* and/or other materials provided with the distribution.
14+
*
15+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
16+
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17+
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
19+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
20+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
21+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
22+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
23+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
24+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25+
*
26+
* Research was sponsored by the United States Air Force Research Laboratory and
27+
* the United States Air Force Artificial Intelligence Accelerator and was
28+
* accomplished under Cooperative Agreement Number FA8750-19-2-1000. The views
29+
* and conclusions contained in this document are those of the authors and should
30+
* not be interpreted as representing the official policies, either expressed or
31+
* implied, of the United States Air Force or the U.S. Government. The U.S.
32+
* Government is authorized to reproduce and distribute reprints for Government
33+
* purposes notwithstanding any copyright notation herein.
34+
* -------------------------------------------------------------------------- */
35+
#include "hydra_ros/places/astro_traversability_estimator.h"
36+
37+
#include <config_utilities/config.h>
38+
#include <config_utilities/validation.h>
39+
#include <ianvs/node_handle.h>
40+
#include <spark_dsg/traversability_boundary.h>
41+
42+
namespace hydra::places {
43+
44+
using spark_dsg::TraversabilityState;
45+
46+
static const auto registration =
47+
config::RegistrationWithConfig<TraversabilityEstimator,
48+
AstroTraversabilityEstimator,
49+
AstroTraversabilityEstimator::Config>(
50+
"AstroTraversabilityEstimator");
51+
52+
void declare_config(AstroTraversabilityEstimator::Config& config) {
53+
using namespace config;
54+
name("AstroTraversabilityEstimator::Config");
55+
field(config.input_topic, "input_topic");
56+
field(config.queue_size, "queue_size");
57+
checkCondition(!config.input_topic.empty(), "'input_topic' must be specified");
58+
}
59+
60+
AstroTraversabilityEstimator::AstroTraversabilityEstimator(const Config& config)
61+
: config(config::checkValid(config)) {
62+
auto nh = ianvs::NodeHandle::this_node();
63+
sub_ = nh.create_subscription<nav_msgs::msg::OccupancyGrid>(
64+
config.input_topic,
65+
config.queue_size,
66+
&AstroTraversabilityEstimator::callback,
67+
this);
68+
}
69+
70+
const TraversabilityLayer& AstroTraversabilityEstimator::getTraversabilityLayer()
71+
const {
72+
std::lock_guard<std::mutex> lock(mutex_);
73+
return *traversability_layer_;
74+
}
75+
76+
void AstroTraversabilityEstimator::updateTraversability(
77+
const ActiveWindowOutput& msg,
78+
const kimera_pgmo::MeshDelta&,
79+
const spark_dsg::DynamicSceneGraph&) {
80+
if (!traversability_layer_) {
81+
const auto& map_config = msg.map().config;
82+
traversability_layer_ = std::make_unique<TraversabilityLayer>(
83+
map_config.voxel_size, map_config.voxels_per_side);
84+
}
85+
}
86+
87+
void AstroTraversabilityEstimator::callback(
88+
const nav_msgs::msg::OccupancyGrid::SharedPtr msg) {
89+
if (!traversability_layer_) {
90+
return;
91+
}
92+
// Reset update tracking.
93+
std::lock_guard<std::mutex> lock(mutex_);
94+
for (auto& block : *traversability_layer_) {
95+
block.updated = false;
96+
for (auto& voxel : block.voxels) {
97+
voxel.confidence = 0.0f;
98+
}
99+
}
100+
101+
// Updated the stored layer with the map.
102+
const float voxel_size = msg->info.resolution;
103+
const Eigen::Vector3f origin(
104+
msg->info.origin.position.x, msg->info.origin.position.y, 0.0f);
105+
for (unsigned int y = 0; y < msg->info.height; ++y) {
106+
for (unsigned int x = 0; x < msg->info.width; ++x) {
107+
const int idx = x + y * msg->info.width;
108+
const State state = occupancyToTraversability(msg->data[idx]);
109+
// Compute the voxel coordinates.
110+
const Eigen::Vector3f position =
111+
Eigen::Vector3f(x + 0.5f, y + 0.5f, 0.0f) * voxel_size + origin;
112+
const auto index = traversability_layer_->globalIndexFromPoint(position);
113+
// TODO(lschmid): Fix the allocate block interfaces for the traversability layer.
114+
auto& block = traversability_layer_->allocateBlock(
115+
traversability_layer_->blockIndexFromGlobal(index),
116+
traversability_layer_->voxels_per_side);
117+
block.updated = true;
118+
auto& voxel = block.voxel(traversability_layer_->voxelIndexFromGlobal(index));
119+
if (voxel.confidence == 0.0f) {
120+
// Overwrite if this is the first observation this iteration.
121+
voxel.state = state;
122+
voxel.confidence = 1.0f;
123+
} else {
124+
spark_dsg::fuseStates(state, voxel.state);
125+
voxel.confidence += 1.0f;
126+
}
127+
}
128+
}
129+
130+
// Remove blocks that were not updated.
131+
spatial_hash::BlockIndices to_remove;
132+
for (auto& block : *traversability_layer_) {
133+
if (!block.updated) {
134+
to_remove.push_back(block.index);
135+
}
136+
}
137+
traversability_layer_->removeBlocks(to_remove);
138+
}
139+
140+
AstroTraversabilityEstimator::State
141+
AstroTraversabilityEstimator::occupancyToTraversability(int8_t occupancy) const {
142+
if (occupancy < 0) {
143+
return State::UNKNOWN;
144+
}
145+
if (occupancy == 0) {
146+
return State::TRAVERSABLE;
147+
}
148+
return State::INTRAVERSABLE;
149+
}
150+
151+
} // namespace hydra::places

hydra_visualizer/include/hydra_visualizer/plugins/khronos_object_plugin.h

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,7 @@
7373

7474
#pragma once
7575

76+
#include <config_utilities/dynamic_config.h>
7677
#include <ianvs/node_handle.h>
7778
#include <spark_dsg/color.h>
7879
#include <spark_dsg/node_attributes.h>
@@ -122,7 +123,7 @@ class KhronosObjectPlugin : public VisualizerPlugin {
122123

123124
//! Layer to draw objects for
124125
std::string layer = spark_dsg::DsgLayers::OBJECTS;
125-
} const config;
126+
};
126127

127128
// Construction.
128129
KhronosObjectPlugin(const Config& config,
@@ -136,9 +137,11 @@ class KhronosObjectPlugin : public VisualizerPlugin {
136137

137138
protected:
138139
// Helper functions.
139-
void drawDynamicObjects(const std_msgs::msg::Header& header,
140+
void drawDynamicObjects(const Config& config,
141+
const std_msgs::msg::Header& header,
140142
const spark_dsg::DynamicSceneGraph& graph);
141-
void drawStaticObjects(const std_msgs::msg::Header& header,
143+
void drawStaticObjects(const Config& config,
144+
const std_msgs::msg::Header& header,
142145
const spark_dsg::DynamicSceneGraph& graph);
143146

144147
// Mesh namespace for the visualizer plugin.
@@ -153,13 +156,15 @@ class KhronosObjectPlugin : public VisualizerPlugin {
153156
const uint64_t id);
154157

155158
// Get the color of a dynamic object.
156-
spark_dsg::Color getDynamicColor(const spark_dsg::KhronosObjectAttributes& attrs,
159+
spark_dsg::Color getDynamicColor(const Config& config,
160+
const spark_dsg::KhronosObjectAttributes& attrs,
157161
const uint64_t id) const;
158162

159163
// Clear static object visuliazation
160164
void resetObject(const std_msgs::msg::Header& header, const uint64_t id);
161165

162166
private:
167+
const config::DynamicConfig<Config> config_;
163168
// ROS.
164169
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr dynamic_pub_;
165170
rclcpp::Publisher<kimera_pgmo_msgs::msg::Mesh>::SharedPtr static_pub_;

hydra_visualizer/include/hydra_visualizer/plugins/mesh_plugin.h

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -33,13 +33,12 @@
3333
* purposes notwithstanding any copyright notation herein.
3434
* -------------------------------------------------------------------------- */
3535
#pragma once
36+
#include <config_utilities/dynamic_config.h>
3637
#include <config_utilities/virtual_config.h>
3738
#include <ianvs/node_handle.h>
3839

3940
#include <kimera_pgmo_msgs/msg/mesh.hpp>
4041
#include <rclcpp/publisher.hpp>
41-
#include <rclcpp/service.hpp>
42-
#include <std_srvs/srv/set_bool.hpp>
4342

4443
#include "hydra_visualizer/adapters/mesh_color.h"
4544
#include "hydra_visualizer/plugins/visualizer_plugin.h"
@@ -52,9 +51,8 @@ class MeshPlugin : public VisualizerPlugin {
5251
using LabelsPtr = std::shared_ptr<Labels>;
5352

5453
struct Config {
55-
bool use_color_adapter = false;
56-
config::VirtualConfig<MeshColoring> coloring{SemanticMeshColoring::Config()};
57-
} const config;
54+
config::VirtualConfig<MeshColoring, true> coloring;
55+
};
5856

5957
MeshPlugin(const Config& config, ianvs::NodeHandle nh, const std::string& name);
6058

@@ -66,15 +64,11 @@ class MeshPlugin : public VisualizerPlugin {
6664
void reset(const std_msgs::msg::Header& header) override;
6765

6866
protected:
69-
void handleService(const std_srvs::srv::SetBool::Request::SharedPtr& req,
70-
std_srvs::srv::SetBool::Response::SharedPtr res);
67+
config::DynamicConfig<Config> config_;
7168

7269
std::string getMsgNamespace() const;
7370

74-
bool use_color_adapter_;
7571
rclcpp::Publisher<kimera_pgmo_msgs::msg::Mesh>::SharedPtr mesh_pub_;
76-
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr toggle_service_;
77-
std::shared_ptr<MeshColoring> mesh_coloring_;
7872
};
7973

8074
void declare_config(MeshPlugin::Config& config);

hydra_visualizer/src/plugins/khronos_object_plugin.cpp

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ KhronosObjectPlugin::KhronosObjectPlugin(const Config& config,
122122
ianvs::NodeHandle nh,
123123
const std::string& name)
124124
: VisualizerPlugin(name),
125-
config(config::checkValid(config)),
125+
config_("KhronosObjectPlugin", config::checkValid(config)),
126126
dynamic_pub_(
127127
nh.create_publisher<MarkerArray>("dynamic_objects", config.queue_size)),
128128
static_pub_(nh.create_publisher<kimera_pgmo_msgs::msg::Mesh>("static_objects",
@@ -131,11 +131,12 @@ KhronosObjectPlugin::KhronosObjectPlugin(const Config& config,
131131

132132
void KhronosObjectPlugin::draw(const std_msgs::msg::Header& header,
133133
const DynamicSceneGraph& graph) {
134+
const auto config = config_.get();
134135
if (!graph.hasLayer(config.layer)) {
135136
return;
136137
}
137-
drawDynamicObjects(header, graph);
138-
drawStaticObjects(header, graph);
138+
drawDynamicObjects(config, header, graph);
139+
drawStaticObjects(config, header, graph);
139140
}
140141

141142
void KhronosObjectPlugin::reset(const std_msgs::msg::Header& header) {
@@ -153,7 +154,8 @@ void KhronosObjectPlugin::reset(const std_msgs::msg::Header& header) {
153154
previous_objects_.clear();
154155
}
155156

156-
void KhronosObjectPlugin::drawDynamicObjects(const std_msgs::msg::Header& header,
157+
void KhronosObjectPlugin::drawDynamicObjects(const Config& config,
158+
const std_msgs::msg::Header& header,
157159
const DynamicSceneGraph& graph) {
158160
if (dynamic_pub_->get_subscription_count() == 0) {
159161
return;
@@ -171,7 +173,7 @@ void KhronosObjectPlugin::drawDynamicObjects(const std_msgs::msg::Header& header
171173

172174
const uint64_t id = spark_dsg::NodeSymbol(node_id).categoryId();
173175
spark_dsg::BoundingBox bbox = attrs->bounding_box;
174-
const auto color = visualizer::makeColorMsg(getDynamicColor(*attrs, id));
176+
const auto color = visualizer::makeColorMsg(getDynamicColor(config, *attrs, id));
175177

176178
Marker bbox_template;
177179
bbox_template.type = Marker::LINE_LIST;
@@ -220,7 +222,8 @@ void KhronosObjectPlugin::drawDynamicObjects(const std_msgs::msg::Header& header
220222
dynamic_pub_->publish(msg);
221223
}
222224

223-
void KhronosObjectPlugin::drawStaticObjects(const std_msgs::msg::Header& header,
225+
void KhronosObjectPlugin::drawStaticObjects(const Config& config,
226+
const std_msgs::msg::Header& header,
224227
const DynamicSceneGraph& dsg) {
225228
if (static_pub_->get_subscription_count() == 0) {
226229
return;
@@ -295,7 +298,8 @@ void KhronosObjectPlugin::publishTransform(const std_msgs::msg::Header& header,
295298
tf_broadcaster_.sendTransform(msg);
296299
}
297300

298-
Color KhronosObjectPlugin::getDynamicColor(const KhronosObjectAttributes& attrs,
301+
Color KhronosObjectPlugin::getDynamicColor(const Config& config,
302+
const KhronosObjectAttributes& attrs,
299303
const uint64_t id) const {
300304
switch (config.dynamic_color_mode) {
301305
case Config::DynamicColorMode::ID:

0 commit comments

Comments
 (0)