LaserScan

Stores up to 360 range measurements from a 2D LiDAR sensor in a fixed-size array. The fixed [f32; 360] layout makes it a POD type safe for zero-copy shared memory transport (~50 ns per message).

Python: Available via horus.LaserScan(angle_min, angle_max, ...). See Python Sensor Messages.

ROS2 equivalent: sensor_msgs/LaserScan — same conceptual fields. HORUS uses a fixed [f32; 360] array (shared-memory safe) instead of a dynamic Vec<f32>.

// simplified
use horus::prelude::*;

Quick Reference — Fields

FieldTypeUnitDefaultDescription
ranges[f32; 360]m[0.0; 360]Range measurements. 0.0 = invalid reading
angle_minf32rad-PIStart angle of the scan
angle_maxf32radPIEnd angle of the scan
range_minf32m0.1Minimum valid range
range_maxf32m30.0Maximum valid range
angle_incrementf32radPI/180Angular resolution (1 degree)
time_incrementf32s0.0Time between individual measurements
scan_timef32s0.1Time to complete a full scan
timestamp_nsu64ns0Timestamp in nanoseconds since epoch

Quick Reference — Methods

MethodReturnsDescription
new()LaserScanCreates with default parameters and current timestamp
angle_at(index)f32Angle in radians for a given range index
is_range_valid(index)boolChecks if a range reading is valid
valid_count()usizeNumber of valid range readings
min_range()Option<f32>Minimum valid range, or None

Constructor Methods

new()

Creates a laser scan with default parameters and the current timestamp.

Signature

// simplified
pub fn new() -> Self

Parameters

None.

Returns

LaserScan — with defaults: -PI to PI scan range, 1-degree resolution, 0.1–30.0m valid range, all ranges zeroed, and timestamp_ns set to current time.

Panics

Never.

Example

// simplified
use horus::prelude::*;

let mut scan = LaserScan::new();
scan.range_min = 0.1;
scan.range_max = 12.0;

// Populate from sensor driver
scan.ranges[0] = 2.5;   // 2.5m at angle_min
scan.ranges[90] = 1.2;  // 1.2m at 90°
scan.ranges[180] = 0.0;  // invalid (no return)

let topic: Topic<LaserScan> = Topic::new("lidar.scan")?;
topic.send(&scan);

Python Constructor

Creates a laser scan from keyword arguments.

Signature

LaserScan(angle_min=0.0, angle_max=0.0, angle_increment=0.0,
          range_min=0.0, range_max=0.0, ranges=None, timestamp_ns=0)

Parameters

NameTypeRequiredDescription
angle_minf32noStart angle in radians. Default: 0.0.
angle_maxf32noEnd angle in radians. Default: 0.0.
angle_incrementf32noAngular resolution in radians. Default: 0.0.
range_minf32noMinimum valid range in meters. Default: 0.0.
range_maxf32noMaximum valid range in meters. Default: 0.0.
rangeslist[f32]noRange values. Padded with zeros to 360, truncated if longer. Default: None (all zeros).
timestamp_nsu64noTimestamp. Default: 0.

Returns

LaserScan instance. Python supports len(scan) which returns valid_count().

Example

from horus import LaserScan, Topic

scan = LaserScan(
    angle_min=-3.14159,
    angle_max=3.14159,
    angle_increment=0.01745,
    range_min=0.1,
    range_max=12.0,
    ranges=[1.0, 1.1, 1.2, 0.0, 2.5],
)

topic = Topic(LaserScan)
topic.send(scan)

print(f"Min range: {scan.min_range()}")
print(f"Valid readings: {len(scan)}")

If your LiDAR has fewer than 360 beams, leave unused indices at 0.0 — they are filtered out by is_range_valid(). If your LiDAR has more than 360 beams, downsample before publishing.


Methods

angle_at(index)

Returns the angle in radians for a given range index.

Signature

// simplified
pub fn angle_at(&self, index: usize) -> f32

Parameters

NameTypeRequiredDescription
indexusizeyesRange array index (0–359).

Returns

f32 — angle in radians, computed as angle_min + (index as f32) * angle_increment.

Panics

Never. Out-of-range indices produce mathematically valid but meaningless angles.

When to use

  • Converting a range reading to a Cartesian point: x = range * cos(angle_at(i)), y = range * sin(angle_at(i))
  • Filtering readings by angular sector

Example

// simplified
use horus::prelude::*;

let scan = LaserScan::new();
for i in 0..360 {
    if scan.is_range_valid(i) {
        let angle = scan.angle_at(i);
        let x = scan.ranges[i] * angle.cos();
        let y = scan.ranges[i] * angle.sin();
        // (x, y) is the obstacle position in the sensor frame
    }
}

is_range_valid(index)

Checks whether a range reading at the given index is valid.

Signature

// simplified
pub fn is_range_valid(&self, index: usize) -> bool

Parameters

NameTypeRequiredDescription
indexusizeyesRange array index (0–359).

Returns

true if ranges[index] is within [range_min, range_max] AND is finite. false otherwise (including 0.0, NaN, infinite).

Behavior

  • 0.0 is always invalid — it indicates no return from the sensor
  • Values below range_min are invalid (too close, likely noise)
  • Values above range_max are invalid (beyond sensor capability)
  • NaN and infinite values are invalid (sensor fault)

valid_count()

Returns the number of valid range readings in the scan.

Signature

// simplified
pub fn valid_count(&self) -> usize

Parameters

None.

Returns

usize — count of indices where is_range_valid(i) returns true.

When to use

  • Diagnostics — a scan with zero valid readings indicates a sensor fault
  • Adaptive algorithms that need to know scan density

min_range()

Returns the minimum valid range reading, or None if no readings are valid.

Signature

// simplified
pub fn min_range(&self) -> Option<f32>

Parameters

None.

Returns

  • Some(f32) — the smallest valid range value in the scan
  • None — no valid readings exist

When to use

  • Emergency stop — if min_range() < safety_distance, halt the robot
  • Closest-obstacle detection for reactive navigation

When NOT to use

  • When you need the angle of the closest obstacle — iterate with angle_at() instead

Example

// simplified
use horus::prelude::*;

fn emergency_stop(scan: &LaserScan, safety_distance: f32) -> bool {
    match scan.min_range() {
        Some(closest) => closest < safety_distance,
        None => true, // no valid readings = assume danger
    }
}

Production Example

Reactive obstacle avoidance node:

// simplified
use horus::prelude::*;

struct ObstacleAvoidance {
    scan_sub: Topic<LaserScan>,
    cmd_pub: Topic<CmdVel>,
    safety_distance: f32,
}

impl Node for ObstacleAvoidance {
    fn name(&self) -> &str { "ObstacleAvoidance" }

    fn tick(&mut self) {
        if let Some(scan) = self.scan_sub.recv() {
            if let Some(closest) = scan.min_range() {
                if closest < self.safety_distance {
                    // Too close — stop and turn
                    self.cmd_pub.send(CmdVel::new(0.0, 0.5));
                } else {
                    // Clear — drive forward
                    self.cmd_pub.send(CmdVel::new(0.3, 0.0));
                }
            } else {
                // No valid readings — stop
                self.cmd_pub.send(CmdVel::zero());
            }
        }
    }

    fn shutdown(&mut self) -> Result<()> {
        self.cmd_pub.send(CmdVel::zero());
        Ok(())
    }
}

See Also