diff --git a/.cspell.json b/.cspell.json
index e29253bd5..7595a3b94 100644
--- a/.cspell.json
+++ b/.cspell.json
@@ -8,6 +8,7 @@
"Adctp",
"Agnocast",
"applicate",
+ "asio",
"AT",
"autosar",
"block_id",
@@ -39,6 +40,7 @@
"millidegrees",
"mkdoxy",
"Msop",
+ "myvendor",
"nohide",
"nohup",
"nproc",
@@ -56,6 +58,7 @@
"QT",
"rclcpp",
"RCPPUTILS",
+ "rviz",
"rosbag",
"rosbags",
"schedutil",
diff --git a/docs/integration_guide.md b/docs/integration_guide.md
new file mode 100644
index 000000000..e7be6ece5
--- /dev/null
+++ b/docs/integration_guide.md
@@ -0,0 +1,444 @@
+# Integrating a new Sensor
+
+This guide provides instructions for adding support for a new sensor to Nebula. We provide a
+template implementation (`nebula_sample`) and reusable components to simplify the process.
+
+## Architecture overview
+
+### Overall package structure
+
+Nebula is organized into core packages and vendor-specific packages:
+
+```mermaid
+graph TB
+
+ %% --- GRAPH STRUCTURE ---
+ subgraph Nebula["Nebula framework"]
+ direction TB
+
+ subgraph Common["Common packages"]
+ direction LR
+ C1["nebula_core_common
Base types, status codes"]
+ C2["nebula_core_decoders
Decoder interfaces"]
+ C3["nebula_core_hw_interfaces
UDP/TCP sockets"]
+ C4["nebula_core_ros
ROS 2 utils"]
+ end
+
+ subgraph Vendors["Vendor packages"]
+ direction LR
+ Hesai["nebula_hesai
hesai_common
hesai_decoders
hesai_hw_interfaces
ROS wrapper"]
+
+ Velodyne["nebula_velodyne
velodyne_common
velodyne_decoders
velodyne_hw_interfaces
ROS wrapper"]
+
+ Sample["nebula_sample
sample_common
sample_decoders
sample_hw_interfaces
ROS wrapper"]
+ end
+ end
+```
+
+- Core packages provide reusable functionality (UDP sockets, point types, etc.)
+- Vendor packages implement vendor-specific logic (packet parsing, calibration)
+- Vendor packages are typically split into `common`, `decoders`, `hw_interfaces` and
+ `ROS wrapper`:
+ - `common`: Vendor-specific types, internal interfaces and utilities
+ - `decoders`: Packet parsing and conversion to point clouds
+ - `hw_interfaces`: Network communication
+ - `ROS wrapper`: ROS 2 node, parameters, publishers, orchestration
+- Vendor packages depend on core packages but not on each other
+
+Except for the ROS wrappers, no package should depend on ROS 2. This allows users to run parts
+of Nebula as a library e.g. in ML pipelines without ROS 2.
+
+!!! warning
+
+ Existing vendor implementations do not strictly follow this architecture as the project
+ evolved over time. New implementations should follow the architecture described here.
+
+### Data Flow
+
+`nebula_sample` supports two runtime modes controlled by `launch_hw`:
+
+```mermaid
+flowchart LR
+
+ subgraph Online["launch_hw:=true (online)"]
+ direction LR
+
+ S[Sensor]
+ HW[Hardware Interface]
+ DC[Decoder]
+ RW[ROS Wrapper]
+ PKT[(packets / NebulaPackets)]
+
+ S-->|UDP| HW
+ HW -->|data packet| DC
+ HW -->|data packet| RW
+ DC -->|pointcloud| RW
+ RW -->|decoded scan's raw packets| PKT[(packets / NebulaPackets)]
+ end
+
+ subgraph Offline["launch_hw:=false (offline replay)"]
+ direction LR
+
+ PKT2[(packets / NebulaPackets)]
+ DC2[Decoder]
+ RW2[ROS Wrapper]
+
+ PKT2 -->|replayed packets| DC2
+ DC2 -->|pointcloud| RW2
+ end
+
+ PTS[(points / PointCloud2)]
+
+ RW -->|decoded scan| PTS
+ RW2 -->|decoded scan| PTS
+```
+
+The ROS wrapper owns the runtime mode resources and wiring:
+
+- Online mode: hardware interface + packet publisher
+- Offline mode: packet subscriber
+
+## Component Library
+
+Nebula provides reusable components to simplify sensor integration. Use these components to
+reduce boilerplate code and ensure consistent behavior across sensors and vendors.
+
+### UDP socket handling
+
+```cpp
+--8<-- "src/nebula_core/nebula_core_hw_interfaces/examples/udp_socket_usage_example.cpp:include"
+```
+
+**What it provides**:
+
+- UDP socket with easy builder-style configuration
+- Threaded packet reception with user-defined callback
+- Metadata (socket timestamp, buffer overflow count) for each packet
+
+**Usage**:
+
+```cpp
+--8<-- "src/nebula_core/nebula_core_hw_interfaces/examples/udp_socket_usage_example.cpp:usage"
+```
+
+### Expected
+
+```c++
+--8<-- "src/nebula_core/nebula_core_common/examples/expected_usage_example.cpp:include"
+```
+
+**What it provides**:
+
+For operations that can fail, but should not crash the program, return values via
+`nebula::util::expected`. Avoid sentinel return values (e.g., `nullptr`, `-1`) and
+exceptions. This keeps APIs explicit about what can fail:
+
+**Usage**:
+
+```cpp
+--8<-- "src/nebula_core/nebula_core_common/examples/expected_usage_example.cpp:usage"
+```
+
+!!! tip
+
+ If the happy path has no meaningful return value, use `std::monostate` (a type with no data) as
+ `T`:
+
+ ```cpp
+ nebula::util::expected do_something();
+ ```
+
+See [CPP Reference](https://en.cppreference.com/w/cpp/utility/expected.html) for more details on the
+`std::expected` type of C++23, which `nebula::util::expected` is based on.
+
+### Point cloud types
+
+```c++
+--8<-- "src/nebula_core/nebula_core_ros/examples/point_types_usage_example.cpp:include"
+```
+
+**What it provides**:
+
+- `NebulaPoint` - Standard point type with x, y, z, intensity, timestamp, return_type, channel,
+ azimuth, elevation, distance
+- `NebulaPointCloud` - Point cloud of NebulaPoints
+- Conversion utilities to ROS/Autoware point types
+
+Nebula point types are designed for compatibility with and efficiency of downstream tasks.
+Since Nebula is the official sensor driver framework for Autoware, using Nebula point types
+ensures seamless integration with Autoware components.
+
+**Usage**:
+
+```cpp
+--8<-- "src/nebula_core/nebula_core_ros/examples/point_types_usage_example.cpp:usage"
+```
+
+### Angle utilities
+
+```c++
+--8<-- "src/nebula_core/nebula_core_common/examples/angle_utilities_usage_example.cpp:include"
+```
+
+**What it provides**:
+
+- `deg2rad()`, `rad2deg()` - Angle conversions
+- `angle_is_between()` - Angle checks with wrap-around support
+- Angle normalization functions
+
+**Usage**:
+
+```c++
+--8<-- "src/nebula_core/nebula_core_common/examples/angle_utilities_usage_example.cpp:usage"
+```
+
+### Logger integration
+
+```c++
+--8<-- "src/nebula_core/nebula_core_common/examples/logger_integration_usage_example.cpp:include"
+```
+
+**What it provides**:
+
+- Unified logging interface via `Logger`
+- ROS 2 logger wrapper (`RclcppLogger`)
+- Macros: `NEBULA_LOG_STREAM(logger->info, "message")`
+
+This is a dependency-injection pattern: non-ROS (ROS-independent) modules log through the generic
+`loggers::Logger` interface, while the ROS wrapper can provide a `RclcppLogger` implementation so
+those modules still log into ROS 2.
+
+**Usage**:
+
+```cpp
+--8<-- "src/nebula_core/nebula_core_common/examples/logger_integration_usage_example.cpp:usage"
+```
+
+### Diagnostic integration
+
+```c++
+--8<-- "src/nebula_core/nebula_core_ros/examples/diagnostic_integration_usage_example.cpp:include"
+```
+
+**What it provides**:
+
+- Diagnostic task helpers used across Nebula (e.g., `RateBoundStatus`, `LivenessMonitor`)
+- Consistent patterns for publish-rate and liveness monitoring
+
+**Usage**:
+
+```cpp
+--8<-- "src/nebula_core/nebula_core_ros/examples/diagnostic_integration_usage_example.cpp:usage"
+```
+
+## Integration workflow
+
+### Step 1: Clone and rename template
+
+Copy the `nebula_sample` directory:
+
+```bash
+cd src
+cp -r nebula_sample nebula_myvendor
+```
+
+### Step 2: Rename components
+
+Rename all occurrences of "sample"/"Sample" to your vendor name:
+
+- Directories: `nebula_sample_*` → `nebula_myvendor_*`
+- Files: `sample_*.{cpp,hpp}` → `myvendor_*.{cpp,hpp}`
+- Classes: Rename wrapper / decoder / HW interface classes (e.g., `SampleRosWrapper`,
+ `SampleDecoder`, `SampleHwInterface`)
+- Namespaces: Update in all files
+- CMake/package: Update `CMakeLists.txt` and `package.xml`
+
+Tip: Use find-and-replace tools:
+
+```bash
+find nebula_myvendor -type f -exec sed -i 's/sample/myvendor/g' {} +
+find nebula_myvendor -type f -exec sed -i 's/Sample/MyVendor/g' {} +
+```
+
+### Step 3: Implement components
+
+See [Implementation details](#implementation-details) below.
+
+### Step 4: Verify
+
+See [Verification](#verification) below.
+
+## Implementation details
+
+The `nebula_sample` package provides a template implementation. Its source files contain
+comments and concise `Implement:` markers in key stubs to guide implementation.
+
+Some examples might not be relevant for your sensor, e.g. calibration handling. Implement only
+what is necessary for your sensor.
+
+### About SDK integration
+
+If you are a sensor vendor with your own SDK, you might be able to replace parts of the decoder
+and HW interface with calls to the SDK. Integrate your SDK either through Git submodules, or
+by adding it to `build_depends.repos`.
+
+!!! warning
+
+ Nebula is licensed under the Apache 2.0 license and has a strict no-binaries policy. Ensure
+ that your SDK _source code_ is public, and ensure that your SDK license allows shipping as
+ part of an Apache 2.0 project.
+
+Please ensure that the SDK is fit for automotive use cases (real-time, safety, reliability).
+Nebula interfaces like
+
+- pointcloud output topic (the sample template uses `/points` with `PointCloud2`)
+- packet publish/replay topic (the sample template uses `/packets` with `NebulaPackets`)
+- `/diagnostics`
+- launch patterns
+
+must be implemented correctly.
+
+## Required behaviors
+
+Your sensor integration must implement these behaviors correctly.
+
+### Startup sequence
+
+Order of operations:
+
+1. Parameter loading: Declare and read ROS parameters
+2. Configuration validation: Validate IP addresses, ports, ranges
+3. Publisher creation: Create ROS publishers
+4. Decoder initialization: Create decoder and register pointcloud callback
+5. Runtime mode setup:
+ - `launch_hw:=true`: create HW interface + packet publisher
+ - `launch_hw:=false`: create packet subscriber for replay
+6. Packet forwarding:
+ - online: register HW callback, decode packets, publish accumulated `NebulaPackets` per scan
+ - offline: decode packets received from `NebulaPackets` subscription
+7. Stream start (online only): call `sensor_interface_start()`
+
+### Reconfiguration (optional)
+
+When parameters change at runtime:
+
+1. Validate new parameters: Check if new values are valid
+2. Update configuration: Apply new parameter values
+3. Reinitialize driver: Create new driver with updated config
+
+### Connection loss handling
+
+Detect and handle sensor disconnection:
+
+1. Liveness timeout: Configure `diagnostics.packet_liveness.timeout_ms`
+2. Diagnostic update: Tick `LivenessMonitor` on each packet path (online and replay)
+3. Optional: Add explicit connection-loss logs/recovery if required by your sensor
+
+### Shutdown sequence
+
+Prefer RAII-based shutdown: sockets/threads/buffers should be owned by objects whose destructors
+stop/join/close automatically, so the wrapper does not require sensor-specific resource cleanup.
+
+Order of operations:
+
+1. Stop stream explicitly (e.g., `sensor_interface_stop()`)
+2. Use RAII to clean up resources (sockets, threads, buffers)
+3. Make sure that dependent components are still valid during shutdown (e.g., decoder should not be
+ destroyed before HW interface stops)
+
+### Diagnostic reporting
+
+Required diagnostic information:
+
+- Publish rate: Use `custom_diagnostic_tasks::RateBoundStatus`
+- Liveness: Use `nebula::ros::LivenessMonitor`
+- Debug timings: Publish receive/decode/publish durations for profiling
+
+## Verification
+
+This section contains basic commands you can use to verify your implementation.
+
+### Build and test
+
+Build and test both have to succeed without warnings or errors.
+
+```bash
+colcon build --packages-up-to nebula_myvendor
+# This tests all myvendor packages
+colcon test --packages-select-regex nebula_myvendor
+colcon test-result --verbose
+```
+
+### Live testing
+
+For testing with a real sensor, launch Nebula with your sensor model:
+
+```bash
+# From your package
+ros2 launch nebula_myvendor nebula_myvendor.launch.xml sensor_model:=mysensor
+# From the `nebula` package
+ros2 launch nebula nebula_launch.py sensor_model:=mysensor
+```
+
+To record a rosbag of Nebula packet output for later replay:
+
+```bash
+ros2 bag record /packets -o mysensor_packets
+```
+
+### Replay testing
+
+You can test Nebula offline with the rosbag recorded above:
+
+```bash
+# Set launch_hw:=false to use rosbag replay
+ros2 launch nebula_myvendor nebula_myvendor.launch.xml launch_hw:=false
+
+# In another terminal, play the recorded ROS 2 bag
+ros2 bag play mysensor_packets
+```
+
+## Integration checklist
+
+### Basic setup
+
+- [ ] Copied and renamed `nebula_sample` to `nebula_myvendor`
+- [ ] Renamed all occurrences of "sample"/"Sample" to your vendor name
+- [ ] Updated `package.xml`s with author and package info
+- [ ] Updated copyright headers
+
+### Implementation tasks
+
+- [ ] Implemented `SensorConfiguration` struct
+- [ ] Mapped ROS parameters in Wrapper
+- [ ] Implemented `unpack()` method in Decoder
+- [ ] Implemented scan completion detection
+- [ ] Implemented communication in HW Interface
+- [ ] Implemented startup sequence
+- [ ] Implemented shutdown sequence
+- [ ] Added diagnostic reporting
+- [ ] Added packet liveness diagnostics
+
+### Verification tasks
+
+- [ ] Verified build succeeds without warnings
+- [ ] Verified point cloud publishes
+- [ ] Verified scan rate matches expected
+- [ ] Verified diagnostics report correctly
+- [ ] Tested with real sensor
+- [ ] Tested rosbag recording of Nebula packet output
+- [ ] Tested rosbag replay with `launch_hw:=false`
+
+## Additional resources
+
+- Hesai implementation: `src/nebula_hesai` - Full reference implementation
+- Velodyne implementation: `src/nebula_velodyne` - Alternative reference
+- Core components: `src/nebula_core` - Reusable building blocks
+- Point types: See [`docs/point_types.md`](point_types.md)
+- Parameters: See [`docs/parameters.md`](parameters.md)
+
+## Getting help
+
+- Check existing sensor implementations for examples
+- Consult the [API reference](https://tier4.github.io/nebula/api_reference/)
+- Ask questions in [GitHub Issues](https://github.com/tier4/nebula/issues)
diff --git a/docs/requirements.txt b/docs/requirements.txt
index 3e3dab3a5..83e54680d 100644
--- a/docs/requirements.txt
+++ b/docs/requirements.txt
@@ -1,6 +1,7 @@
-mkdocs==1.6.1
-mkdocs-drawio>=1.8.2
-mkdoxy==1.2.8
-zensical==0.0.15
+mkdocs>=1.6.1,<2.0.0
+mkdocs-drawio>=1.13.0,<2.0.0
+mkdoxy>=1.2.8,<2.0.0
+pymdown-extensions
+zensical>=0.0.15,<1.0.0
tabulate
lxml
diff --git a/docs/tutorials.md b/docs/tutorials.md
index f526027ea..78f6cad90 100644
--- a/docs/tutorials.md
+++ b/docs/tutorials.md
@@ -1,4 +1,4 @@
# Nebula tutorials
WIP - we are currently working on making tutorials for Nebula development, so please check back soon!
-In the meantime, check out the [tutorial branch](https://github.com/tier4/nebula/tree/tutorial).
+In the meantime, check out the [integration guide](integration_guide.md).
diff --git a/scripts/mkdoxy_gen.yml b/scripts/mkdoxy_gen.yml
index cbfe0abed..09749885e 100644
--- a/scripts/mkdoxy_gen.yml
+++ b/scripts/mkdoxy_gen.yml
@@ -79,6 +79,22 @@ plugins:
ENABLE_PREPROCESSING: true
MACRO_EXPANSION: true
+ sample:
+ src-dirs: >
+ src/nebula_sample/nebula_sample_common/include
+ src/nebula_sample/nebula_sample_decoders/include
+ src/nebula_sample/nebula_sample_hw_interfaces/include
+ src/nebula_sample/nebula_sample/include
+ api-path: .
+ full-doc: true
+ doxy-cfg:
+ FILE_PATTERNS: "*.hpp *.h"
+ RECURSIVE: true
+ EXTRACT_ALL: true
+ INLINE_SOURCES: true
+ ENABLE_PREPROCESSING: true
+ MACRO_EXPANSION: true
+
save-api: .mkdoxy
full-doc: true
debug: false
diff --git a/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_ars548_hw_interface.hpp b/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_ars548_hw_interface.hpp
index 76168280d..39231ae06 100644
--- a/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_ars548_hw_interface.hpp
+++ b/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_ars548_hw_interface.hpp
@@ -16,7 +16,7 @@
#define NEBULA_CONTINENTAL_ARS548_HW_INTERFACE_H
#include "nebula_core_common/nebula_status.hpp"
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp"
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
#include
#include
diff --git a/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_srr520_hw_interface.hpp b/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_srr520_hw_interface.hpp
index 29c4d46dd..65d7c4df5 100644
--- a/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_srr520_hw_interface.hpp
+++ b/src/nebula_continental/nebula_continental_hw_interfaces/include/nebula_continental_hw_interfaces/continental_srr520_hw_interface.hpp
@@ -15,7 +15,7 @@
#ifndef NEBULA_CONTINENTAL_SRR520_HW_INTERFACE_H
#define NEBULA_CONTINENTAL_SRR520_HW_INTERFACE_H
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"
+#include "nebula_core_hw_interfaces/nebula_hw_interface_base.hpp"
#include
#include
diff --git a/src/nebula_continental/nebula_continental_hw_interfaces/src/continental_ars548_hw_interface.cpp b/src/nebula_continental/nebula_continental_hw_interfaces/src/continental_ars548_hw_interface.cpp
index ff3362dbf..846c2eae3 100644
--- a/src/nebula_continental/nebula_continental_hw_interfaces/src/continental_ars548_hw_interface.cpp
+++ b/src/nebula_continental/nebula_continental_hw_interfaces/src/continental_ars548_hw_interface.cpp
@@ -15,7 +15,7 @@
#include "nebula_continental_hw_interfaces/continental_ars548_hw_interface.hpp"
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp"
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
#include
diff --git a/src/nebula_core/nebula_core_common/CMakeLists.txt b/src/nebula_core/nebula_core_common/CMakeLists.txt
index c512267d4..272c601d6 100644
--- a/src/nebula_core/nebula_core_common/CMakeLists.txt
+++ b/src/nebula_core/nebula_core_common/CMakeLists.txt
@@ -28,6 +28,15 @@ endif()
install(TARGETS nebula_core_common EXPORT export_nebula_core_common)
install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME})
+if(BUILD_TESTING OR BUILD_EXAMPLES)
+ add_library(
+ nebula_core_common_examples OBJECT
+ examples/expected_usage_example.cpp
+ examples/logger_integration_usage_example.cpp
+ examples/angle_utilities_usage_example.cpp)
+ target_link_libraries(nebula_core_common_examples PRIVATE nebula_core_common)
+endif()
+
ament_export_include_directories("include/${PROJECT_NAME}")
ament_export_targets(export_nebula_core_common)
diff --git a/src/nebula_core/nebula_core_common/examples/angle_utilities_usage_example.cpp b/src/nebula_core/nebula_core_common/examples/angle_utilities_usage_example.cpp
new file mode 100644
index 000000000..3d6d4ab87
--- /dev/null
+++ b/src/nebula_core/nebula_core_common/examples/angle_utilities_usage_example.cpp
@@ -0,0 +1,49 @@
+// Copyright 2026 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+// # --8<-- [start:include]
+#include "nebula_core_common/nebula_common.hpp"
+#include "nebula_core_common/util/angles.hpp"
+// # --8<-- [end:include]
+
+#include
+#include
+
+namespace nebula::drivers::examples
+{
+
+void angle_utilities_usage_example()
+{
+ // # --8<-- [start:usage]
+ const float azimuth_deg = 45.0F;
+
+ const auto azimuth_rad = deg2rad(azimuth_deg);
+ const float fov_min_rad = 0.0F;
+ const auto fov_max_rad = deg2rad(90.0F);
+ assert(angle_is_between(fov_min_rad, fov_max_rad, azimuth_rad));
+
+ // Normalize any angle to [0, 360) or [0, 2pi) (depending on the chosen max_angle):
+ const float azimuth_deg_norm = normalize_angle(azimuth_deg, 360.0F);
+ assert(azimuth_deg_norm >= 0.0F && azimuth_deg_norm < 360.0F);
+ const float azimuth_rad_norm = normalize_angle(azimuth_rad, 2 * M_PI);
+ assert(azimuth_rad_norm >= 0.0F && azimuth_rad_norm < 2 * M_PI);
+ // # --8<-- [end:usage]
+
+ (void)fov_min_rad;
+ (void)fov_max_rad;
+ (void)azimuth_deg_norm;
+ (void)azimuth_rad_norm;
+}
+
+} // namespace nebula::drivers::examples
diff --git a/src/nebula_core/nebula_core_common/examples/expected_usage_example.cpp b/src/nebula_core/nebula_core_common/examples/expected_usage_example.cpp
new file mode 100644
index 000000000..4b7a26039
--- /dev/null
+++ b/src/nebula_core/nebula_core_common/examples/expected_usage_example.cpp
@@ -0,0 +1,47 @@
+// Copyright 2026 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+// # --8<-- [start:include]
+#include "nebula_core_common/util/expected.hpp"
+// # --8<-- [end:include]
+
+#include
+#include
+#include
+
+struct Config
+{
+ std::string required_field;
+ int percentage_field{0};
+};
+
+// # --8<-- [start:usage]
+enum class ValidationError : uint8_t {
+ MissingField,
+ OutOfRange,
+};
+
+nebula::util::expected validate(const Config & config)
+{
+ if (config.required_field.empty()) {
+ return ValidationError::MissingField;
+ }
+
+ if (config.percentage_field < 0 || config.percentage_field > 100) {
+ return ValidationError::OutOfRange;
+ }
+
+ return std::monostate{};
+}
+// # --8<-- [end:usage]
diff --git a/src/nebula_core/nebula_core_common/examples/logger_integration_usage_example.cpp b/src/nebula_core/nebula_core_common/examples/logger_integration_usage_example.cpp
new file mode 100644
index 000000000..cc6181384
--- /dev/null
+++ b/src/nebula_core/nebula_core_common/examples/logger_integration_usage_example.cpp
@@ -0,0 +1,48 @@
+// Copyright 2026 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+// # --8<-- [start:include]
+#include "nebula_core_common/loggers/console_logger.hpp"
+#include "nebula_core_common/loggers/logger.hpp"
+// # --8<-- [end:include]
+
+#include
+#include
+
+using nebula::drivers::loggers::ConsoleLogger;
+using nebula::drivers::loggers::Logger;
+
+// # --8<-- [start:usage]
+class SomeModule
+{
+private:
+ std::shared_ptr logger_;
+
+public:
+ explicit SomeModule(const std::shared_ptr & logger) : logger_(logger) {}
+
+ void do_something() { logger_->info("Doing something important"); }
+};
+
+int main()
+{
+ auto logger = std::make_shared("MyApp");
+ SomeModule module(logger->child("SomeModule"));
+ module.do_something();
+ return 0;
+}
+
+// Output:
+// [MyApp.SomeModule][INFO] Doing something important
+// # --8<-- [end:usage]
diff --git a/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/angles.hpp b/src/nebula_core/nebula_core_common/include/nebula_core_common/util/angles.hpp
similarity index 100%
rename from src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/angles.hpp
rename to src/nebula_core/nebula_core_common/include/nebula_core_common/util/angles.hpp
diff --git a/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/blockage_mask.hpp b/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/blockage_mask.hpp
index c165a9293..18bd66f49 100644
--- a/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/blockage_mask.hpp
+++ b/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/blockage_mask.hpp
@@ -14,7 +14,7 @@
#pragma once
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include
#include
diff --git a/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/downsample_mask.hpp b/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/downsample_mask.hpp
index 55b64d7f8..f6703b35b 100644
--- a/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/downsample_mask.hpp
+++ b/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/point_filters/downsample_mask.hpp
@@ -14,7 +14,7 @@
#pragma once
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include
#include
diff --git a/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/scan_cutter.hpp b/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/scan_cutter.hpp
index 255aabfe3..029e093fa 100644
--- a/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/scan_cutter.hpp
+++ b/src/nebula_core/nebula_core_decoders/include/nebula_core_decoders/scan_cutter.hpp
@@ -14,7 +14,7 @@
#pragma once
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include "nebula_core_decoders/scan_cutter/fsm_cut_at_fov_end.hpp"
#include "nebula_core_decoders/scan_cutter/fsm_cut_in_fov.hpp"
#include "nebula_core_decoders/scan_cutter/types.hpp"
diff --git a/src/nebula_core/nebula_core_decoders/tests/point_filters/test_downsample_mask.cpp b/src/nebula_core/nebula_core_decoders/tests/point_filters/test_downsample_mask.cpp
index 62e92ffaa..b2ec7772a 100644
--- a/src/nebula_core/nebula_core_decoders/tests/point_filters/test_downsample_mask.cpp
+++ b/src/nebula_core/nebula_core_decoders/tests/point_filters/test_downsample_mask.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include "nebula_core_decoders/point_filters/downsample_mask.hpp"
#include
diff --git a/src/nebula_core/nebula_core_decoders/tests/test_angles.cpp b/src/nebula_core/nebula_core_decoders/tests/test_angles.cpp
index d9c5039ca..bfaa189a3 100644
--- a/src/nebula_core/nebula_core_decoders/tests/test_angles.cpp
+++ b/src/nebula_core/nebula_core_decoders/tests/test_angles.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include
diff --git a/src/nebula_core/nebula_core_hw_interfaces/CMakeLists.txt b/src/nebula_core/nebula_core_hw_interfaces/CMakeLists.txt
index 32f4c5a4a..95f87a323 100644
--- a/src/nebula_core/nebula_core_hw_interfaces/CMakeLists.txt
+++ b/src/nebula_core/nebula_core_hw_interfaces/CMakeLists.txt
@@ -30,6 +30,13 @@ if(BUILD_TESTING)
target_link_libraries(test_udp nebula_core_common::nebula_core_common)
endif()
+if(BUILD_TESTING OR BUILD_EXAMPLES)
+ add_library(nebula_core_hw_interfaces_examples OBJECT
+ examples/udp_socket_usage_example.cpp)
+ target_link_libraries(nebula_core_hw_interfaces_examples
+ PRIVATE nebula_core_hw_interfaces)
+endif()
+
ament_export_targets(export_nebula_core_hw_interfaces)
ament_export_dependencies(nebula_core_common)
diff --git a/src/nebula_core/nebula_core_hw_interfaces/examples/udp_socket_usage_example.cpp b/src/nebula_core/nebula_core_hw_interfaces/examples/udp_socket_usage_example.cpp
new file mode 100644
index 000000000..e2d684157
--- /dev/null
+++ b/src/nebula_core/nebula_core_hw_interfaces/examples/udp_socket_usage_example.cpp
@@ -0,0 +1,41 @@
+// Copyright 2026 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+// # --8<-- [start:include]
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
+// # --8<-- [end:include]
+
+#include
+#include
+
+int main()
+{
+ // # --8<-- [start:usage]
+ using nebula::drivers::connections::UdpSocket;
+ auto socket = UdpSocket::Builder("192.168.1.10", 9000)
+ .set_socket_buffer_size(10'000'000)
+ .limit_to_sender("192.168.10.20", 7000)
+ .bind();
+
+ socket.subscribe([](const std::vector & data, const UdpSocket::RxMetadata & metadata) {
+ (void)data;
+ (void)metadata;
+ // Process received data and metadata here. This callback will be executed in the socket's
+ // receive thread.
+ });
+
+ socket.unsubscribe();
+ // # --8<-- [end:usage]
+ return 0;
+}
diff --git a/src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp b/src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/connections/udp.hpp
similarity index 100%
rename from src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp
rename to src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/connections/udp.hpp
diff --git a/src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp b/src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/nebula_hw_interface_base.hpp
similarity index 100%
rename from src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp
rename to src/nebula_core/nebula_core_hw_interfaces/include/nebula_core_hw_interfaces/nebula_hw_interface_base.hpp
diff --git a/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp.cpp b/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp.cpp
index ebdd7eeb2..db7eb58a7 100644
--- a/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp.cpp
+++ b/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp.cpp
@@ -2,7 +2,7 @@
#include "common/test_udp/utils.hpp"
#include "nebula_core_common/util/expected.hpp"
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp"
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
#include
#include
diff --git a/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp/utils.hpp b/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp/utils.hpp
index 9ae90de76..244e4a25a 100644
--- a/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp/utils.hpp
+++ b/src/nebula_core/nebula_core_hw_interfaces/test/common/test_udp/utils.hpp
@@ -14,7 +14,7 @@
#pragma once
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp"
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
#include
#include
diff --git a/src/nebula_core/nebula_core_ros/CMakeLists.txt b/src/nebula_core/nebula_core_ros/CMakeLists.txt
index b64376482..fb8a89860 100644
--- a/src/nebula_core/nebula_core_ros/CMakeLists.txt
+++ b/src/nebula_core/nebula_core_ros/CMakeLists.txt
@@ -20,6 +20,16 @@ install(
LIBRARY DESTINATION lib)
install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME})
+if(BUILD_TESTING OR BUILD_EXAMPLES)
+ add_library(
+ nebula_core_ros_examples OBJECT
+ examples/diagnostic_integration_usage_example.cpp
+ examples/point_types_usage_example.cpp)
+ target_link_libraries(nebula_core_ros_examples PRIVATE nebula_core_ros)
+ ament_target_dependencies(nebula_core_ros_examples PUBLIC
+ diagnostic_msgs diagnostic_updater rclcpp sensor_msgs pcl_conversions)
+endif()
+
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gtest REQUIRED)
diff --git a/src/nebula_core/nebula_core_ros/examples/diagnostic_integration_usage_example.cpp b/src/nebula_core/nebula_core_ros/examples/diagnostic_integration_usage_example.cpp
new file mode 100644
index 000000000..d377f74a3
--- /dev/null
+++ b/src/nebula_core/nebula_core_ros/examples/diagnostic_integration_usage_example.cpp
@@ -0,0 +1,64 @@
+// Copyright 2026 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+// # --8<-- [start:include]
+#include "nebula_core_ros/diagnostics/liveness_monitor.hpp"
+#include "nebula_core_ros/diagnostics/rate_bound_status.hpp"
+// # --8<-- [end:include]
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+namespace nebula::ros::examples
+{
+
+using custom_diagnostic_tasks::RateBoundStatus;
+using custom_diagnostic_tasks::RateBoundStatusParam;
+using std::chrono_literals::operator""ms;
+
+// # --8<-- [start:usage]
+class MyNode : public rclcpp::Node
+{
+public:
+ MyNode() : Node("diagnostic_integration_usage_example")
+ {
+ updater_.add(publish_rate_diag_);
+ updater_.add(liveness_diag_);
+ }
+
+ void on_packet_received(const std::array & packet)
+ {
+ liveness_diag_.tick();
+
+ if (packet[0] == 1 /* some condition indicating we should publish */) {
+ // publish something here
+ publish_rate_diag_.tick();
+ }
+ }
+
+private:
+ diagnostic_updater::Updater updater_{this, 0.1};
+ RateBoundStatus publish_rate_diag_{
+ this, RateBoundStatusParam{9, 11}, RateBoundStatusParam{8, 12}};
+ LivenessMonitor liveness_diag_{"packet_receive", this, 10ms};
+};
+// # --8<-- [end:usage]
+
+} // namespace nebula::ros::examples
diff --git a/src/nebula_core/nebula_core_ros/examples/point_types_usage_example.cpp b/src/nebula_core/nebula_core_ros/examples/point_types_usage_example.cpp
new file mode 100644
index 000000000..bfc956bff
--- /dev/null
+++ b/src/nebula_core/nebula_core_ros/examples/point_types_usage_example.cpp
@@ -0,0 +1,63 @@
+// Copyright 2026 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "nebula_core_common/nebula_common.hpp"
+// # --8<-- [start:include]
+#include "nebula_core_common/point_types.hpp"
+// # --8<-- [end:include]
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+
+namespace nebula::ros::examples
+{
+
+void point_types_usage_example()
+{
+ // # --8<-- [start:usage]
+ auto cloud = std::make_shared();
+ cloud->reserve(2);
+
+ nebula::drivers::NebulaPoint point{};
+ point.x = 1.0F;
+ point.y = 2.0F;
+ point.z = 3.0F;
+ point.intensity = 10U;
+ point.return_type = static_cast(nebula::drivers::ReturnType::STRONGEST);
+ point.channel = 5U;
+ point.azimuth = 0.0F;
+ point.elevation = 0.1F;
+ point.distance = 3.74F;
+ point.time_stamp = 42U;
+ cloud->push_back(point);
+
+ const auto cloud_xyzir = nebula::drivers::convert_point_xyzircaedt_to_point_xyzir(cloud);
+ assert(cloud_xyzir != nullptr);
+
+ sensor_msgs::msg::PointCloud2 cloud_ros{};
+ pcl::toROSMsg(*cloud_xyzir, cloud_ros);
+
+ // my_publisher->publish(cloud_ros);
+ // # --8<-- [end:usage]
+
+ (void)cloud;
+ (void)cloud_xyzir;
+}
+
+} // namespace nebula::ros::examples
diff --git a/src/nebula_core/nebula_core_ros/include/nebula_core_ros/parameter_descriptors.hpp b/src/nebula_core/nebula_core_ros/include/nebula_core_ros/parameter_descriptors.hpp
index 8d5355c35..9611c38a5 100644
--- a/src/nebula_core/nebula_core_ros/include/nebula_core_ros/parameter_descriptors.hpp
+++ b/src/nebula_core/nebula_core_ros/include/nebula_core_ros/parameter_descriptors.hpp
@@ -16,6 +16,7 @@
#include
#include
+#include
#include
#include
@@ -52,4 +53,14 @@ bool get_param(const std::vector & p, const std::string & nam
return false;
}
+template
+T ensure_and_get_parameter(rclcpp::Node & node, const std::string & name)
+{
+ if (!node.has_parameter(name)) {
+ node.declare_parameter(name);
+ }
+
+ return node.get_parameter(name);
+}
+
} // namespace nebula::ros
diff --git a/src/nebula_core/nebula_core_ros/package.xml b/src/nebula_core/nebula_core_ros/package.xml
index 0ab508f83..59e7b5edb 100644
--- a/src/nebula_core/nebula_core_ros/package.xml
+++ b/src/nebula_core/nebula_core_ros/package.xml
@@ -16,6 +16,7 @@
diagnostic_msgs
diagnostic_updater
nebula_core_common
+ pcl_conversions
rclcpp
rosbag2_storage
diff --git a/src/nebula_hesai/nebula_hesai/include/nebula_hesai/hesai_ros_wrapper.hpp b/src/nebula_hesai/nebula_hesai/include/nebula_hesai/hesai_ros_wrapper.hpp
index 482eba2d8..fc13208a4 100644
--- a/src/nebula_hesai/nebula_hesai/include/nebula_hesai/hesai_ros_wrapper.hpp
+++ b/src/nebula_hesai/nebula_hesai/include/nebula_hesai/hesai_ros_wrapper.hpp
@@ -16,7 +16,7 @@
#include "nebula_core_common/nebula_common.hpp"
#include "nebula_core_common/nebula_status.hpp"
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp"
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
#include "nebula_core_ros/sync_tooling/sync_tooling_worker.hpp"
#include "nebula_hesai/decoder_wrapper.hpp"
#include "nebula_hesai/hw_interface_wrapper.hpp"
diff --git a/src/nebula_hesai/nebula_hesai/src/hesai_ros_wrapper.cpp b/src/nebula_hesai/nebula_hesai/src/hesai_ros_wrapper.cpp
index 5f92f2407..c28643b70 100644
--- a/src/nebula_hesai/nebula_hesai/src/hesai_ros_wrapper.cpp
+++ b/src/nebula_hesai/nebula_hesai/src/hesai_ros_wrapper.cpp
@@ -5,10 +5,10 @@
#include "nebula_core_ros/parameter_descriptors.hpp"
#include
+#include
#include
#include
#include
-#include
#include
#include
diff --git a/src/nebula_hesai/nebula_hesai/tests/hesai_ros_scan_cutting_test_main.cpp b/src/nebula_hesai/nebula_hesai/tests/hesai_ros_scan_cutting_test_main.cpp
index acacba1c8..aeeccdc43 100644
--- a/src/nebula_hesai/nebula_hesai/tests/hesai_ros_scan_cutting_test_main.cpp
+++ b/src/nebula_hesai/nebula_hesai/tests/hesai_ros_scan_cutting_test_main.cpp
@@ -6,7 +6,7 @@
#include
#include
-#include
+#include
#include
#include
#include
diff --git a/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_calibration_based.hpp b/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_calibration_based.hpp
index 86027d3f1..fa9044c42 100644
--- a/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_calibration_based.hpp
+++ b/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_calibration_based.hpp
@@ -14,7 +14,7 @@
#pragma once
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include "nebula_hesai_common/hesai_common.hpp"
#include "nebula_hesai_decoders/decoders/angle_corrector.hpp"
diff --git a/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_correction_based.hpp b/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_correction_based.hpp
index b04e507c7..983a6bea4 100644
--- a/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_correction_based.hpp
+++ b/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/angle_corrector_correction_based.hpp
@@ -14,7 +14,7 @@
#pragma once
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include "nebula_hesai_common/hesai_common.hpp"
#include "nebula_hesai_decoders/decoders/angle_corrector.hpp"
diff --git a/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/pandar_40.hpp b/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/pandar_40.hpp
index 60b1fa881..36481b8cf 100644
--- a/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/pandar_40.hpp
+++ b/src/nebula_hesai/nebula_hesai_decoders/include/nebula_hesai_decoders/decoders/pandar_40.hpp
@@ -14,7 +14,7 @@
#pragma once
-#include "nebula_core_decoders/angles.hpp"
+#include "nebula_core_common/util/angles.hpp"
#include "nebula_hesai_decoders/decoders/hesai_packet.hpp"
#include "nebula_hesai_decoders/decoders/hesai_sensor.hpp"
diff --git a/src/nebula_hesai/nebula_hesai_hw_interfaces/include/nebula_hesai_hw_interfaces/hesai_hw_interface.hpp b/src/nebula_hesai/nebula_hesai_hw_interfaces/include/nebula_hesai_hw_interfaces/hesai_hw_interface.hpp
index 02a077f4a..890a92607 100644
--- a/src/nebula_hesai/nebula_hesai_hw_interfaces/include/nebula_hesai_hw_interfaces/hesai_hw_interface.hpp
+++ b/src/nebula_hesai/nebula_hesai_hw_interfaces/include/nebula_hesai_hw_interfaces/hesai_hw_interface.hpp
@@ -17,7 +17,7 @@
// Have to define macros to silence warnings about deprecated headers being used by
// boost/property_tree/ in some versions of boost.
// See: https://github.com/boostorg/property_tree/issues/51
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp"
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
#include
diff --git a/src/nebula_hesai/nebula_hesai_hw_interfaces/src/hesai_hw_interface.cpp b/src/nebula_hesai/nebula_hesai_hw_interfaces/src/hesai_hw_interface.cpp
index f01c69f3b..19d1830f9 100644
--- a/src/nebula_hesai/nebula_hesai_hw_interfaces/src/hesai_hw_interface.cpp
+++ b/src/nebula_hesai/nebula_hesai_hw_interfaces/src/hesai_hw_interface.cpp
@@ -5,7 +5,7 @@
#include "nebula_core_common/loggers/logger.hpp"
#include "nebula_core_common/nebula_common.hpp"
#include "nebula_core_common/nebula_status.hpp"
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/connections/udp.hpp"
+#include "nebula_core_hw_interfaces/connections/udp.hpp"
#include "nebula_hesai_common/hesai_common.hpp"
#include "nebula_hesai_common/hesai_status.hpp"
#include "nebula_hesai_hw_interfaces/hesai_cmd_response.hpp"
diff --git a/src/nebula_sample/README.md b/src/nebula_sample/README.md
new file mode 100644
index 000000000..3ef3468a8
--- /dev/null
+++ b/src/nebula_sample/README.md
@@ -0,0 +1,70 @@
+# Nebula sample sensor package
+
+A template sensor package for the Nebula LiDAR driver framework. This package provides a minimal, working example that developers can copy and modify to add support for new sensors.
+
+## Purpose
+
+This package serves as a starting point for adding new sensor support to Nebula. It includes all necessary components with empty/stub implementations that compile and run without errors.
+
+## Package structure
+
+The sample sensor consists of four packages:
+
+- **nebula_sample_common** - Common definitions and configuration structures
+- **nebula_sample_decoders** - Packet decoder and driver implementation
+- **nebula_sample_hw_interfaces** - Hardware interface for sensor communication
+- **nebula_sample** - ROS 2 wrapper and launch files
+
+## Building
+
+```bash
+colcon build --packages-up-to nebula_sample
+```
+
+## Running
+
+```bash
+# Online mode (with hardware)
+ros2 launch nebula_sample nebula_sample.launch.xml
+# Offline mode (replay from rosbag)
+ros2 launch nebula_sample nebula_sample.launch.xml launch_hw:=false
+```
+
+## Using as a template
+
+For detailed instructions on how to use this package as a template for adding a new sensor, please refer to the [Integration guide](../../docs/integration_guide.md).
+
+The guide covers:
+
+1. Cloning and renaming the package
+2. Implementing sensor-specific logic
+3. Verifying the new implementation
+
+## Key components
+
+### Configuration (`*_common`)
+
+- `SampleSensorConfiguration` - Sensor-specific settings
+
+### Decoder (`*_decoders`)
+
+- `SampleDecoder` - Packet decoder implementation
+- `PacketDecodeResult` - Decoder output containing metadata/error and performance counters
+- `DecodeError` - Decoder error codes for packet handling failures
+
+### Hardware interface (`*_hw_interfaces`)
+
+- `SampleHwInterface` - Sensor communication interface
+
+### ROS wrapper
+
+- `SampleRosWrapper` - ROS 2 node wrapping the driver
+- Point cloud publisher on `/points`
+- Packet publish/replay topic on `/packets` (`nebula_msgs/msg/NebulaPackets`) depending on
+ runtime mode (`launch_hw` parameter)
+
+## Reference implementation
+
+This package provides a template structure for adding new sensor support. For complete examples, refer to existing sensor packages like `nebula_hesai` or `nebula_velodyne`.
+
+**For detailed integration instructions, see the [Integration guide](../../docs/integration_guide.md) in the documentation.**
diff --git a/src/nebula_sample/nebula_sample/CMakeLists.txt b/src/nebula_sample/nebula_sample/CMakeLists.txt
new file mode 100644
index 000000000..6da37e514
--- /dev/null
+++ b/src/nebula_sample/nebula_sample/CMakeLists.txt
@@ -0,0 +1,70 @@
+cmake_minimum_required(VERSION 3.20)
+project(nebula_sample)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+if(BUILD_TESTING OR BUILD_EXAMPLES)
+ find_package(PCL REQUIRED components common io)
+else()
+ find_package(PCL REQUIRED components common)
+endif()
+
+# Sample
+add_library(
+ sample_ros_wrapper SHARED
+ src/sample_ros_wrapper.cpp)
+
+target_include_directories(
+ sample_ros_wrapper
+ PUBLIC $
+ $)
+
+target_link_libraries(
+ sample_ros_wrapper
+ PUBLIC nebula_sample_decoders::nebula_sample_decoders
+ nebula_sample_hw_interfaces::nebula_sample_hw_interfaces
+ nebula_core_ros::nebula_core_ros
+ pcl_common)
+ament_target_dependencies(
+ sample_ros_wrapper
+ PUBLIC
+ diagnostic_updater
+ nebula_msgs
+ rclcpp
+ rclcpp_components
+ sensor_msgs
+ std_msgs
+ pcl_conversions)
+
+rclcpp_components_register_node(sample_ros_wrapper PLUGIN "nebula::ros::SampleRosWrapper"
+ EXECUTABLE sample_ros_wrapper_node)
+
+install(
+ TARGETS sample_ros_wrapper
+ EXPORT export_sample_ros_wrapper
+ LIBRARY DESTINATION lib)
+install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME})
+
+install(DIRECTORY config launch DESTINATION share/${PROJECT_NAME})
+
+ament_export_include_directories("include/${PROJECT_NAME}")
+ament_export_targets(export_sample_ros_wrapper)
+
+ament_export_dependencies(
+ PCL
+ nebula_core_common
+ nebula_sample_common
+ nebula_core_decoders
+ nebula_sample_decoders
+ nebula_core_hw_interfaces
+ nebula_sample_hw_interfaces
+ nebula_core_ros
+ diagnostic_updater
+ nebula_msgs
+ rclcpp_components
+ sensor_msgs
+ std_msgs
+ pcl_conversions)
+
+ament_package()
diff --git a/src/nebula_sample/nebula_sample/config/sample_sensor.param.yaml b/src/nebula_sample/nebula_sample/config/sample_sensor.param.yaml
new file mode 100644
index 000000000..e0ab6dd04
--- /dev/null
+++ b/src/nebula_sample/nebula_sample/config/sample_sensor.param.yaml
@@ -0,0 +1,38 @@
+# Sample Sensor ROS 2 Parameters
+# This file contains example parameters for the Sample LiDAR sensor.
+# Copy and modify this file for your specific sensor model.
+
+/**:
+ ros__parameters:
+ # ROS wrapper configuration
+ sensor_model: SampleSensor
+ launch_hw: true
+ frame_id: sample_lidar
+
+ # Network configuration
+ connection:
+ sensor_ip: 192.168.1.201
+ host_ip: 192.168.1.100
+ data_port: 2368
+
+ # Decoder configuration
+ fov:
+ azimuth:
+ min_deg: 0.0
+ max_deg: 360.0
+ elevation:
+ min_deg: -15.0
+ max_deg: 15.0
+
+ # Diagnostics configuration
+ diagnostics:
+ pointcloud_publish_rate:
+ frequency_ok:
+ min_hz: 9.0
+ max_hz: 11.0
+ frequency_warn:
+ min_hz: 8.0
+ max_hz: 12.0
+ num_frame_transition: 1
+ packet_liveness:
+ timeout_ms: 10
diff --git a/src/nebula_sample/nebula_sample/include/nebula_sample/sample_ros_wrapper.hpp b/src/nebula_sample/nebula_sample/include/nebula_sample/sample_ros_wrapper.hpp
new file mode 100644
index 000000000..b214c543b
--- /dev/null
+++ b/src/nebula_sample/nebula_sample/include/nebula_sample/sample_ros_wrapper.hpp
@@ -0,0 +1,176 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NEBULA_SAMPLE_ROS_WRAPPER_HPP
+#define NEBULA_SAMPLE_ROS_WRAPPER_HPP
+
+#include "nebula_sample_decoders/sample_decoder.hpp"
+#include "nebula_sample_hw_interfaces/sample_hw_interface.hpp"
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace nebula::ros
+{
+
+struct ConfigError
+{
+ enum class Code : uint8_t {
+ PARAMETER_DECLARATION_FAILED, ///< Parameter declaration/read failed.
+ PARAMETER_VALIDATION_FAILED, ///< Parameter value failed semantic validation.
+ };
+
+ Code code;
+ std::string message;
+};
+
+/// @brief Read and validate sample driver configuration from ROS parameters.
+/// @param node Node used to declare/read parameters.
+/// @return Parsed SampleSensorConfiguration or ConfigError on validation failure.
+util::expected load_config_from_ros_parameters(
+ rclcpp::Node & node);
+
+/// @brief ROS 2 wrapper for the Sample LiDAR driver
+/// @details This node bridges the C++ driver with ROS 2.
+/// Responsibilities:
+/// - Turn ROS 2 parameters into sensor configuration
+/// - Initialize decoder and hardware interface
+/// - Forward packets from HW interface and pass to decoder
+/// - Convert decoded point clouds to ROS messages
+/// - Publish point clouds on ROS topics
+/// - Optionally: provide services for runtime configuration
+class SampleRosWrapper : public rclcpp::Node
+{
+public:
+ struct Error
+ {
+ enum class Code : uint8_t {
+ HW_INTERFACE_NOT_INITIALIZED, ///< Stream start requested while HW interface is absent.
+ HW_STREAM_START_FAILED, ///< Underlying HW interface failed to start.
+ };
+
+ Code code;
+ std::string message;
+ };
+
+ /// @brief Construct the ROS 2 node and initialize decoder + optional HW stream.
+ /// @param options Standard ROS 2 component/node options.
+ /// @throws std::runtime_error on invalid configuration or startup failures.
+ explicit SampleRosWrapper(const rclcpp::NodeOptions & options);
+ ~SampleRosWrapper() override;
+
+private:
+ /// @brief Resources used only when launch_hw is true.
+ struct OnlineMode
+ {
+ explicit OnlineMode(drivers::ConnectionConfiguration connection_configuration)
+ : hw_interface(std::move(connection_configuration))
+ {
+ }
+
+ drivers::SampleHwInterface hw_interface;
+ rclcpp::Publisher::SharedPtr packets_pub;
+ std::unique_ptr current_scan_packets_msg{
+ std::make_unique()};
+ };
+
+ /// @brief Resources used only when launch_hw is false.
+ struct OfflineMode
+ {
+ rclcpp::Subscription::SharedPtr packets_sub;
+ };
+
+ struct Publishers
+ {
+ rclcpp::Publisher::SharedPtr points;
+ rclcpp::Publisher::SharedPtr receive_duration_ms;
+ rclcpp::Publisher::SharedPtr decode_duration_ms;
+ rclcpp::Publisher::SharedPtr publish_duration_ms;
+ };
+
+ struct Diagnostics
+ {
+ explicit Diagnostics(rclcpp::Node * node) : updater(node) {}
+
+ diagnostic_updater::Updater updater;
+ std::optional publish_rate;
+ std::optional packet_liveness;
+ };
+
+ /// @brief Publish a decoded pointcloud to ROS.
+ /// @param pointcloud Decoded pointcloud from the decoder.
+ /// @param timestamp_s Scan timestamp in seconds, epoch time.
+ void publish_pointcloud_callback(
+ const drivers::NebulaPointCloudPtr & pointcloud, double timestamp_s);
+
+ /// @brief Process one received UDP packet through the decoder pipeline.
+ /// @param packet Raw packet payload.
+ /// @param metadata Transport metadata provided by the UDP receiver.
+ void receive_cloud_packet_callback(
+ const std::vector & packet,
+ const drivers::connections::UdpSocket::RxMetadata & metadata);
+
+ /// @brief Process one replayed NebulaPackets message.
+ /// @param packets_msg Packed scan data used for software-only replay.
+ void receive_packets_message_callback(
+ std::unique_ptr packets_msg);
+
+ /// @brief Configure common diagnostics used by most sensor integrations.
+ void initialize_diagnostics();
+
+ /// @brief Decode one packet and publish relevant outputs.
+ /// @param packet Raw packet payload.
+ /// @param receive_duration_ns Time spent in transport receive path for this packet.
+ void process_packet(const std::vector & packet, uint64_t receive_duration_ns);
+
+ /// @brief Publish receive/decode/publish debug durations.
+ /// @param receive_duration_ns Time spent in transport receive path.
+ /// @param decode_duration_ns Time spent decoding one packet.
+ /// @param publish_duration_ns Time spent publishing one completed scan callback.
+ void publish_debug_durations(
+ uint64_t receive_duration_ns, uint64_t decode_duration_ns, uint64_t publish_duration_ns) const;
+
+ static const char * to_cstr(Error::Code code);
+
+ drivers::SampleSensorConfiguration config_;
+ std::string frame_id_;
+ Publishers publishers_;
+ Diagnostics diagnostics_;
+
+ std::optional decoder_;
+ /// @brief Exactly one runtime mode is active: offline replay or online hardware mode.
+ /// @details During construction, neither mode is active.
+ std::variant runtime_mode_;
+};
+
+} // namespace nebula::ros
+
+#endif // NEBULA_SAMPLE_ROS_WRAPPER_HPP
diff --git a/src/nebula_sample/nebula_sample/launch/nebula_sample.launch.xml b/src/nebula_sample/nebula_sample/launch/nebula_sample.launch.xml
new file mode 100644
index 000000000..868f36f4e
--- /dev/null
+++ b/src/nebula_sample/nebula_sample/launch/nebula_sample.launch.xml
@@ -0,0 +1,11 @@
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/nebula_sample/nebula_sample/package.xml b/src/nebula_sample/nebula_sample/package.xml
new file mode 100644
index 000000000..943bcf576
--- /dev/null
+++ b/src/nebula_sample/nebula_sample/package.xml
@@ -0,0 +1,31 @@
+
+
+
+ nebula_sample
+ 0.3.0
+ Nebula Sample ROS 2 Package
+ David Wong
+ Max Schmeller
+
+ Apache 2
+ TIER IV
+
+ autoware_cmake
+
+ diagnostic_updater
+ nebula_core_common
+ nebula_core_ros
+ nebula_msgs
+ nebula_sample_common
+ nebula_sample_decoders
+ nebula_sample_hw_interfaces
+ pcl_conversions
+ rclcpp
+ rclcpp_components
+ sensor_msgs
+ std_msgs
+
+
+ ament_cmake
+
+
diff --git a/src/nebula_sample/nebula_sample/src/sample_ros_wrapper.cpp b/src/nebula_sample/nebula_sample/src/sample_ros_wrapper.cpp
new file mode 100644
index 000000000..11e14f91f
--- /dev/null
+++ b/src/nebula_sample/nebula_sample/src/sample_ros_wrapper.cpp
@@ -0,0 +1,399 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "nebula_sample/sample_ros_wrapper.hpp"
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace nebula::ros
+{
+
+namespace
+{
+constexpr double k_ns_to_ms = 1e-6;
+
+uint64_t current_system_time_ns()
+{
+ return static_cast(std::chrono::duration_cast(
+ std::chrono::system_clock::now().time_since_epoch())
+ .count());
+}
+
+template
+util::expected declare_required_parameter(
+ rclcpp::Node & node, const std::string & name,
+ const rcl_interfaces::msg::ParameterDescriptor & descriptor)
+{
+ try {
+ return node.declare_parameter(name, descriptor);
+ } catch (const std::exception & e) {
+ return ConfigError{
+ ConfigError::Code::PARAMETER_DECLARATION_FAILED,
+ "Failed to declare/read parameter '" + name + "': " + e.what()};
+ }
+}
+} // namespace
+
+util::expected load_config_from_ros_parameters(
+ rclcpp::Node & node)
+{
+ drivers::SampleSensorConfiguration config{};
+
+ const auto host_ip =
+ declare_required_parameter(node, "connection.host_ip", param_read_only());
+ if (!host_ip.has_value()) {
+ return host_ip.error();
+ }
+ config.connection.host_ip = host_ip.value();
+ if (!drivers::connections::parse_ip(config.connection.host_ip).has_value()) {
+ return ConfigError{
+ ConfigError::Code::PARAMETER_VALIDATION_FAILED,
+ "Parameter 'connection.host_ip' must be a valid IPv4 address, got '" +
+ config.connection.host_ip + "'"};
+ }
+
+ const auto sensor_ip =
+ declare_required_parameter(node, "connection.sensor_ip", param_read_only());
+ if (!sensor_ip.has_value()) {
+ return sensor_ip.error();
+ }
+ config.connection.sensor_ip = sensor_ip.value();
+ if (!drivers::connections::parse_ip(config.connection.sensor_ip).has_value()) {
+ return ConfigError{
+ ConfigError::Code::PARAMETER_VALIDATION_FAILED,
+ "Parameter 'connection.sensor_ip' must be a valid IPv4 address, got '" +
+ config.connection.sensor_ip + "'"};
+ }
+
+ const auto data_port =
+ declare_required_parameter(node, "connection.data_port", param_read_only());
+ if (!data_port.has_value()) {
+ return data_port.error();
+ }
+ if (data_port.value() <= 0 || data_port.value() > 65535) {
+ return ConfigError{
+ ConfigError::Code::PARAMETER_VALIDATION_FAILED,
+ "Parameter 'connection.data_port' must be in [1, 65535], got " +
+ std::to_string(data_port.value())};
+ }
+ config.connection.data_port = static_cast(data_port.value());
+
+ const auto azimuth_min =
+ declare_required_parameter(node, "fov.azimuth.min_deg", param_read_write());
+ if (!azimuth_min.has_value()) {
+ return azimuth_min.error();
+ }
+ const auto azimuth_max =
+ declare_required_parameter(node, "fov.azimuth.max_deg", param_read_write());
+ if (!azimuth_max.has_value()) {
+ return azimuth_max.error();
+ }
+ const auto elevation_min =
+ declare_required_parameter(node, "fov.elevation.min_deg", param_read_write());
+ if (!elevation_min.has_value()) {
+ return elevation_min.error();
+ }
+ const auto elevation_max =
+ declare_required_parameter(node, "fov.elevation.max_deg", param_read_write());
+ if (!elevation_max.has_value()) {
+ return elevation_max.error();
+ }
+
+ config.fov.azimuth.start = static_cast(azimuth_min.value());
+ config.fov.azimuth.end = static_cast(azimuth_max.value());
+ config.fov.elevation.start = static_cast(elevation_min.value());
+ config.fov.elevation.end = static_cast(elevation_max.value());
+
+ return config;
+}
+
+SampleRosWrapper::SampleRosWrapper(const rclcpp::NodeOptions & options)
+: Node("nebula_sample_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)),
+ diagnostics_(this),
+ runtime_mode_(std::monostate{})
+{
+ const bool launch_hw = declare_parameter("launch_hw", true, param_read_only());
+ declare_parameter("sensor_model", "SampleSensor", param_read_only());
+ frame_id_ = declare_parameter("frame_id", "sample_lidar", param_read_write());
+
+ const auto config_or_error = load_config_from_ros_parameters(*this);
+ if (!config_or_error.has_value()) {
+ throw std::runtime_error(
+ "Invalid sample sensor configuration: " + config_or_error.error().message);
+ }
+ config_ = config_or_error.value();
+
+ publishers_.points =
+ create_publisher("points", rclcpp::SensorDataQoS());
+ publishers_.receive_duration_ms =
+ create_publisher("debug/receive_duration_ms", 10);
+ publishers_.decode_duration_ms =
+ create_publisher("debug/decode_duration_ms", 10);
+ publishers_.publish_duration_ms =
+ create_publisher("debug/publish_duration_ms", 10);
+
+ initialize_diagnostics();
+
+ decoder_.emplace(
+ config_.fov, [this](const drivers::NebulaPointCloudPtr & pointcloud, double timestamp_s) {
+ publish_pointcloud_callback(pointcloud, timestamp_s);
+ });
+
+ if (launch_hw) {
+ runtime_mode_.emplace(config_.connection);
+ auto & online_mode = std::get(runtime_mode_);
+ online_mode.packets_pub =
+ create_publisher("packets", rclcpp::SensorDataQoS());
+ const auto callback_result = online_mode.hw_interface.register_scan_callback(
+ [this](
+ const std::vector & raw_packet,
+ const drivers::connections::UdpSocket::RxMetadata & metadata) {
+ receive_cloud_packet_callback(raw_packet, metadata);
+ });
+ if (!callback_result.has_value()) {
+ const auto error = callback_result.error();
+ throw std::runtime_error(
+ "Failed to register sample sensor packet callback: " + error.message);
+ }
+
+ const auto stream_start_result = online_mode.hw_interface.sensor_interface_start();
+ if (!stream_start_result.has_value()) {
+ const auto error = stream_start_result.error();
+ throw std::runtime_error("Failed to start sample sensor stream: " + error.message);
+ }
+ } else {
+ runtime_mode_.emplace();
+ auto & offline_mode = std::get(runtime_mode_);
+ offline_mode.packets_sub = create_subscription(
+ "packets", rclcpp::SensorDataQoS(),
+ [this](std::unique_ptr packets_msg) {
+ receive_packets_message_callback(std::move(packets_msg));
+ });
+ RCLCPP_INFO(
+ get_logger(), "Hardware connection disabled, listening for packets on %s",
+ offline_mode.packets_sub->get_topic_name());
+ }
+}
+
+SampleRosWrapper::~SampleRosWrapper()
+{
+ auto * online_mode = std::get_if(&runtime_mode_);
+ if (!online_mode) {
+ return;
+ }
+
+ const auto stop_result = online_mode->hw_interface.sensor_interface_stop();
+ if (!stop_result.has_value()) {
+ const auto error = stop_result.error();
+ RCLCPP_WARN(
+ get_logger(), "Failed to stop sample sensor stream cleanly: %s", error.message.c_str());
+ }
+}
+
+void SampleRosWrapper::initialize_diagnostics()
+{
+ const double min_ok_hz = declare_parameter(
+ "diagnostics.pointcloud_publish_rate.frequency_ok.min_hz", param_read_only());
+ const double max_ok_hz = declare_parameter(
+ "diagnostics.pointcloud_publish_rate.frequency_ok.max_hz", param_read_only());
+ const double min_warn_hz = declare_parameter(
+ "diagnostics.pointcloud_publish_rate.frequency_warn.min_hz", param_read_only());
+ const double max_warn_hz = declare_parameter(
+ "diagnostics.pointcloud_publish_rate.frequency_warn.max_hz", param_read_only());
+ const auto num_frame_transition = static_cast(declare_parameter(
+ "diagnostics.pointcloud_publish_rate.num_frame_transition", param_read_only()));
+ const auto packet_liveness_timeout_ms =
+ declare_parameter("diagnostics.packet_liveness.timeout_ms", param_read_only());
+
+ if (min_warn_hz >= min_ok_hz) {
+ throw std::runtime_error(
+ "Invalid diagnostics config: frequency_warn.min_hz must be smaller than "
+ "frequency_ok.min_hz.");
+ }
+ if (max_warn_hz <= max_ok_hz) {
+ throw std::runtime_error(
+ "Invalid diagnostics config: frequency_warn.max_hz must be greater than "
+ "frequency_ok.max_hz.");
+ }
+ if (packet_liveness_timeout_ms <= 0) {
+ throw std::runtime_error(
+ "Invalid diagnostics config: packet_liveness.timeout_ms must be positive.");
+ }
+ const auto packet_liveness_timeout = std::chrono::milliseconds(packet_liveness_timeout_ms);
+
+ diagnostics_.publish_rate.emplace(
+ this, custom_diagnostic_tasks::RateBoundStatusParam{min_ok_hz, max_ok_hz},
+ custom_diagnostic_tasks::RateBoundStatusParam{min_warn_hz, max_warn_hz},
+ std::max(1, num_frame_transition), false, true, "pointcloud publish rate");
+ diagnostics_.packet_liveness.emplace(
+ "packet_receive", this,
+ rclcpp::Duration::from_seconds(
+ std::chrono::duration(packet_liveness_timeout).count() * 1e-3));
+
+ diagnostics_.updater.setHardwareID(frame_id_);
+ diagnostics_.updater.add(diagnostics_.publish_rate.value());
+ diagnostics_.updater.add(diagnostics_.packet_liveness.value());
+ diagnostics_.updater.force_update();
+}
+
+void SampleRosWrapper::publish_pointcloud_callback(
+ const drivers::NebulaPointCloudPtr & pointcloud, double timestamp_s)
+{
+ if (!pointcloud) {
+ return;
+ }
+
+ if (publishers_.points->get_subscription_count() > 0) {
+ auto ros_pc_msg_ptr = std::make_unique();
+ pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr);
+ ros_pc_msg_ptr->header.stamp = rclcpp::Time(static_cast(timestamp_s * 1e9));
+ ros_pc_msg_ptr->header.frame_id = frame_id_;
+ publishers_.points->publish(std::move(ros_pc_msg_ptr));
+ }
+
+ diagnostics_.publish_rate->tick();
+}
+
+void SampleRosWrapper::receive_cloud_packet_callback(
+ const std::vector & packet, const drivers::connections::UdpSocket::RxMetadata & metadata)
+{
+ diagnostics_.packet_liveness->tick();
+ auto * online_mode = std::get_if(&runtime_mode_);
+ if (online_mode && online_mode->packets_pub) {
+ if (!online_mode->current_scan_packets_msg) {
+ online_mode->current_scan_packets_msg = std::make_unique();
+ }
+
+ const auto packet_timestamp_ns = metadata.timestamp_ns.value_or(current_system_time_ns());
+ nebula_msgs::msg::NebulaPacket packet_msg{};
+ packet_msg.stamp.sec = static_cast(packet_timestamp_ns / 1'000'000'000ULL);
+ packet_msg.stamp.nanosec = static_cast(packet_timestamp_ns % 1'000'000'000ULL);
+ packet_msg.data = packet;
+ if (online_mode->current_scan_packets_msg->packets.empty()) {
+ online_mode->current_scan_packets_msg->header.stamp = packet_msg.stamp;
+ online_mode->current_scan_packets_msg->header.frame_id = frame_id_;
+ }
+ online_mode->current_scan_packets_msg->packets.emplace_back(std::move(packet_msg));
+ }
+
+ process_packet(packet, metadata.packet_perf_counters.receive_duration_ns);
+}
+
+void SampleRosWrapper::receive_packets_message_callback(
+ std::unique_ptr packets_msg)
+{
+ if (!packets_msg) {
+ return;
+ }
+
+ if (!std::holds_alternative(runtime_mode_)) {
+ RCLCPP_ERROR_ONCE(
+ get_logger(),
+ "Ignoring NebulaPackets. Launch with launch_hw:=false to enable NebulaPackets replay.");
+ return;
+ }
+
+ for (const auto & packet_msg : packets_msg->packets) {
+ diagnostics_.packet_liveness->tick();
+ process_packet(packet_msg.data, 0U);
+ }
+}
+
+void SampleRosWrapper::process_packet(
+ const std::vector & packet, const uint64_t receive_duration_ns)
+{
+ if (!decoder_) {
+ return;
+ }
+
+ const auto decode_result = decoder_->unpack(packet);
+ publish_debug_durations(
+ receive_duration_ns, decode_result.performance_counters.decode_time_ns,
+ decode_result.performance_counters.callback_time_ns);
+
+ if (!decode_result.metadata_or_error.has_value()) {
+ RCLCPP_DEBUG_THROTTLE(
+ get_logger(), *get_clock(), 1000, "Packet decode failed: %s.",
+ drivers::to_cstr(decode_result.metadata_or_error.error()));
+ return;
+ }
+
+ auto * online_mode = std::get_if(&runtime_mode_);
+ if (
+ online_mode && online_mode->packets_pub &&
+ decode_result.metadata_or_error.value().did_scan_complete &&
+ online_mode->current_scan_packets_msg &&
+ !online_mode->current_scan_packets_msg->packets.empty()) {
+ online_mode->packets_pub->publish(std::move(online_mode->current_scan_packets_msg));
+ online_mode->current_scan_packets_msg = std::make_unique();
+ }
+}
+
+void SampleRosWrapper::publish_debug_durations(
+ uint64_t receive_duration_ns, uint64_t decode_duration_ns, uint64_t publish_duration_ns) const
+{
+ const auto publish_metric = [](const auto & publisher, const uint64_t duration_ns) {
+ if (!publisher) {
+ return;
+ }
+ if (
+ publisher->get_subscription_count() == 0 &&
+ publisher->get_intra_process_subscription_count() == 0) {
+ return;
+ }
+
+ std_msgs::msg::Float64 msg;
+ msg.data = static_cast(duration_ns) * k_ns_to_ms;
+ publisher->publish(msg);
+ };
+
+ publish_metric(publishers_.receive_duration_ms, receive_duration_ns);
+ publish_metric(publishers_.decode_duration_ms, decode_duration_ns);
+ publish_metric(publishers_.publish_duration_ms, publish_duration_ns);
+}
+
+const char * SampleRosWrapper::to_cstr(const Error::Code code)
+{
+ switch (code) {
+ case Error::Code::HW_INTERFACE_NOT_INITIALIZED:
+ return "hardware interface not initialized";
+ case Error::Code::HW_STREAM_START_FAILED:
+ return "hardware stream start failed";
+ default:
+ return "unknown wrapper error";
+ }
+}
+
+} // namespace nebula::ros
+
+RCLCPP_COMPONENTS_REGISTER_NODE(nebula::ros::SampleRosWrapper)
diff --git a/src/nebula_sample/nebula_sample_common/CMakeLists.txt b/src/nebula_sample/nebula_sample_common/CMakeLists.txt
new file mode 100644
index 000000000..010cdfd69
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_common/CMakeLists.txt
@@ -0,0 +1,22 @@
+cmake_minimum_required(VERSION 3.20)
+project(nebula_sample_common)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+add_library(nebula_sample_common INTERFACE)
+
+target_include_directories(
+ nebula_sample_common
+ INTERFACE $
+ $)
+target_link_libraries(nebula_sample_common
+ INTERFACE nebula_core_common::nebula_core_common)
+
+install(TARGETS nebula_sample_common EXPORT export_nebula_sample_common)
+install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME})
+
+ament_export_targets(export_nebula_sample_common)
+ament_export_dependencies(nebula_core_common)
+
+ament_package()
diff --git a/src/nebula_sample/nebula_sample_common/include/nebula_sample_common/sample_calibration_data.hpp b/src/nebula_sample/nebula_sample_common/include/nebula_sample_common/sample_calibration_data.hpp
new file mode 100644
index 000000000..2d6ab6113
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_common/include/nebula_sample_common/sample_calibration_data.hpp
@@ -0,0 +1,86 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#pragma once
+
+#include
+
+#include
+#include
+#include
+#include
+
+namespace nebula::drivers
+{
+
+/// @brief Calibration data for the Sample LiDAR (required for some sensors)
+/// @details Real sensor integrations can replace this stub with calibration tables
+/// such as per-laser angle offsets, distance corrections, or timing offsets.
+struct SampleCalibrationData
+{
+ enum class ErrorCode : uint8_t {
+ OPEN_FOR_READ_FAILED, ///< Opening a calibration file for reading failed.
+ OPEN_FOR_WRITE_FAILED, ///< Opening a calibration file for writing failed.
+ };
+
+ /// @brief Error payload for calibration file operations.
+ struct Error
+ {
+ ErrorCode code;
+ std::string message;
+ };
+
+ /// @brief Load calibration data from a file, e.g. for offline decoding
+ /// @param calibration_file Path to the calibration file
+ /// @return Parsed calibration data on success, Error on failure.
+ static util::expected load_from_file(
+ const std::string & calibration_file)
+ {
+ std::ifstream file;
+ file.exceptions(std::ifstream::failbit | std::ifstream::badbit);
+
+ try {
+ file.open(calibration_file);
+ } catch (const std::ifstream::failure & e) {
+ return Error{
+ ErrorCode::OPEN_FOR_READ_FAILED,
+ "Failed to open calibration file: " + calibration_file + " Error: " + e.what()};
+ }
+
+ // Implement: Parse and validate sensor calibration fields from the opened file.
+ return SampleCalibrationData{};
+ }
+
+ /// @brief Save calibration data to a file
+ /// @param calibration_file Path to save the calibration file
+ /// @return std::monostate on success, Error on failure.
+ util::expected save_to_file(const std::string & calibration_file)
+ {
+ std::ofstream file;
+ file.exceptions(std::ofstream::failbit | std::ofstream::badbit);
+
+ try {
+ file.open(calibration_file);
+ } catch (const std::ofstream::failure & e) {
+ return Error{
+ ErrorCode::OPEN_FOR_WRITE_FAILED,
+ "Failed to open calibration file for writing: " + calibration_file + " Error: " + e.what()};
+ }
+
+ // Implement: Serialize sensor calibration fields to the opened file.
+ return std::monostate{};
+ }
+};
+
+} // namespace nebula::drivers
diff --git a/src/nebula_sample/nebula_sample_common/include/nebula_sample_common/sample_configuration.hpp b/src/nebula_sample/nebula_sample_common/include/nebula_sample_common/sample_configuration.hpp
new file mode 100644
index 000000000..95453821a
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_common/include/nebula_sample_common/sample_configuration.hpp
@@ -0,0 +1,85 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#pragma once
+
+#include
+#include
+#include
+
+#include
+
+namespace nebula::drivers
+{
+
+/// @brief Network endpoint settings used by the sample driver.
+/// @details These values define where the UDP packets are received from and on which local port.
+struct ConnectionConfiguration
+{
+ /// IP address of the host interface that receives LiDAR packets.
+ std::string host_ip;
+ /// IP address assigned to the sensor.
+ std::string sensor_ip;
+ /// UDP destination port on the host for sensor data.
+ uint16_t data_port;
+};
+
+// Allow automatic JSON serialization/deserialization
+NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(ConnectionConfiguration, host_ip, sensor_ip, data_port);
+
+/// @brief Sensor-specific configuration for the Sample LiDAR
+/// @details Minimal tutorial configuration that combines connection settings and angular filtering.
+struct SampleSensorConfiguration
+{
+ ConnectionConfiguration connection;
+ FieldOfView fov{};
+};
+
+/// @brief Serialize SampleSensorConfiguration to JSON.
+/// @details The JSON schema contains:
+/// - `connection` (ConnectionConfiguration)
+/// - `fov` (FieldOfView)
+inline void to_json(nlohmann::json & j, const SampleSensorConfiguration & config)
+{
+ j = nlohmann::json{};
+ j["connection"] = config.connection;
+
+ nlohmann::json azimuth_fov;
+ azimuth_fov["min_deg"] = config.fov.azimuth.start;
+ azimuth_fov["max_deg"] = config.fov.azimuth.end;
+
+ nlohmann::json elevation_fov;
+ elevation_fov["min_deg"] = config.fov.elevation.start;
+ elevation_fov["max_deg"] = config.fov.elevation.end;
+
+ j["fov"] = {{"azimuth", azimuth_fov}, {"elevation", elevation_fov}};
+}
+
+/// @brief Parse SampleSensorConfiguration from JSON.
+/// @throws nlohmann::json::exception if required fields are missing or have incompatible types.
+inline void from_json(const nlohmann::json & j, SampleSensorConfiguration & config)
+{
+ j.at("connection").get_to(config.connection);
+
+ const auto & fov_json = j.at("fov");
+ const auto & azimuth_fov = fov_json.at("azimuth");
+ azimuth_fov.at("min_deg").get_to(config.fov.azimuth.start);
+ azimuth_fov.at("max_deg").get_to(config.fov.azimuth.end);
+
+ const auto & elevation_fov = fov_json.at("elevation");
+ elevation_fov.at("min_deg").get_to(config.fov.elevation.start);
+ elevation_fov.at("max_deg").get_to(config.fov.elevation.end);
+}
+
+} // namespace nebula::drivers
diff --git a/src/nebula_sample/nebula_sample_common/package.xml b/src/nebula_sample/nebula_sample_common/package.xml
new file mode 100644
index 000000000..6023612b4
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_common/package.xml
@@ -0,0 +1,21 @@
+
+
+
+ nebula_sample_common
+ 0.3.0
+ Nebula Sample Common Libraries and Headers
+ David Wong
+ Max Schmeller
+
+ Apache 2
+ TIER IV
+
+ autoware_cmake
+ ros_environment
+
+ nebula_core_common
+
+
+ ament_cmake
+
+
diff --git a/src/nebula_sample/nebula_sample_decoders/CMakeLists.txt b/src/nebula_sample/nebula_sample_decoders/CMakeLists.txt
new file mode 100644
index 000000000..95f4f84f8
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_decoders/CMakeLists.txt
@@ -0,0 +1,29 @@
+cmake_minimum_required(VERSION 3.20)
+project(nebula_sample_decoders)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+# Sample Decoder
+add_library(nebula_sample_decoders SHARED src/sample_decoder.cpp)
+
+target_include_directories(
+ nebula_sample_decoders
+ PUBLIC $
+ $)
+
+target_link_libraries(
+ nebula_sample_decoders
+ PUBLIC nebula_core_common::nebula_core_common
+ nebula_sample_common::nebula_sample_common
+ nebula_core_decoders::nebula_core_decoders)
+
+install(TARGETS nebula_sample_decoders EXPORT export_nebula_sample_decoders)
+install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME})
+
+ament_export_include_directories("include/${PROJECT_NAME}")
+ament_export_targets(export_nebula_sample_decoders)
+
+ament_export_dependencies(nebula_core_common nebula_sample_common nebula_core_decoders)
+
+ament_package()
diff --git a/src/nebula_sample/nebula_sample_decoders/include/nebula_sample_decoders/sample_decoder.hpp b/src/nebula_sample/nebula_sample_decoders/include/nebula_sample_decoders/sample_decoder.hpp
new file mode 100644
index 000000000..2f9d5c21c
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_decoders/include/nebula_sample_decoders/sample_decoder.hpp
@@ -0,0 +1,100 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NEBULA_SAMPLE_DECODER_HPP
+#define NEBULA_SAMPLE_DECODER_HPP
+
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+namespace nebula::drivers
+{
+
+/// @brief Error codes returned during packet decoding
+enum class DecodeError : uint8_t {
+ PACKET_FORMAT_INVALID, ///< Packet content did not match the expected format
+ CALLBACK_NOT_SET, ///< Decoder cannot publish scans because callback is missing
+ EMPTY_PACKET, ///< Received packet had zero bytes
+};
+
+/// @brief Convert DecodeError to a stable string literal for logging.
+const char * to_cstr(DecodeError error);
+
+/// @brief Metadata extracted from a decoded packet
+struct PacketMetadata
+{
+ uint64_t packet_timestamp_ns{}; ///< Timestamp of the packet in nanoseconds
+ bool did_scan_complete{false}; ///< True if this packet completed a scan
+};
+
+/// @brief Performance metrics for packet decoding
+struct PerformanceCounters
+{
+ uint64_t decode_time_ns{0}; ///< Time spent decoding the packet (ns)
+ uint64_t callback_time_ns{0}; ///< Time spent in the pointcloud callback (ns)
+};
+
+/// @brief Result of decoding a single packet
+/// @details Contains either successful metadata or an error, plus performance counters
+struct PacketDecodeResult
+{
+ /// Timing measurements for the decode and callback path.
+ PerformanceCounters performance_counters;
+ /// Successful metadata or a decode error.
+ util::expected metadata_or_error;
+};
+
+/// @brief Decoder that accumulates and converts incoming raw packets into point clouds.
+/// @details The tutorial implementation emits synthetic points for demonstration purposes.
+class SampleDecoder
+{
+public:
+ /// @brief Callback type for publishing complete point clouds
+ /// @param pointcloud The decoded point cloud
+ /// @param timestamp_s Timestamp of the scan in seconds
+ using pointcloud_callback_t =
+ std::function;
+
+ /// @brief Constructor
+ /// @param fov Field of view to crop the point cloud to
+ /// @param pointcloud_cb Callback invoked when a full scan is assembled
+ explicit SampleDecoder(
+ FieldOfView fov /*, other decoder args */, pointcloud_callback_t pointcloud_cb);
+
+ /// @brief Decode a single UDP packet
+ /// @param packet Raw packet bytes from the sensor
+ /// @return PacketDecodeResult with metadata on success, or DecodeError on failure.
+ /// @post performance_counters.decode_time_ns is always set.
+ [[nodiscard]] PacketDecodeResult unpack(const std::vector & packet);
+
+ /// @brief Replace the callback used for completed scans.
+ void set_pointcloud_callback(pointcloud_callback_t pointcloud_cb);
+
+private:
+ static constexpr uint64_t k_packets_per_dummy_scan = 10;
+
+ FieldOfView fov_;
+ pointcloud_callback_t pointcloud_callback_;
+ NebulaPointCloudPtr current_scan_cloud_{std::make_shared()};
+ uint64_t packet_count_{0};
+};
+
+} // namespace nebula::drivers
+
+#endif // NEBULA_SAMPLE_DECODER_HPP
diff --git a/src/nebula_sample/nebula_sample_decoders/package.xml b/src/nebula_sample/nebula_sample_decoders/package.xml
new file mode 100644
index 000000000..b2880ce36
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_decoders/package.xml
@@ -0,0 +1,22 @@
+
+
+
+ nebula_sample_decoders
+ 0.3.0
+ Nebula Sample Decoders Library
+ David Wong
+ Max Schmeller
+
+ Apache 2
+ TIER IV
+
+ autoware_cmake
+ ros_environment
+ nebula_core_common
+ nebula_core_decoders
+ nebula_sample_common
+
+
+ ament_cmake
+
+
diff --git a/src/nebula_sample/nebula_sample_decoders/src/sample_decoder.cpp b/src/nebula_sample/nebula_sample_decoders/src/sample_decoder.cpp
new file mode 100644
index 000000000..d28cce8b5
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_decoders/src/sample_decoder.cpp
@@ -0,0 +1,104 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "nebula_sample_decoders/sample_decoder.hpp"
+
+#include
+#include
+#include
+#include
+
+namespace nebula::drivers
+{
+
+const char * to_cstr(const DecodeError error)
+{
+ switch (error) {
+ case DecodeError::PACKET_FORMAT_INVALID:
+ return "packet format invalid";
+ case DecodeError::CALLBACK_NOT_SET:
+ return "pointcloud callback is not set";
+ case DecodeError::EMPTY_PACKET:
+ return "packet is empty";
+ default:
+ return "unknown decode error";
+ }
+}
+
+SampleDecoder::SampleDecoder(
+ FieldOfView fov /*, other decoder args */, pointcloud_callback_t pointcloud_cb)
+: fov_(fov), pointcloud_callback_(std::move(pointcloud_cb))
+{
+ // Implement: Initialize sensor-specific decode state (buffers, angle tracking, timestamps).
+}
+
+PacketDecodeResult SampleDecoder::unpack(const std::vector & packet)
+{
+ const auto decode_begin = std::chrono::steady_clock::now();
+ PacketDecodeResult result{{}, DecodeError::CALLBACK_NOT_SET};
+
+ if (!pointcloud_callback_) {
+ result.metadata_or_error = DecodeError::CALLBACK_NOT_SET;
+ } else if (packet.empty()) {
+ result.metadata_or_error = DecodeError::EMPTY_PACKET;
+ } else {
+ ++packet_count_;
+
+ NebulaPoint point{};
+ point.x = static_cast(packet_count_);
+ point.y = 0.0F;
+ point.z = 0.0F;
+ point.intensity = packet.front();
+ point.return_type = 0U;
+ point.channel = 0U;
+ point.azimuth = fov_.azimuth.start;
+ point.elevation = fov_.elevation.start;
+ point.distance = static_cast(packet.size());
+ point.time_stamp = static_cast(packet_count_);
+ current_scan_cloud_->push_back(point);
+
+ PacketMetadata metadata{};
+ metadata.packet_timestamp_ns =
+ static_cast(std::chrono::duration_cast(
+ std::chrono::system_clock::now().time_since_epoch())
+ .count());
+ metadata.did_scan_complete = (packet_count_ % k_packets_per_dummy_scan) == 0;
+
+ if (metadata.did_scan_complete) {
+ const auto callback_begin = std::chrono::steady_clock::now();
+ pointcloud_callback_(
+ current_scan_cloud_, static_cast(metadata.packet_timestamp_ns) * 1e-9);
+ result.performance_counters.callback_time_ns =
+ static_cast(std::chrono::duration_cast(
+ std::chrono::steady_clock::now() - callback_begin)
+ .count());
+ current_scan_cloud_ = std::make_shared();
+ }
+
+ result.metadata_or_error = metadata;
+ }
+
+ result.performance_counters.decode_time_ns =
+ static_cast(std::chrono::duration_cast(
+ std::chrono::steady_clock::now() - decode_begin)
+ .count());
+ return result;
+}
+
+void SampleDecoder::set_pointcloud_callback(pointcloud_callback_t pointcloud_cb)
+{
+ pointcloud_callback_ = std::move(pointcloud_cb);
+}
+
+} // namespace nebula::drivers
diff --git a/src/nebula_sample/nebula_sample_hw_interfaces/CMakeLists.txt b/src/nebula_sample/nebula_sample_hw_interfaces/CMakeLists.txt
new file mode 100644
index 000000000..5b621e020
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_hw_interfaces/CMakeLists.txt
@@ -0,0 +1,26 @@
+cmake_minimum_required(VERSION 3.20)
+project(nebula_sample_hw_interfaces)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+add_library(nebula_sample_hw_interfaces SHARED src/sample_hw_interface.cpp)
+
+target_include_directories(
+ nebula_sample_hw_interfaces
+ PUBLIC $
+ $)
+
+ament_target_dependencies(
+ nebula_sample_hw_interfaces PUBLIC nebula_core_common nebula_sample_common
+ nebula_core_hw_interfaces)
+
+install(TARGETS nebula_sample_hw_interfaces
+ EXPORT export_nebula_sample_hw_interfaces)
+install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME})
+
+ament_export_include_directories("include/${PROJECT_NAME}")
+ament_export_targets(export_nebula_sample_hw_interfaces)
+ament_export_dependencies(nebula_core_common nebula_sample_common nebula_core_hw_interfaces)
+
+ament_package()
diff --git a/src/nebula_sample/nebula_sample_hw_interfaces/include/nebula_sample_hw_interfaces/sample_hw_interface.hpp b/src/nebula_sample/nebula_sample_hw_interfaces/include/nebula_sample_hw_interfaces/sample_hw_interface.hpp
new file mode 100644
index 000000000..005822193
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_hw_interfaces/include/nebula_sample_hw_interfaces/sample_hw_interface.hpp
@@ -0,0 +1,83 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NEBULA_SAMPLE_HW_INTERFACE_HPP
+#define NEBULA_SAMPLE_HW_INTERFACE_HPP
+
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace nebula::drivers
+{
+
+/// @brief Receives raw sensor packets and forwards them to a registered callback.
+/// @details This class owns the transport-facing state used by the sample driver.
+class SampleHwInterface
+{
+public:
+ /// @brief Rich error payload for hardware interface operations.
+ struct Error
+ {
+ /// @brief Coarse category for quick handling and branching.
+ enum class Code : uint8_t {
+ CALLBACK_NOT_REGISTERED, ///< Start requested before a callback was registered.
+ INVALID_CALLBACK, ///< Empty callback passed to register_scan_callback.
+ INVALID_OPERATION, ///< Operation is invalid in the current interface state.
+ SOCKET_OPEN_FAILED, ///< UDP socket creation/bind/subscribe failed.
+ SOCKET_CLOSE_FAILED, ///< UDP socket unsubscribe/teardown failed.
+ };
+
+ Code code;
+ std::string message;
+ };
+
+ static const char * to_cstr(Error::Code code);
+
+ /// @brief Construct the hardware interface with connection settings.
+ /// @param connection_configuration Network addresses and ports used by the sensor stream.
+ explicit SampleHwInterface(ConnectionConfiguration connection_configuration);
+
+ /// @brief Start packet reception.
+ /// @return std::monostate on success, Error on failure.
+ /// @post On success, incoming packets are delivered through the registered callback.
+ util::expected sensor_interface_start();
+
+ /// @brief Stop packet reception.
+ /// @return std::monostate on success, Error on failure.
+ util::expected sensor_interface_stop();
+
+ /// @brief Register or replace the callback invoked for each incoming packet.
+ /// @param scan_callback Callback receiving packet bytes and transport metadata.
+ /// @return std::monostate if callback is accepted, Error otherwise.
+ util::expected register_scan_callback(
+ connections::UdpSocket::callback_t scan_callback);
+
+private:
+ ConnectionConfiguration connection_configuration_;
+ std::optional udp_socket_;
+ std::shared_ptr packet_callback_;
+ std::mutex callback_mutex_;
+};
+
+} // namespace nebula::drivers
+
+#endif // NEBULA_SAMPLE_HW_INTERFACE_HPP
diff --git a/src/nebula_sample/nebula_sample_hw_interfaces/package.xml b/src/nebula_sample/nebula_sample_hw_interfaces/package.xml
new file mode 100644
index 000000000..e890e48da
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_hw_interfaces/package.xml
@@ -0,0 +1,21 @@
+
+
+
+ nebula_sample_hw_interfaces
+ 0.3.0
+ Nebula Sample HW Interfaces
+ David Wong
+
+ Apache 2
+ TIER IV
+
+ autoware_cmake
+
+ nebula_core_common
+ nebula_core_hw_interfaces
+ nebula_sample_common
+
+
+ ament_cmake
+
+
diff --git a/src/nebula_sample/nebula_sample_hw_interfaces/src/sample_hw_interface.cpp b/src/nebula_sample/nebula_sample_hw_interfaces/src/sample_hw_interface.cpp
new file mode 100644
index 000000000..dd503231c
--- /dev/null
+++ b/src/nebula_sample/nebula_sample_hw_interfaces/src/sample_hw_interface.cpp
@@ -0,0 +1,132 @@
+// Copyright 2025 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "nebula_sample_hw_interfaces/sample_hw_interface.hpp"
+
+#include
+#include
+#include
+#include
+#include
+
+namespace nebula::drivers
+{
+
+SampleHwInterface::SampleHwInterface(ConnectionConfiguration connection_configuration)
+: connection_configuration_(std::move(connection_configuration))
+{
+ // The sample driver is UDP-only. Real integrations can initialize control/sync channels here.
+}
+
+util::expected SampleHwInterface::sensor_interface_start()
+{
+ std::lock_guard lock(callback_mutex_);
+
+ if (!packet_callback_) {
+ return Error{
+ Error::Code::CALLBACK_NOT_REGISTERED,
+ "Cannot start sensor interface before registering a packet callback"};
+ }
+
+ if (udp_socket_ && udp_socket_->is_subscribed()) {
+ return std::monostate{};
+ }
+
+ try {
+ udp_socket_.emplace(
+ connections::UdpSocket::Builder(
+ connection_configuration_.host_ip, connection_configuration_.data_port)
+ .bind());
+
+ // Callback can only be set while udp_socket_ is nullopt, so we don't need locking here
+ udp_socket_->subscribe(
+ [this](
+ const std::vector & packet, const connections::UdpSocket::RxMetadata & metadata) {
+ if (this->packet_callback_ && *this->packet_callback_) {
+ (*this->packet_callback_)(packet, metadata);
+ }
+ });
+ } catch (const connections::SocketError & e) {
+ return Error{
+ Error::Code::SOCKET_OPEN_FAILED, std::string("Failed to open UDP socket: ") + e.what()};
+ } catch (const connections::UsageError & e) {
+ return Error{
+ Error::Code::SOCKET_OPEN_FAILED,
+ std::string("Invalid UDP socket configuration: ") + e.what()};
+ } catch (const std::exception & e) {
+ return Error{
+ Error::Code::SOCKET_OPEN_FAILED,
+ std::string("Failed to open UDP socket due to unexpected error: ") + e.what()};
+ }
+
+ return std::monostate{};
+}
+
+util::expected SampleHwInterface::sensor_interface_stop()
+{
+ if (!udp_socket_) {
+ return std::monostate{};
+ }
+
+ try {
+ udp_socket_->unsubscribe();
+ udp_socket_.reset();
+ } catch (const connections::SocketError & e) {
+ return Error{
+ Error::Code::SOCKET_CLOSE_FAILED, std::string("Failed to close UDP socket: ") + e.what()};
+ } catch (const std::exception & e) {
+ return Error{
+ Error::Code::SOCKET_CLOSE_FAILED,
+ std::string("Failed to close UDP socket due to unexpected error: ") + e.what()};
+ }
+
+ return std::monostate{};
+}
+
+util::expected SampleHwInterface::register_scan_callback(
+ connections::UdpSocket::callback_t scan_callback)
+{
+ if (!scan_callback) {
+ return Error{Error::Code::INVALID_CALLBACK, "Cannot register an empty packet callback"};
+ }
+
+ std::lock_guard lock(callback_mutex_);
+ if (udp_socket_) {
+ return Error{
+ Error::Code::INVALID_OPERATION,
+ "Cannot replace packet callback while sensor interface is active"};
+ }
+ packet_callback_ = std::make_shared(std::move(scan_callback));
+ return std::monostate{};
+}
+
+const char * SampleHwInterface::to_cstr(SampleHwInterface::Error::Code code)
+{
+ switch (code) {
+ case Error::Code::CALLBACK_NOT_REGISTERED:
+ return "callback not registered";
+ case Error::Code::INVALID_CALLBACK:
+ return "invalid callback";
+ case Error::Code::INVALID_OPERATION:
+ return "invalid operation";
+ case Error::Code::SOCKET_OPEN_FAILED:
+ return "failed to open UDP socket";
+ case Error::Code::SOCKET_CLOSE_FAILED:
+ return "failed to close UDP socket";
+ default:
+ return "unknown hardware error";
+ }
+}
+
+} // namespace nebula::drivers
diff --git a/src/nebula_velodyne/nebula_velodyne_hw_interfaces/include/nebula_velodyne_hw_interfaces/velodyne_hw_interface.hpp b/src/nebula_velodyne/nebula_velodyne_hw_interfaces/include/nebula_velodyne_hw_interfaces/velodyne_hw_interface.hpp
index 2f37645c3..9f93e4c51 100644
--- a/src/nebula_velodyne/nebula_velodyne_hw_interfaces/include/nebula_velodyne_hw_interfaces/velodyne_hw_interface.hpp
+++ b/src/nebula_velodyne/nebula_velodyne_hw_interfaces/include/nebula_velodyne_hw_interfaces/velodyne_hw_interface.hpp
@@ -29,12 +29,12 @@
#endif
#include "nebula_core_common/util/expected.hpp"
-#include "nebula_core_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"
+#include "nebula_core_hw_interfaces/nebula_hw_interface_base.hpp"
#include
#include