Decode Hesai Pandar Packets to NumPy arrays or PointCloud2 messages
Project description
hydra4
A Python library for decoding Hesai Pandar LiDAR packets into pypcd4 PointCloud objects.
hydra4 converts raw pandar_msgs/PandarScan messages — whether read from a rosbag file or received in real time over ROS 2 — into structured point clouds that are ready for downstream processing.
Supported Models
| Model | Channels | Default Range | Return Modes |
|---|---|---|---|
| Pandar XT-32 | 32 | 0.1 – 120.0 m | Single / Dual (Last-Strongest, …) |
| Pandar OT-128 | 128 | 0.3 – 230.0 m | Single / Dual, High-Res & Standard |
Requirements
Installation
pip install hydra4
Quick Start
from hydra4 import Hydra
hydra = Hydra(model=Hydra.Model.PandarXT32)
# `pandar_scan_msg` is a pandar_msgs/PandarScan message
point_clouds = hydra.to_pypcd4(pandar_scan_msg)
for pc in point_clouds:
print(pc.pc_data["x"][:5])
Usage with rosbags
rosbags can read ROS 1 and ROS 2 bag files without a ROS installation.
The example below decodes every PandarScan message in a bag and converts them to pypcd4.PointCloud objects.
from pathlib import Path
from rosbags.highlevel import AnyReader
from rosbags.typesys import Stores, get_types_from_msg, get_typestore
from hydra4 import Hydra
# 1. Register the Pandar message types with rosbags
typestore = get_typestore(Stores.LATEST)
typestore.register(
get_types_from_msg(
"builtin_interfaces/Time stamp\nuint8[1500] data\nuint32 size\n",
"pandar_msgs/msg/PandarPacket",
)
)
typestore.register(
get_types_from_msg(
"std_msgs/Header header\nPandarPacket[] packets\n",
"pandar_msgs/msg/PandarScan",
)
)
# 2. Create the decoder
hydra = Hydra(model=Hydra.Model.PandarXT32)
# 3. Read the bag and decode each scan
bag_path = Path("path/to/rosbag")
with AnyReader([bag_path], default_typestore=typestore) as reader:
for connection, _timestamp, rawdata in reader.messages():
msg = reader.deserialize(rawdata, connection.msgtype)
for pc in hydra.to_pypcd4(msg):
# Each `pc` is a pypcd4.PointCloud
print(f"Frame with {pc.points} points")
# Save to PCD file
pc.save("output.pcd")
Usage with a ROS 2 Subscriber
You can also use hydra4 inside a standard ROS 2 subscriber node.
import rclpy
from rclpy.node import Node
from hydra4 import Hydra
class PandarDecoderNode(Node):
def __init__(self) -> None:
super().__init__("pandar_decoder_node")
self.hydra = Hydra(model=Hydra.Model.PandarXT32)
self.subscription = self.create_subscription(
msg_type=..., # pandar_msgs.msg.PandarScan
topic="/pandar/pandar_packets",
callback=self.on_scan,
qos_profile=10,
)
def on_scan(self, msg) -> None:
for pc in self.hydra.to_pypcd4(msg):
self.get_logger().info(f"Decoded frame: {pc.points} points")
# Process or publish the point cloud ...
def main() -> None:
rclpy.init()
node = PandarDecoderNode()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":
main()
Constructor Parameters
| Parameter | Type | Description |
|---|---|---|
model |
Hydra.Model |
LiDAR model (PandarXT32 or PandarOT128) |
calibration_path |
str | Path | None |
Path to a calibration CSV. Defaults to the built-in file. |
min_distance |
float | None |
Minimum valid distance in metres. Defaults to model spec. |
max_distance |
float | None |
Maximum valid distance in metres. Defaults to model spec. |
dual_return_distance_threshold |
float |
Dual-return deduplication threshold in metres (default: 0.1). |
Dual-Return Deduplication
When the sensor operates in a dual-return mode (e.g. Last-Strongest), two blocks share the same azimuth angle. If the distance difference between the first and last return for the same channel is smaller than dual_return_distance_threshold, the first return is discarded to avoid near-duplicate points. Set the threshold to 0.0 to keep all returns.
Output Fields
Each pypcd4.PointCloud contains a structured NumPy array with the following fields:
| Field | Type | Description |
|---|---|---|
x |
float32 | X coordinate in metres |
y |
float32 | Y coordinate in metres |
z |
float32 | Z coordinate in metres |
intensity |
float32 | Return intensity (0 – 255) |
ring |
uint16 | Channel / laser ring index |
azimuth |
float32 | Raw azimuth value (hundredths deg) |
stamp |
float64 | Per-point timestamp (Unix epoch) |
Project Structure
src/hydra4/
├── __init__.py # Public API — exports Hydra
├── hydra4.py # Hydra class (message → PointCloud pipeline)
├── structs.py # ReturnMode enum, Block dataclass
├── calibrations/ # Built-in calibration CSVs
│ ├── pandar_xt32.csv
│ └── pandar_ot128.csv
├── decoders/
│ ├── base.py # PandarBase abstract decoder
│ ├── pandar_xt32.py # XT-32 packet decoder
│ └── pandar_ot128.py # OT-128 packet decoder
└── msgs/ # Lightweight ROS message dataclasses
├── pandar_msgs.py
├── std_msgs.py
└── builtin_interfaces.py
Development
# Set up the development environment
uv sync --group dev
# Run the full test suite
pytest tests -vv
# Run only unit / integration / e2e tests
pytest tests/unit -vv
pytest tests/integration -vv
pytest tests/e2e -vv
# Lint and format
ruff check src/ tests/
ruff format src/ tests/
License
Apache License 2.0 — see LICENSE.txt for details.
Project details
Release history Release notifications | RSS feed
Download files
Download the file for your platform. If you're not sure which to choose, learn more about installing packages.
Source Distribution
Built Distribution
Filter files by name, interpreter, ABI, and platform.
If you're not sure about the file name format, learn more about wheel file names.
Copy a direct link to the current filters
File details
Details for the file hydra4-0.2.0.tar.gz.
File metadata
- Download URL: hydra4-0.2.0.tar.gz
- Upload date:
- Size: 89.0 kB
- Tags: Source
- Uploaded using Trusted Publishing? No
- Uploaded via: uv/0.11.6 {"installer":{"name":"uv","version":"0.11.6","subcommand":["publish"]},"python":null,"implementation":{"name":null,"version":null},"distro":{"name":"Ubuntu","version":"22.04","id":"jammy","libc":null},"system":{"name":null,"release":null},"cpu":null,"openssl_version":null,"setuptools_version":null,"rustc_version":null,"ci":null}
File hashes
| Algorithm | Hash digest | |
|---|---|---|
| SHA256 |
d98c7a6743bb24b3019debbe32ea4c77abec19c406fc1a240077ddaa48a87cd5
|
|
| MD5 |
d9bde34ec96610d8e18e6ed28e5741c5
|
|
| BLAKE2b-256 |
b362511e30e657d6d633bd5be018bddbd3bc2b29af35efd6bb83f0c31acfa736
|
File details
Details for the file hydra4-0.2.0-py3-none-any.whl.
File metadata
- Download URL: hydra4-0.2.0-py3-none-any.whl
- Upload date:
- Size: 25.4 kB
- Tags: Python 3
- Uploaded using Trusted Publishing? No
- Uploaded via: uv/0.11.6 {"installer":{"name":"uv","version":"0.11.6","subcommand":["publish"]},"python":null,"implementation":{"name":null,"version":null},"distro":{"name":"Ubuntu","version":"22.04","id":"jammy","libc":null},"system":{"name":null,"release":null},"cpu":null,"openssl_version":null,"setuptools_version":null,"rustc_version":null,"ci":null}
File hashes
| Algorithm | Hash digest | |
|---|---|---|
| SHA256 |
cd38caba42b7a25501292d958cc3e79c5edd9c060bab1c93be30f5a1d8347707
|
|
| MD5 |
18ddfcdfe200dcd429ac0ccca25d4a65
|
|
| BLAKE2b-256 |
5ba73e266254e9e4ed537cc11486473436e35cece378657d9f4240817ef8d892
|