diff --git a/hydra_ros/include/hydra_ros/places/external_traversability_estimator.h b/hydra_ros/include/hydra_ros/places/external_traversability_estimator.h index a8cea81..63772e1 100644 --- a/hydra_ros/include/hydra_ros/places/external_traversability_estimator.h +++ b/hydra_ros/include/hydra_ros/places/external_traversability_estimator.h @@ -60,9 +60,7 @@ class ExternalTraversabilityEstimator : public TraversabilityEstimator { ExternalTraversabilityEstimator(const Config& config); ~ExternalTraversabilityEstimator() override = default; - void updateTraversability(const ActiveWindowOutput& msg, - const kimera_pgmo::MeshDelta& /* mesh_delta */, - const spark_dsg::DynamicSceneGraph& /* graph */) override; + void updateTraversability(const ActiveWindowOutput& msg) override; void callback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg); diff --git a/hydra_ros/src/places/external_traversability_estimator.cpp b/hydra_ros/src/places/external_traversability_estimator.cpp index 4f440b1..f331d04 100644 --- a/hydra_ros/src/places/external_traversability_estimator.cpp +++ b/hydra_ros/src/places/external_traversability_estimator.cpp @@ -74,9 +74,7 @@ const TraversabilityLayer& ExternalTraversabilityEstimator::getTraversabilityLay } void ExternalTraversabilityEstimator::updateTraversability( - const ActiveWindowOutput& msg, - const kimera_pgmo::MeshDelta&, - const spark_dsg::DynamicSceneGraph&) { + const ActiveWindowOutput& msg) { if (!traversability_layer_) { const auto& map_config = msg.map().config; traversability_layer_ = std::make_unique(