Skip to content

Commit d885a14

Browse files
authored
Feature/geometry only (#41)
* add no semantic data receiver * add single channel grayscale parsing for color inputs * astro place subscriber * play around with fixing astro input relative pose * rename traversability estimator * rename files accordingly * run pre-commit * rename RGBD image receiver
1 parent 605769d commit d885a14

File tree

10 files changed

+345
-51
lines changed

10 files changed

+345
-51
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/external_traversability_estimator.cpp
5253
src/odometry/ros_pose_graph_tracker.cpp
5354
src/openset/ros_embedding_group.cpp
5455
src/utils/bow_subscriber.cpp

hydra_ros/include/hydra_ros/input/image_receiver.h

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,30 @@ void ImageReceiverImpl<SemanticT>::callback(
182182
queue.push(packet);
183183
}
184184

185+
class RGBDImageReceiver : public RosDataReceiver {
186+
public:
187+
struct Config : RosDataReceiver::Config {};
188+
using Policy =
189+
message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image,
190+
sensor_msgs::msg::Image>;
191+
using Synchronizer = message_filters::Synchronizer<Policy>;
192+
193+
RGBDImageReceiver(const Config& config, const std::string& sensor_name);
194+
virtual ~RGBDImageReceiver() = default;
195+
196+
protected:
197+
bool initImpl() override;
198+
199+
void callback(const sensor_msgs::msg::Image::ConstSharedPtr& color,
200+
const sensor_msgs::msg::Image::ConstSharedPtr& depth);
201+
202+
ColorSubscriber color_sub_;
203+
DepthSubscriber depth_sub_;
204+
std::unique_ptr<Synchronizer> sync_;
205+
};
206+
207+
void declare_config(RGBDImageReceiver::Config& config);
208+
185209
class ClosedSetImageReceiver : public ImageReceiverImpl<LabelSubscriber> {
186210
public:
187211
struct Config : RosDataReceiver::Config {};
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
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 as occupancy grid to perform
48+
* traversability analysis.
49+
*/
50+
class ExternalTraversabilityEstimator : public TraversabilityEstimator {
51+
public:
52+
struct Config {
53+
//! @brief The height above the robot body to consider for traversability in meters.
54+
std::string input_topic = "/local_cost_map";
55+
unsigned int queue_size = 2;
56+
} const config;
57+
58+
using State = spark_dsg::TraversabilityState;
59+
60+
ExternalTraversabilityEstimator(const Config& config);
61+
~ExternalTraversabilityEstimator() override = default;
62+
63+
void updateTraversability(const ActiveWindowOutput& msg,
64+
const kimera_pgmo::MeshDelta& /* mesh_delta */,
65+
const spark_dsg::DynamicSceneGraph& /* graph */) override;
66+
67+
void callback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
68+
69+
const TraversabilityLayer& getTraversabilityLayer() const override;
70+
71+
protected:
72+
rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr sub_;
73+
mutable std::mutex mutex_;
74+
75+
protected:
76+
State occupancyToTraversability(int8_t occupancy) const;
77+
};
78+
79+
void declare_config(ExternalTraversabilityEstimator::Config& config);
80+
81+
} // namespace hydra::places

hydra_ros/src/frontend/traversability_visualizer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ Color TraversabilityVisualizer::debugColor(float value) const {
173173
if (value < 0.0f) {
174174
return Color::black();
175175
}
176-
return spark_dsg::colormaps::rainbowId(static_cast<int>(value), 5);
176+
return spark_dsg::colormaps::rainbowId(static_cast<int>(value), 10);
177177
}
178178

179179
} // namespace hydra

hydra_ros/src/input/image_receiver.cpp

Lines changed: 59 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -56,11 +56,28 @@ ColorSubscriber::Filter& ColorSubscriber::getFilter() const {
5656
}
5757

