Skip to content

Commit

Permalink
Remove option to use a non-zero min_range in the ray casting renderer
Browse files Browse the repository at this point in the history
  • Loading branch information
victorreijgwart committed Dec 6, 2024
1 parent 21a6143 commit 730cb28
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 16 deletions.
14 changes: 10 additions & 4 deletions examples/python/render/raycast_depth_image.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,14 @@ def save_depth_as_png(depth_map: np.ndarray, output_path: Path):
out_path = Path(__file__).parent / "depth.png"

# Configure the virtual sensor's projection model
# NOTE: These intrinsics match the Zed 2i depth camera.
# NOTE: The projection model can be configured through a Python dictionary.
# Diagnostics for invalid configurations are printed to the terminal.
# For an overview of all the available models and their params, see:
# pylint: disable=line-too-long
# https://ethz-asl.github.io/wavemap/pages/parameters/measurement_integrators.html#projection-models
# Examples for a broad selection of common sensors can be found in the
# `interfaces/ros1/wavemap_ros/config` directory.
# The intrinsics below match the Zed 2i depth camera.
projection_model = wm.Projector.create({
"type": "pinhole_camera_projector",
"width": 1280,
Expand All @@ -49,12 +56,11 @@ def save_depth_as_png(depth_map: np.ndarray, output_path: Path):

# Create the depth image renderer
log_odds_occupancy_threshold = 0.1
min_range = 0.1
max_range = 6.0
default_depth_value = -1.0
renderer = wm.RaycastingRenderer(your_map, projection_model,
log_odds_occupancy_threshold, min_range,
max_range, default_depth_value)
log_odds_occupancy_threshold, max_range,
default_depth_value)

# Create pose
rotation = wm.Rotation(np.eye(3))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ class RaycastingRenderer {
RaycastingRenderer(MapBase::ConstPtr occupancy_map,
ProjectorBase::ConstPtr projection_model,
FloatingPoint log_odds_occupancy_threshold = 1e-3f,
FloatingPoint min_range = 0.f,
FloatingPoint max_range = 10.f,
FloatingPoint default_depth_value = -1.f,
std::shared_ptr<ThreadPool> thread_pool = nullptr);
Expand All @@ -28,7 +27,6 @@ class RaycastingRenderer {
const std::shared_ptr<ThreadPool> thread_pool_;

const ProjectorBase::ConstPtr projection_model_;
const FloatingPoint min_range_;
const FloatingPoint max_range_;
const FloatingPoint log_odds_occupancy_threshold_;

Expand Down
10 changes: 3 additions & 7 deletions library/cpp/src/core/utils/render/raycasting_renderer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,12 @@
namespace wavemap {
RaycastingRenderer::RaycastingRenderer(
MapBase::ConstPtr occupancy_map, ProjectorBase::ConstPtr projection_model,
FloatingPoint log_odds_occupancy_threshold, FloatingPoint min_range,
FloatingPoint max_range, FloatingPoint default_depth_value,
std::shared_ptr<ThreadPool> thread_pool)
FloatingPoint log_odds_occupancy_threshold, FloatingPoint max_range,
FloatingPoint default_depth_value, std::shared_ptr<ThreadPool> thread_pool)
: map_(CHECK_NOTNULL(occupancy_map)),
thread_pool_(thread_pool ? std::move(thread_pool)
: std::make_shared<ThreadPool>()),
projection_model_(CHECK_NOTNULL(projection_model)),
min_range_(min_range),
max_range_(max_range),
log_odds_occupancy_threshold_(log_odds_occupancy_threshold),
depth_image_(projection_model_->getDimensions(), default_depth_value) {}
Expand All @@ -36,11 +34,9 @@ void RaycastingRenderer::renderPatch(const MapT& map,
for (const Index2D& index : Grid(patch_min, patch_max)) {
FloatingPoint& depth_pixel = depth_image_.at(index);
const Vector2D image_xy = projection_model_->indexToImage(index);
const Point3D C_start_point =
projection_model_->sensorToCartesian({image_xy, min_range_});
const Point3D& W_start_point = T_W_C.getPosition();
const Point3D C_end_point =
projection_model_->sensorToCartesian({image_xy, max_range_});
const Point3D W_start_point = T_W_C * C_start_point;
const Point3D W_end_point = T_W_C * C_end_point;
const auto d_start_collision = raycast::first_collision_distance(
query_accelerator, W_start_point, W_end_point,
Expand Down
6 changes: 3 additions & 3 deletions library/python/src/render.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@ void add_render_bindings(nb::module_& m) {
"Render depth images using ray casting.")
.def(nb::init<std::shared_ptr<const MapBase>,
std::shared_ptr<const ProjectorBase>, FloatingPoint,
FloatingPoint, FloatingPoint, FloatingPoint>(),
FloatingPoint, FloatingPoint>(),
"occupancy_map"_a, "projection_model"_a,
"log_odds_occupancy_threshold"_a = 1e-3f, "min_range"_a = 0.f,
"max_range"_a = 10.f, "default_depth_value"_a = -1.f)
"log_odds_occupancy_threshold"_a = 1e-3f, "max_range"_a = 10.f,
"default_depth_value"_a = -1.f)
.def("render", &RaycastingRenderer::render, "pose"_a);
}
} // namespace wavemap

0 comments on commit 730cb28

Please sign in to comment.