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