5858
void ColorSubscriber::fillInput(const Image& img, ImageInputPacket& packet) const {
59-
try {
60-
packet.color = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::RGB8)->image;
61-
} catch (const cv_bridge::Exception& e) {
62-
LOG(ERROR) << "Failed to convert color image: " << e.what();
59+
// Allow also mono images to be converted to grayscale.
60+
if (sensor_msgs::image_encodings::isColor(img.encoding)) {
61+
try {
62+
packet.color =
63+
cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::RGB8)->image;
64+
return;
65+
} catch (const cv_bridge::Exception& e) {
66+
LOG(ERROR) << "Failed to convert mono image as color input: " << e.what();
67+
return;
68+
}
69+
} else if (sensor_msgs::image_encodings::isMono(img.encoding)) {
70+
try {
71+
cv::Mat mono =
72+
cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8)->image;
73+
cv::cvtColor(mono, packet.color, cv::COLOR_GRAY2RGB);
74+
return;
75+
} catch (const cv_bridge::Exception& e) {
76+
LOG(ERROR) << "Failed to convert color image: " << e.what();
77+
return;
78+
}
6379
}
80+
LOG(ERROR) << "Failed to convert color image: unsupported encoding: " << img.encoding;
6481
}
6582

6683
DepthSubscriber::DepthSubscriber() = default;
@@ -130,6 +147,38 @@ void FeatureSubscriber::fillInput(const MsgType& msg, ImageInputPacket& packet)
130147
}
131148
}
132149

150+
void declare_config(RGBDImageReceiver::Config& config) {
151+
using namespace config;
152+
name("RGBDImageReceiver::Config");
153+
base<RosDataReceiver::Config>(config);
154+
}
155+
156+
RGBDImageReceiver::RGBDImageReceiver(const Config& config,
157+
const std::string& sensor_name)
158+
: RosDataReceiver(config, sensor_name) {}
159+
160+
bool RGBDImageReceiver::initImpl() {
161+
color_sub_ = ColorSubscriber(ianvs::NodeHandle::this_node(ns_));
162+
depth_sub_ = DepthSubscriber(ianvs::NodeHandle::this_node(ns_));
163+
sync_.reset(new Synchronizer(
164+
Policy(config.queue_size), color_sub_.getFilter(), depth_sub_.getFilter()));
165+
sync_->registerCallback(&RGBDImageReceiver::callback, this);
166+
return true;
167+
}
168+
169+
void RGBDImageReceiver::callback(const sensor_msgs::msg::Image::ConstSharedPtr& color,
170+
const sensor_msgs::msg::Image::ConstSharedPtr& depth) {
171+
const auto timestamp_ns = rclcpp::Time(color->header.stamp).nanoseconds();
172+
if (!checkInputTimestamp(timestamp_ns)) {
173+
return;
174+
}
175+
176+
auto packet = std::make_shared<ImageInputPacket>(timestamp_ns, sensor_name_);
177+
color_sub_.fillInput(*color, *packet);
178+
depth_sub_.fillInput(*depth, *packet);
179+
queue.push(packet);
180+
}
181+
133182
void declare_config(ClosedSetImageReceiver::Config& config) {
134183
using namespace config;
135184
name("ClosedSetImageReceiver::Config");
@@ -152,6 +201,12 @@ OpenSetImageReceiver::OpenSetImageReceiver(const Config& config,
152201

153202
namespace {
154203

204+
static const auto no_semantic_registration =
205+
config::RegistrationWithConfig<DataReceiver,
206+
RGBDImageReceiver,
207+
RGBDImageReceiver::Config,
208+
std::string>("RGBDImageReceiver");
209+
155210
static const auto closed_registration =
156211
config::RegistrationWithConfig<DataReceiver,
157212
ClosedSetImageReceiver,
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/external_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+
ExternalTraversabilityEstimator,
49+
ExternalTraversabilityEstimator::Config>(
50+
"ExternalTraversabilityEstimator");
51+
52+
void declare_config(ExternalTraversabilityEstimator::Config& config) {
53+
using namespace config;
54+
name("ExternalTraversabilityEstimator::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+
ExternalTraversabilityEstimator::ExternalTraversabilityEstimator(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+
&ExternalTraversabilityEstimator::callback,
67+
this);
68+
}
69+
70+
const TraversabilityLayer& ExternalTraversabilityEstimator::getTraversabilityLayer()
71+
const {
72+
std::lock_guard<std::mutex> lock(mutex_);
73+
return *traversability_layer_;
74+
}
75+
76+
void ExternalTraversabilityEstimator::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 ExternalTraversabilityEstimator::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, y, 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+
ExternalTraversabilityEstimator::State
141+
ExternalTraversabilityEstimator::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

0 commit comments

Comments
 (0)