Struct jalansim::range::Bresenham
template <typename T>
ClassList > jalansim > range > Bresenham
Bresenham line algorithm-based range sensing.More...
#include <bresenham.hpp>
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 Bresenham line algorithm. |
Detailed Description
Implements range sensing using the classic Bresenham line drawing algorithm to trace rays through an occupancy grid. Efficiently steps through grid cells along a straight line from origin to target, checking each cell for occupancy. Handles both steep and shallow line angles using coordinate swapping for optimal performance on discrete grids.
Template parameters:
T
Numeric type for range calculations (default: double)
Public Static Functions Documentation
function map_calc_range
Calculate range using Bresenham line algorithm.
static inline JALANSIM_HOST_DEVICE T jalansim::range::Bresenham::map_calc_range (
const jalansim::map::Map < T > * map,
T ox,
T oy,
T oa,
T max_range
)
Traces a ray from origin in the specified direction using Bresenham's line algorithm to efficiently step through grid cells. Returns distance to first occupied cell or maximum range if no obstacle is encountered.
Parameters:
map
Pointer to the occupancy grid mapox
Origin X coordinate in world frameoy
Origin Y coordinate in world frameoa
Ray direction angle in radiansmax_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/bresenham.hpp