Struct jalansim::range::RayMarching
template <typename T>
ClassList > jalansim > range > RayMarching
Ray marching-based range sensing algorithm. More...
#include <ray_marching.hpp>
Public Attributes
Type | Name |
---|---|
const T | clearance_threshold = T(0.1) Threshold for obstacle detection. |
Public Static Functions
Type | Name |
---|---|
JALANSIM_HOST_DEVICE T | map_calc_range (const jalansim::map::Map< T > * map, T ox, T oy, T oa, T max_range) Calculate range using ray marching algorithm. |
Detailed Description
Implements range sensing using adaptive step size ray marching through a distance field map. Uses the signed distance field to accelerate computation by taking larger steps in free space and smaller steps near obstacles. Provides accurate range measurements with efficient computation, especially in environments with precomputed distance fields.
Template parameters:
T
Numeric type for range calculations (default: double)
Public Attributes Documentation
variable clearance_threshold
Threshold for obstacle detection.
const T jalansim::range::RayMarching< T >::clearance_threshold;
Public Static Functions Documentation
function map_calc_range
Calculate range using ray marching algorithm.
static inline JALANSIM_HOST_DEVICE T jalansim::range::RayMarching::map_calc_range (
const jalansim::map::Map < T > * map,
T ox,
T oy,
T oa,
T max_range
)
Marches a ray from the origin in the specified direction until an obstacle is encountered or maximum range is reached. Uses adaptive step sizing based on the distance field for efficiency.
Parameters:
map
Pointer to the occupancy grid map with distance fieldox
Origin X coordinate in world frame-
oy
Origin Y coordinate in world frame -
oa
Ray direction angle in radians max_range
Maximum sensing range
Returns:
Distance to nearest obstacle or max_range if no obstacle found
The documentation for this class was generated from the following file include/jalansim/range/ray_marching.hpp