diff --git a/.clang-format b/.clang-format index b41fae912..82c94e663 100644 --- a/.clang-format +++ b/.clang-format @@ -45,3 +45,6 @@ IncludeCategories: - Regex: '".*"' Priority: 1 CaseSensitive: true +--- +Language: Json +BasedOnStyle: llvm diff --git a/.cspell.json b/.cspell.json index e83fb6742..8c180631a 100644 --- a/.cspell.json +++ b/.cspell.json @@ -19,6 +19,7 @@ "gptp", "Helios", "Hesai", + "horiz", "Idat", "ipaddr", "manc", @@ -50,6 +51,7 @@ "vccint", "Vccint", "Vdat", + "Wbitwise", "XT", "XTM", "yukkysaito" diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 354a1b3d3..cdd07d2e3 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -54,4 +54,3 @@ jobs: fail_ci_if_error: false verbose: true flags: differential - diff --git a/.github/workflows/json-schema-check.yaml b/.github/workflows/json-schema-check.yaml index 735641acd..bac83a126 100644 --- a/.github/workflows/json-schema-check.yaml +++ b/.github/workflows/json-schema-check.yaml @@ -36,4 +36,4 @@ jobs: runs-on: ubuntu-latest steps: - name: Dummy step - run: echo "No relevant changes, passing check" \ No newline at end of file + run: echo "No relevant changes, passing check" diff --git a/.markdown-link-check.json b/.markdown-link-check.json index c71a3e425..03b977748 100644 --- a/.markdown-link-check.json +++ b/.markdown-link-check.json @@ -1,5 +1,9 @@ { - "aliveStatusCodes": [200, 206, 403], + "aliveStatusCodes": [ + 200, + 206, + 403 + ], "ignorePatterns": [ { "pattern": "^http://localhost" diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index b4c2e9f2f..9bc48e55e 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -11,6 +11,7 @@ repos: - id: check-toml - id: check-xml - id: check-yaml + args: [--allow-multiple-documents] - id: detect-private-key - id: end-of-file-fixer - id: mixed-line-ending @@ -24,7 +25,7 @@ repos: args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v4.0.0-alpha.8 + rev: v3.1.0 hooks: - id: prettier diff --git a/.prettierignore b/.prettierignore index a3c34d00a..21c2dd9fd 100644 --- a/.prettierignore +++ b/.prettierignore @@ -1,2 +1,3 @@ -*.param.yaml +*.yaml *.rviz +*.json diff --git a/.yamllint.yaml b/.yamllint.yaml index 2c7bd088e..7837bfe0a 100644 --- a/.yamllint.yaml +++ b/.yamllint.yaml @@ -1,8 +1,5 @@ extends: default -ignore: | - *.param.yaml - rules: braces: level: error @@ -13,6 +10,8 @@ rules: document-start: level: error present: false # Don't need document start markers + ignore: + - .clang-format # Needs '---' between languages line-length: disable # Delegate to Prettier truthy: level: error @@ -20,3 +19,7 @@ rules: quoted-strings: level: error required: only-when-needed # To keep consistent style + indentation: + spaces: consistent + indent-sequences: true + check-multi-line-strings: false diff --git a/README.md b/README.md index 9b55340f6..e39121907 100644 --- a/README.md +++ b/README.md @@ -1,13 +1,16 @@ # Nebula ## Welcome to Nebula, the universal sensor driver + Nebula is a sensor driver platform that is designed to provide a unified framework for as wide a variety of devices as possible. -While it primarily targets Ethernet-based LiDAR sensors, it aims to be easily extendable to support new sensors and interfaces. +While it primarily targets Ethernet-based LiDAR sensors, it aims to be easily extendable to support new sensors and interfaces. Nebula works with ROS 2 and is the recommended sensor driver for the [Autoware](https://autoware.org/) project. ## Documentation + We recommend you get started with the [Nebula Documention](https://tier4.github.io/nebula/). Here you will find information about the background of the project, how to install and use with ROS 2, and also how to add new sensors to the Nebula driver. + - [About Nebula](https://tier4.github.io/nebula/about) - [Design](https://tier4.github.io/nebula/design) - [Supported Sensors](https://tier4.github.io/nebula/supported_sensors) @@ -15,10 +18,11 @@ Here you will find information about the background of the project, how to insta - [Launching with ROS 2](https://tier4.github.io/nebula/usage) - [Parameters](https://tier4.github.io/nebula/parameters) - [Point cloud types](https://tier4.github.io/nebula/point_types) -- [Contributing](https://tier4.github.io/nebula/contributing) +- [Contributing](https://tier4.github.io/nebula/contribute) - [Tutorials](https://tier4.github.io/nebula/tutorials) ## Quick start + Nebula builds with ROS 2 Galactic and Humble. > **Note** @@ -39,6 +43,7 @@ rosdep install --from-paths src --ignore-src -y -r # Build Nebula colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ``` + To launch Nebula as a ROS 2 node with default parameters for your sensor model: ```bash @@ -46,6 +51,7 @@ ros2 launch nebula_ros *sensor_vendor_name*_launch_all_hw.xml sensor_model:=*sen ``` For example, for a Hesai Pandar40P sensor: + ```bash ros2 launch nebula_ros hesai_launch_all_hw.xml sensor_model:=Pandar40P ``` diff --git a/docs/about.md b/docs/about.md index db95e44a5..06a9f909e 100644 --- a/docs/about.md +++ b/docs/about.md @@ -1,7 +1,3 @@ # About Nebula WIP, please check back soon! - - - - diff --git a/docs/contribute.md b/docs/contribute.md new file mode 100644 index 000000000..f0a80b161 --- /dev/null +++ b/docs/contribute.md @@ -0,0 +1,3 @@ +# Contributing to Nebula + +WIP - please check back soon! diff --git a/docs/contributing.md b/docs/contributing.md deleted file mode 100644 index ab0ef86ba..000000000 --- a/docs/contributing.md +++ /dev/null @@ -1,3 +0,0 @@ -# Contributing to Nebula - -WIP - please check back soon! \ No newline at end of file diff --git a/docs/hesai_decoder_design.md b/docs/hesai_decoder_design.md index a3d48f0a3..827b87773 100644 --- a/docs/hesai_decoder_design.md +++ b/docs/hesai_decoder_design.md @@ -11,6 +11,7 @@ This way, runtime overhead for this generalization is `0`. ### Packet formats For all handled Hesai sensors, the packet structure follows this rough format: + 1. (optional) header: static sensor info and feature flags 2. body: point data 3. tail and other appendices: timestamp, operation mode info @@ -18,10 +19,11 @@ For all handled Hesai sensors, the packet structure follows this rough format: ### Decoding steps For all handled Hesai sensors, decoding a packet follows these steps: + ```python def unpack(packet): parse_and_validate(packet) - # return group: one (single-return) or more (multi-return) + # return group: one (single-return) or more (multi-return) # blocks that belong to the same azimuth for return_group in packet: if is_start_of_new_scan(return_group): @@ -40,17 +42,18 @@ def decode(return_group): append to pointcloud ``` -The steps marked with __*__ are model-specific: +The steps marked with **\*** are model-specific: -* angle correction -* timing correction -* return type assignment +- angle correction +- timing correction +- return type assignment ### Angle correction There are two approaches between all the supported sensors: -* Calibration file based -* Correction file based (currently only used by AT128) + +- Calibration file based +- Correction file based (currently only used by AT128) For both approaches, sin/cos lookup tables can be computed. However, the resolution and calculation of these tables is different. @@ -60,7 +63,7 @@ However, the resolution and calculation of these tables is different. For each laser channel, a fixed elevation angle and azimuth angle offset are defined in the calibration file. Thus, sin/cos for elevation are only a function of the laser channel (not dependent on azimuth) while those for azimuth are a function of azimuth AND elevation. -Lookup tables for elevation can thus be sized with `n_channels`, yielding a maximum size of +Lookup tables for elevation can thus be sized with `n_channels`, yielding a maximum size of `128 * sizeof(float) = 512B` each. For azimuth, the size is `n_channels * n_azimuths = n_channels * 360 * azimuth_resolution <= 128 * 36000`. @@ -94,9 +97,10 @@ While there is a wide range of different supported return modes (e.g. single (fi Differences only arise in multi-return (dual or triple) in the output order of the returns, and in the handling of some returns being duplicates (e.g. in dual(first, strongest), the first return coincides with the strongest one). Here is an exhaustive list of differences: -* For Dual (First, Last) `0x3B`, 128E3X, 128E4X and XT32 reverse the output order (Last, First) -* For Dual (Last, Strongest) `0x39`, all sensors except XT32M place the second strongest return in the even block if last == strongest -* For Dual (First, Strongest) `0x3c`, the same as for `0x39` holds. + +- For Dual (First, Last) `0x3B`, 128E3X, 128E4X and XT32 reverse the output order (Last, First) +- For Dual (Last, Strongest) `0x39`, all sensors except XT32M place the second strongest return in the even block if last == strongest +- For Dual (First, Strongest) `0x3c`, the same as for `0x39` holds. For all other return modes, duplicate points are output if the two returns coincide. @@ -119,9 +123,10 @@ Return mode handling has a default implementation that is supplemented by additi ### `AngleCorrector` The angle corrector has three main tasks: -* compute corrected azimuth/elevation for given azimuth and channel -* implement `hasScanCompleted()` logic that decides where one scan ends and the next starts -* compute and provide lookup tables for sin/cos/etc. + +- compute corrected azimuth/elevation for given azimuth and channel +- implement `hasScanCompleted()` logic that decides where one scan ends and the next starts +- compute and provide lookup tables for sin/cos/etc. The two angle correction types are calibration-based and correction-based. In both approaches, a file from the sensor is used to extract the angle correction for each azimuth/channel. For all approaches, cos/sin lookup tables in the appropriate size are generated (see requirements section above). @@ -133,9 +138,10 @@ It is a template class taking a sensor type `SensorT` from which packet type, an Thus, this unified decoder is an almost zero-cost abstraction. Its tasks are: -* parsing an incoming packet -* managing decode/output point buffers -* converting all points in the packet using the sensor-specific functions of `SensorT` where necessary + +- parsing an incoming packet +- managing decode/output point buffers +- converting all points in the packet using the sensor-specific functions of `SensorT` where necessary `HesaiDecoder` is a subclass of the existing `HesaiScanDecoder` to allow all template instantiations to be assigned to variables of the supertype. @@ -144,24 +150,24 @@ Its tasks are: To support a new sensor model, first familiarize with the already implemented decoders. Then, consult the new sensor's datasheet and identify the following parameters: -| Parameter | Chapter | Possible values | Notes | -|-|-|-|-| -| Header format | 3.1 | `Header12B`, `Header8B`, ... | `Header12B` is the standard and comprises the UDP pre-header and header (6+6B) mentioned in the data sheets | -| Blocks per packet | 3.1 | `2`, `6`, `10`, ... | | -| Number of channels | 3.1 | `32`, `40`, `64`, ... | | -| Unit format | 3.1 | `Unit3B`, `Unit4B`, ... | | -| Angle correction | App. 3 | `CALIBRATION`, `CORRECTION`, ... | The datasheet usually specifies whether a calibration/correction file is used | -| Timing correction | App. 2 | | There is usually a block and channel component. These come in the form of formulas/lookup tables. For most sensors, these depend on return mode and for some, features like high resolution mode, alternate firing etc. might change the timing | -| Return type handling | 3.1 | | Return modes are handled identically for most sensors but some re-order the returns or replace returns if there are duplicates | -| Bytes per second | 1.4 | | | -| Lowest supported frequency | 1.4 | `5 Hz`, `10 Hz`, ... | | - -| Chapter | Full title | -|-|-| -|1.4| Introduction > Specifications| -|3.1| Data Structure > Point Cloud Data Packet| -|App. 2| Absolute Time of Point Cloud Data| -|App. 3| Angle Correction| +| Parameter | Chapter | Possible values | Notes | +| -------------------------- | ------- | -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Header format | 3.1 | `Header12B`, `Header8B`, ... | `Header12B` is the standard and comprises the UDP pre-header and header (6+6B) mentioned in the data sheets | +| Blocks per packet | 3.1 | `2`, `6`, `10`, ... | | +| Number of channels | 3.1 | `32`, `40`, `64`, ... | | +| Unit format | 3.1 | `Unit3B`, `Unit4B`, ... | | +| Angle correction | App. 3 | `CALIBRATION`, `CORRECTION`, ... | The datasheet usually specifies whether a calibration/correction file is used | +| Timing correction | App. 2 | | There is usually a block and channel component. These come in the form of formulas/lookup tables. For most sensors, these depend on return mode and for some, features like high resolution mode, alternate firing etc. might change the timing | +| Return type handling | 3.1 | | Return modes are handled identically for most sensors but some re-order the returns or replace returns if there are duplicates | +| Bytes per second | 1.4 | | | +| Lowest supported frequency | 1.4 | `5 Hz`, `10 Hz`, ... | | + +| Chapter | Full title | +| ------- | ---------------------------------------- | +| 1.4 | Introduction > Specifications | +| 3.1 | Data Structure > Point Cloud Data Packet | +| App. 2 | Absolute Time of Point Cloud Data | +| App. 3 | Angle Correction | With this information, create a `PacketMySensor` struct and `SensorMySensor` class. Reuse already-defined structs as much as possible (c.f. `Packet128E3X` and `Packet128E4X`). @@ -169,7 +175,7 @@ Reuse already-defined structs as much as possible (c.f. `Packet128E3X` and `Pack Implement timing correction in `SensorMySensor` and define the class constants `float MIN_RANGE`, `float MAX_RANGE` and `size_t MAX_SCAN_BUFFER_POINTS`. The former two are used for filtering out too-close and too-far away points while the latter is used to -allocate pointcloud buffers. +allocate pointcloud buffers. Set `MAX_SCAN_BUFFER_POINTS = bytes_per_second / lowest_supported_frequency` from the parameters found above. If there are any non-standard features your sensor has, implement them as generically as possible to allow for future sensors to re-use your code. diff --git a/docs/index.md b/docs/index.md index c5c3153b1..e79da77a5 100644 --- a/docs/index.md +++ b/docs/index.md @@ -1,9 +1,11 @@ # Welcome to the Nebula documentation + Welcome to the Nebula documentation. Here you will find information about the background of the project, how to install and use with ROS 2, and also how to add new sensors to the Nebula driver. -# About Nebula +## About Nebula + Nebula is a sensor driver platform that is designed to provide a unified framework for as wide a variety of devices as possible. -While it primarily targets Ethernet-based LiDAR sensors, it aims to be easily extendable to support new sensors and interfaces. +While it primarily targets Ethernet-based LiDAR sensors, it aims to be easily extendable to support new sensors and interfaces. Nebula works with ROS 2 and is the recommended sensor driver for the [Autoware](https://autoware.org/) project. The project aims to provide: - A universal sensor driver @@ -15,18 +17,22 @@ Nebula works with ROS 2 and is the recommended sensor driver for the [Autoware]( For more information, please refer to [About Nebula](about.md). -# Getting started +## Getting started + - [Installation](installation.md) - [Launching with ROS 2](usage.md) -# Nebula architecture +## Nebula architecture + - [Design](design.md) - [Parameters](parameters.md) - [Point cloud types](point_types.md) -# Supported sensors +## Supported sensors + - [Supported sensors](supported_sensors.md) -# Development +## Development + - [Tutorials](tutorials.md) -- [Contributing](contributing.md) \ No newline at end of file +- [Contributing](contribute.md) diff --git a/docs/installation.md b/docs/installation.md index 07e5eec43..e8124e99e 100644 --- a/docs/installation.md +++ b/docs/installation.md @@ -1,11 +1,12 @@ # Installing Nebula ## Requirements + Nebula requires ROS 2 (Galactic or Humble) to build the ROS 2 wrapper. Please see the [ROS 2 documentation](https://docs.ros.org/en/humble/index.html) for how to install. - ## Getting the source and building + > **Note** > > A [TCP enabled version of ROS' Transport Driver](https://github.com/mojomex/transport_drivers/tree/mutable-buffer-in-udp-callback) is required to use Nebula. @@ -28,6 +29,7 @@ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ## Testing your build To run Nebula unit tests: + ```bash colcon test --event-handlers console_cohesion+ --packages-above nebula_common ``` @@ -36,4 +38,4 @@ Show results: ```bash colcon test-result --all -``` \ No newline at end of file +``` diff --git a/docs/parameters.md b/docs/parameters.md index 466b05c44..8cb3c62a0 100644 --- a/docs/parameters.md +++ b/docs/parameters.md @@ -118,4 +118,4 @@ Parameters shared by all supported models: | min_range | double | 0.3 | meters, >= 0.3 | Minimum point range published | | max_range | double | 300.0 | meters, <= 300.0 | Maximum point range published | | cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle | -| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle | \ No newline at end of file +| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle | diff --git a/docs/point_types.md b/docs/point_types.md index f19f5d30b..63f629f99 100644 --- a/docs/point_types.md +++ b/docs/point_types.md @@ -53,4 +53,4 @@ These definitions can be found in the `nebula_common/include/point_types.hpp`. | `return type` | `uint8` | | Contains the lase return type according to the sensor configuration. | | `azimuth` | `float` | `degrees` | Contains the azimuth of the current point. | | `distance` | `float` | `m` | Contains the distance from the sensor origin to this echo on the XY plane. | -| `timestamp` | `float` | `ns` | Contains the relative time to the triggered scan time. \ No newline at end of file +| `timestamp` | `float` | `ns` | Contains the relative time to the triggered scan time. | diff --git a/docs/supported_sensors.md b/docs/supported_sensors.md index a142677f4..82821c29b 100644 --- a/docs/supported_sensors.md +++ b/docs/supported_sensors.md @@ -1,45 +1,44 @@ # Supported sensors -Nebula currently supports the following sensor models, where `sensor_model` is the ROS parameter to be used at launch: +Nebula currently supports the following sensor models, where `sensor_model` is the ROS parameter to be used at launch: ## Hesai LiDARs -| Model | `sensor_model` | Configuration file | Test status | -| ------------- | -------------- | ------------------ | -------------------- | -| Pandar64 | Pandar64 | Pandar64.yaml | ✅ | -| Pandar 40P | Pandar40P | Pandar40P.yaml | ✅ | -| Pandar XT32 | PandarXT32 | PandarXT32.yaml | ✅ | -| Pandar XT32M | PandarXT32M | PandarXT32M.yaml | ⚠️ | -| Pandar QT64 | PandarQT64 | PandarQT64.yaml | ✅ | -| Pandar QT128 | PandarQT128 | PandarQT128.yaml | ⚠️ | -| Pandar AT128 | PandarAT128 | PandarAT128.yaml | ✅\* | -| Pandar 128E4X | Pandar128E4X | Pandar128E4X.yaml | ⚠️ | +| Model | `sensor_model` | Configuration file | Test status | +| ------------- | -------------- | ------------------ | ----------- | +| Pandar64 | Pandar64 | Pandar64.yaml | ✅ | +| Pandar 40P | Pandar40P | Pandar40P.yaml | ✅ | +| Pandar XT32 | PandarXT32 | PandarXT32.yaml | ✅ | +| Pandar XT32M | PandarXT32M | PandarXT32M.yaml | ⚠️ | +| Pandar QT64 | PandarQT64 | PandarQT64.yaml | ✅ | +| Pandar QT128 | PandarQT128 | PandarQT128.yaml | ⚠️ | +| Pandar AT128 | PandarAT128 | PandarAT128.yaml | ✅\* | +| Pandar 128E4X | Pandar128E4X | Pandar128E4X.yaml | ⚠️ | ## Velodyne LiDARs -| Model | `sensor_model` | Configuration file | Test status | -| ------------- | -------------- | ------------------ | -------------------- | -| VLP-16 | VLP16 | VLP16.yaml | ⚠️ | -| VLP-16-HiRes | VLP16 | | ❌ | -| VLP-32 | VLP32 | VLP32.yaml | ⚠️ | -| VLS-128 | VLS128 | VLS128.yaml | ⚠️ | +| Model | `sensor_model` | Configuration file | Test status | +| ------------ | -------------- | ------------------ | ----------- | +| VLP-16 | VLP16 | VLP16.yaml | ⚠️ | +| VLP-16-HiRes | VLP16 | | ❌ | +| VLP-32 | VLP32 | VLP32.yaml | ⚠️ | +| VLS-128 | VLS128 | VLS128.yaml | ⚠️ | ## Robosense LiDARs -| Model | `sensor_model` | Configuration file | Test status | -| ------------- | -------------- | ------------------ | -------------------- | -| Bpearl | Bpearl | Bpearl.yaml | ⚠️ | -| Helios | Helios | Helios.yaml | ⚠️ | +| Model | `sensor_model` | Configuration file | Test status | +| ------ | -------------- | ------------------ | ----------- | +| Bpearl | Bpearl | Bpearl.yaml | ⚠️ | +| Helios | Helios | Helios.yaml | ⚠️ | ## Continental radars -| Model | `sensor_model` | Configuration file | Test status | -| ------------- | -------------- | ------------------ | -------------------- | -| ARS548 | ARS548 | ARS548.yaml | ⚠️ | +| Model | `sensor_model` | Configuration file | Test status | +| ------ | -------------- | ------------------ | ----------- | +| ARS548 | ARS548 | ARS548.yaml | ⚠️ | - -Test status:\ -✅: complete\ -⚠️: some functionality yet to be tested\ -❌: untested\ -\*: AT128 needs software version 3.50.8 or newer for the `scan_angle` setting to work correctly. \ No newline at end of file +Test status: +✅: complete +⚠️: some functionality yet to be tested +❌: untested +\*: AT128 needs software version 3.50.8 or newer for the `scan_angle` setting to work correctly. diff --git a/docs/tutorials.md b/docs/tutorials.md index 78be591cc..9edf03660 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/mojomex/nebula/tree/single-node-refactor-tutorial). \ No newline at end of file +In the meantime, check out the [tutorial branch](https://github.com/mojomex/nebula/tree/single-node-refactor-tutorial). diff --git a/docs/usage.md b/docs/usage.md index 5448cf389..cb635954c 100644 --- a/docs/usage.md +++ b/docs/usage.md @@ -1,6 +1,7 @@ # Running Nebula ## Launch with default parameters + To launch Nebula as a ROS 2 node with default parameters for your sensor model: ```bash @@ -8,9 +9,11 @@ ros2 launch nebula_ros *sensor_vendor_name*_launch_all_hw.xml sensor_model:=*sen ``` For example, for a Hesai Pandar40P sensor: + ```bash ros2 launch nebula_ros hesai_launch_all_hw.xml sensor_model:=Pandar40P ``` ## Sensor configuration -WIP \ No newline at end of file + +WIP diff --git a/local.cspell.json b/local.cspell.json deleted file mode 100644 index e69de29bb..000000000 diff --git a/mkdocs.yml b/mkdocs.yml index 4b8513cec..3e25eaaba 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -43,7 +43,7 @@ nav: - Point cloud types: point_types.md - Supported sensors: supported_sensors.md - Tutorials: tutorials.md - - Contributing: contributing.md + - Contributing: contribute.md - Nebula common: nebula_common/links.md - Nebula decoders: nebula_decoders/links.md - Nebula HW interfaces: nebula_hw_interfaces/links.md @@ -55,49 +55,49 @@ plugins: projects: nebula_common: src-dirs: nebula_common/include - full-doc: True + full-doc: true doxy-cfg: FILE_PATTERNS: "*.hpp *.h" - RECURSIVE: True - EXTRACT_ALL: True - INLINE_SOURCES: True - ENABLE_PREPROCESSING: True - MACRO_EXPANSION: True + RECURSIVE: true + EXTRACT_ALL: true + INLINE_SOURCES: true + ENABLE_PREPROCESSING: true + MACRO_EXPANSION: true nebula_decoders: src-dirs: nebula_decoders/include - full-doc: True + full-doc: true doxy-cfg: FILE_PATTERNS: "*.hpp *.h" - RECURSIVE: True - EXTRACT_ALL: True - INLINE_SOURCES: True - ENABLE_PREPROCESSING: True - MACRO_EXPANSION: True + RECURSIVE: true + EXTRACT_ALL: true + INLINE_SOURCES: true + ENABLE_PREPROCESSING: true + MACRO_EXPANSION: true nebula_hw_interfaces: src-dirs: nebula_hw_interfaces/include - full-doc: True + full-doc: true doxy-cfg: FILE_PATTERNS: "*.hpp *.h" - RECURSIVE: True - EXTRACT_ALL: True - INLINE_SOURCES: True - ENABLE_PREPROCESSING: True - MACRO_EXPANSION: True + RECURSIVE: true + EXTRACT_ALL: true + INLINE_SOURCES: true + ENABLE_PREPROCESSING: true + MACRO_EXPANSION: true nebula_ros: src-dirs: nebula_ros/include - full-doc: True + full-doc: true doxy-cfg: FILE_PATTERNS: "*.hpp *.h" - RECURSIVE: True - EXTRACT_ALL: True - INLINE_SOURCES: True - ENABLE_PREPROCESSING: True - MACRO_EXPANSION: True + RECURSIVE: true + EXTRACT_ALL: true + INLINE_SOURCES: true + ENABLE_PREPROCESSING: true + MACRO_EXPANSION: true save-api: .mkdoxy - full-doc: True - debug: False - ignore-errors: False + full-doc: true + debug: false + ignore-errors: false - search: lang: en diff --git a/nebula_common/include/nebula_common/hesai/hesai_common.hpp b/nebula_common/include/nebula_common/hesai/hesai_common.hpp index 8e0600999..2017bbf4f 100644 --- a/nebula_common/include/nebula_common/hesai/hesai_common.hpp +++ b/nebula_common/include/nebula_common/hesai/hesai_common.hpp @@ -1,10 +1,23 @@ +// Copyright 2024 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_HESAI_COMMON_H #define NEBULA_HESAI_COMMON_H #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -#include #include #include #include @@ -72,7 +85,7 @@ struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase return LoadFromString(ss.str()); } - nebula::Status LoadFromBytes(const std::vector & buf) + nebula::Status LoadFromBytes(const std::vector & buf) override { std::string calibration_string = std::string(buf.begin(), buf.end()); return LoadFromString(calibration_string); diff --git a/nebula_common/include/nebula_common/hesai/hesai_status.hpp b/nebula_common/include/nebula_common/hesai/hesai_status.hpp index e7547f666..a375bb606 100644 --- a/nebula_common/include/nebula_common/hesai/hesai_status.hpp +++ b/nebula_common/include/nebula_common/hesai/hesai_status.hpp @@ -1,10 +1,23 @@ +// Copyright 2024 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 HESAI_STATUS_HPP #define HESAI_STATUS_HPP #include "nebula_common/nebula_status.hpp" #include -#include namespace nebula { @@ -26,12 +39,13 @@ struct HesaiStatus : Status Type_end_of_Status = INVALID_RPM_ERROR } _hesai_type; HesaiStatus() : _type_num(static_cast(Status::OK)) { _type = static_cast(type()); } - HesaiStatus(Type v) : _type_num(static_cast(v)) { _type = v; } - HesaiStatus(HesaiType v) : _type_num(static_cast(v)), _hesai_type(v) + /* NOLINT(runtime/explicit) */ HesaiStatus(Type v) : _type_num(static_cast(v)) { _type = v; } + /* NOLINT(runtime/explicit) */ HesaiStatus(HesaiType v) + : _type_num(static_cast(v)), _hesai_type(v) { _type = Type::Type_end_of_Status; } - HesaiStatus(int type) : _type_num(type) {} + explicit HesaiStatus(int type) : _type_num(type) {} int type() const { return _type_num; } friend bool operator==(const HesaiStatus & L, const HesaiStatus & R) { diff --git a/nebula_common/include/nebula_common/nebula_common.hpp b/nebula_common/include/nebula_common/nebula_common.hpp index 0331179c0..747946255 100644 --- a/nebula_common/include/nebula_common/nebula_common.hpp +++ b/nebula_common/include/nebula_common/nebula_common.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_COMMON_H #define NEBULA_COMMON_H @@ -458,7 +472,8 @@ struct CANSensorConfigurationBase : SensorConfigurationBase std::string interface; float receiver_timeout_sec{}; float sender_timeout_sec{}; - /// @brief Socketcan filters, see the documentation of SocketCanReceiver::CanFilterList for details + /// @brief Socketcan filters, see the documentation of SocketCanReceiver::CanFilterList for + /// details std::string filters{}; bool use_bus_time{}; }; diff --git a/nebula_common/include/nebula_common/nebula_status.hpp b/nebula_common/include/nebula_common/nebula_status.hpp index 7d04fae55..9f9eef655 100644 --- a/nebula_common/include/nebula_common/nebula_status.hpp +++ b/nebula_common/include/nebula_common/nebula_status.hpp @@ -16,7 +16,6 @@ #define NEBULA_STATUS_HPP #include -#include namespace nebula { @@ -42,8 +41,8 @@ struct Status Type_end_of_Status = ERROR_1 } _type; Status() : _type(Type::OK) {} - Status(Type v) : _type(v) {} - Status(int type) : _type(static_cast(type)) {} + /* NOLINT(runtime/explicit) */ Status(Type v) : _type(v) {} + explicit Status(int type) : _type(static_cast(type)) {} Type type() const { return _type; } friend bool operator==(const Status & L, const Status & R) { return L.type() == R.type(); } friend bool operator!=(const Status & L, const Status & R) { return L.type() != R.type(); } diff --git a/nebula_common/include/nebula_common/point_types.hpp b/nebula_common/include/nebula_common/point_types.hpp index 260b7b9db..db66f6941 100644 --- a/nebula_common/include/nebula_common/point_types.hpp +++ b/nebula_common/include/nebula_common/point_types.hpp @@ -1,9 +1,25 @@ +// Copyright 2024 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_POINT_TYPES_H #define NEBULA_POINT_TYPES_H #include #include +#include + namespace nebula { namespace drivers @@ -63,20 +79,15 @@ using NebulaPointCloudPtr = pcl::PointCloud::Ptr; } // namespace drivers } // namespace nebula -POINT_CLOUD_REGISTER_POINT_STRUCT(nebula::drivers::PointXYZIR, - (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, - ring, ring)) +POINT_CLOUD_REGISTER_POINT_STRUCT( + nebula::drivers::PointXYZIR, + (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)) -POINT_CLOUD_REGISTER_POINT_STRUCT(nebula::drivers::PointXYZIRADT, - (float, x, x) - (float, y, y) - (float, z, z) - (float, intensity, intensity) - (std::uint16_t, ring, ring) - (float, azimuth, azimuth) - (float, distance, distance) - (std::uint8_t, return_type, return_type) - (double, time_stamp, time_stamp)) +POINT_CLOUD_REGISTER_POINT_STRUCT( + nebula::drivers::PointXYZIRADT, + (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)( + float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)( + double, time_stamp, time_stamp)) POINT_CLOUD_REGISTER_POINT_STRUCT( nebula::drivers::PointXYZICATR, diff --git a/nebula_common/include/nebula_common/robosense/robosense_common.hpp b/nebula_common/include/nebula_common/robosense/robosense_common.hpp index 68f8e0600..8541f8f90 100644 --- a/nebula_common/include/nebula_common/robosense/robosense_common.hpp +++ b/nebula_common/include/nebula_common/robosense/robosense_common.hpp @@ -1,14 +1,27 @@ +// Copyright 2024 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 "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -#include #include #include #include -#include #include +#include #include namespace nebula @@ -74,7 +87,7 @@ struct RobosenseCalibrationConfiguration : CalibrationConfigurationBase std::getline(stream, header); char sep; - int laser_id; + size_t laser_id; float elevation; float azimuth; Status load_status = Status::OK; @@ -174,10 +187,10 @@ struct RobosenseCalibrationConfiguration : CalibrationConfigurationBase void CreateCorrectedChannels() { - for(auto& correction : calibration) { + for (auto & correction : calibration) { uint16_t channel = 0; - for(const auto& compare:calibration) { - if(compare.elevation < correction.elevation) ++channel; + for (const auto & compare : calibration) { + if (compare.elevation < correction.elevation) ++channel; } correction.channel = channel; } diff --git a/nebula_common/include/nebula_common/util/expected.hpp b/nebula_common/include/nebula_common/util/expected.hpp index 25cb5f83d..1d4333443 100644 --- a/nebula_common/include/nebula_common/util/expected.hpp +++ b/nebula_common/include/nebula_common/util/expected.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 diff --git a/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp b/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp index 9cbbb53ea..49b8a427f 100644 --- a/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp +++ b/nebula_common/include/nebula_common/velodyne/velodyne_calibration_decoder.hpp @@ -15,9 +15,6 @@ #include #include -#include -#include -#include #include #include #include @@ -61,12 +58,8 @@ class VelodyneCalibration bool initialized; public: - explicit VelodyneCalibration() - : distance_resolution_m(0.002f), initialized(false) - { - } - explicit VelodyneCalibration(const std::string & calibration_file) - : distance_resolution_m(0.002f) + VelodyneCalibration() : distance_resolution_m(0.002f), initialized(false) {} + explicit VelodyneCalibration(const std::string & calibration_file) : distance_resolution_m(0.002f) { read(calibration_file); } diff --git a/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp b/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp index b429e7b53..22265780b 100644 --- a/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp +++ b/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_VELODYNE_COMMON_H #define NEBULA_VELODYNE_COMMON_H @@ -5,8 +19,7 @@ #include "nebula_common/nebula_status.hpp" #include "nebula_common/velodyne/velodyne_calibration_decoder.hpp" -#include -#include +#include namespace nebula { namespace drivers diff --git a/nebula_common/include/nebula_common/velodyne/velodyne_status.hpp b/nebula_common/include/nebula_common/velodyne/velodyne_status.hpp index 783f57af6..ac60e7994 100644 --- a/nebula_common/include/nebula_common/velodyne/velodyne_status.hpp +++ b/nebula_common/include/nebula_common/velodyne/velodyne_status.hpp @@ -1,10 +1,23 @@ +// Copyright 2024 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 VELODYNE_STATUS_HPP #define VELODYNE_STATUS_HPP #include "nebula_common/nebula_status.hpp" #include -#include namespace nebula { @@ -26,12 +39,16 @@ struct VelodyneStatus : Status Type_end_of_Status = INVALID_RPM_ERROR } _velo_type; VelodyneStatus() : _type_num(static_cast(Status::OK)) { _type = static_cast(type()); } - VelodyneStatus(Type v) : _type_num(static_cast(v)) { _type = v; } - VelodyneStatus(VelodyneType v) : _type_num(static_cast(v)), _velo_type(v) + /* NOLINT(runtime/explicit) */ VelodyneStatus(Type v) : _type_num(static_cast(v)) + { + _type = v; + } + /* NOLINT(runtime/explicit) */ VelodyneStatus(VelodyneType v) + : _type_num(static_cast(v)), _velo_type(v) { _type = Type::Type_end_of_Status; } - VelodyneStatus(int type) : _type_num(type) {} + explicit VelodyneStatus(int type) : _type_num(type) {} int type() const { return _type_num; } friend bool operator==(const VelodyneStatus & L, const VelodyneStatus & R) { diff --git a/nebula_common/src/nebula_common.cpp b/nebula_common/src/nebula_common.cpp index 7af599032..c87331421 100644 --- a/nebula_common/src/nebula_common.cpp +++ b/nebula_common/src/nebula_common.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include namespace nebula @@ -60,7 +62,7 @@ pcl::PointCloud::Ptr convertPointXYZIRCAEDTToPointXYZIRADT( point.ring = p.channel; point.azimuth = rad2deg(p.azimuth) * 100.0; point.distance = p.distance; - point.time_stamp = stamp + static_cast(p.time_stamp)*1e-9; + point.time_stamp = stamp + static_cast(p.time_stamp) * 1e-9; output_pointcloud->points.emplace_back(point); } diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 0c03c3c9e..d4d69e018 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -8,6 +8,9 @@ #include +#include +#include + #ifdef HAVE_NEW_YAMLCPP namespace YAML { @@ -25,22 +28,22 @@ namespace nebula { namespace drivers { -const std::string NUM_LASERS = "num_lasers"; -const std::string DISTANCE_RESOLUTION = "distance_resolution"; -const std::string LASERS = "lasers"; -const std::string LASER_ID = "laser_id"; -const std::string ROT_CORRECTION = "rot_correction"; -const std::string VERT_CORRECTION = "vert_correction"; -const std::string DIST_CORRECTION = "dist_correction"; -const std::string TWO_PT_CORRECTION_AVAILABLE = "two_pt_correction_available"; -const std::string DIST_CORRECTION_X = "dist_correction_x"; -const std::string DIST_CORRECTION_Y = "dist_correction_y"; -const std::string VERT_OFFSET_CORRECTION = "vert_offset_correction"; -const std::string HORIZ_OFFSET_CORRECTION = "horiz_offset_correction"; -const std::string MAX_INTENSITY = "max_intensity"; -const std::string MIN_INTENSITY = "min_intensity"; -const std::string FOCAL_DISTANCE = "focal_distance"; -const std::string FOCAL_SLOPE = "focal_slope"; +const char NUM_LASERS[] = "num_lasers"; +const char DISTANCE_RESOLUTION[] = "distance_resolution"; +const char LASERS[] = "lasers"; +const char LASER_ID[] = "laser_id"; +const char ROT_CORRECTION[] = "rot_correction"; +const char VERT_CORRECTION[] = "vert_correction"; +const char DIST_CORRECTION[] = "dist_correction"; +const char TWO_PT_CORRECTION_AVAILABLE[] = "two_pt_correction_available"; +const char DIST_CORRECTION_X[] = "dist_correction_x"; +const char DIST_CORRECTION_Y[] = "dist_correction_y"; +const char VERT_OFFSET_CORRECTION[] = "vert_offset_correction"; +const char HORIZ_OFFSET_CORRECTION[] = "horiz_offset_correction"; +const char MAX_INTENSITY[] = "max_intensity"; +const char MIN_INTENSITY[] = "min_intensity"; +const char FOCAL_DISTANCE[] = "focal_distance"; +const char FOCAL_SLOPE[] = "focal_slope"; /** Read calibration for a single laser. */ void operator>>(const YAML::Node & node, std::pair & correction) @@ -158,7 +161,6 @@ void operator>>(const YAML::Node & node, VelodyneCalibration & calibration) } if (next_index < num_lasers) { // anything found in this ring? - // store this ring number with its corresponding laser number calibration.laser_corrections[next_index].laser_ring = ring; next_angle = min_seen; diff --git a/nebula_decoders/calibration/velodyne/HDL32.yaml b/nebula_decoders/calibration/velodyne/HDL32.yaml index 7a0e6f6e4..e276ec43e 100644 --- a/nebula_decoders/calibration/velodyne/HDL32.yaml +++ b/nebula_decoders/calibration/velodyne/HDL32.yaml @@ -1,388 +1,388 @@ # standard Velodyne HDL-32E calibration parameters lasers: - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 0, - rot_correction: 0.0, - vert_correction: -0.5352924815866609, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 1, - rot_correction: 0.0, - vert_correction: -0.1628392174657417, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 2, - rot_correction: 0.0, - vert_correction: -0.5119050696099369, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 3, - rot_correction: 0.0, - vert_correction: -0.13962634015954636, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 4, - rot_correction: 0.0, - vert_correction: -0.4886921905584123, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 5, - rot_correction: 0.0, - vert_correction: -0.11641346285335104, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 6, - rot_correction: 0.0, - vert_correction: -0.4654793115068877, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 7, - rot_correction: 0.0, - vert_correction: -0.09302604738596851, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 8, - rot_correction: 0.0, - vert_correction: -0.44209189953016365, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 9, - rot_correction: 0.0, - vert_correction: -0.06981317007977318, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 10, - rot_correction: 0.0, - vert_correction: -0.4188790204786391, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 11, - rot_correction: 0.0, - vert_correction: -0.046600292773577856, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 12, - rot_correction: 0.0, - vert_correction: -0.39566614142711454, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 13, - rot_correction: 0.0, - vert_correction: -0.023212879051524585, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 14, - rot_correction: 0.0, - vert_correction: -0.3722787294503905, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 15, - rot_correction: 0.0, - vert_correction: 0.0, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 16, - rot_correction: 0.0, - vert_correction: -0.3490658503988659, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 17, - rot_correction: 0.0, - vert_correction: 0.023212879051524585, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 18, - rot_correction: 0.0, - vert_correction: -0.32585297134734137, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 19, - rot_correction: 0.0, - vert_correction: 0.046600292773577856, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 20, - rot_correction: 0.0, - vert_correction: -0.30246555937061725, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 21, - rot_correction: 0.0, - vert_correction: 0.06981317007977318, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 22, - rot_correction: 0.0, - vert_correction: -0.2792526803190927, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 23, - rot_correction: 0.0, - vert_correction: 0.09302604738596851, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 24, - rot_correction: 0.0, - vert_correction: -0.25603980126756815, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 25, - rot_correction: 0.0, - vert_correction: 0.11641346285335104, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 26, - rot_correction: 0.0, - vert_correction: -0.23265238929084414, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 27, - rot_correction: 0.0, - vert_correction: 0.13962634015954636, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 28, - rot_correction: 0.0, - vert_correction: -0.20943951023931956, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 29, - rot_correction: 0.0, - vert_correction: 0.1628392174657417, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 30, - rot_correction: 0.0, - vert_correction: -0.18622663118779495, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 31, - rot_correction: 0.0, - vert_correction: 0.18622663118779495, - vert_offset_correction: 0.0, + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 0, + rot_correction: 0.0, + vert_correction: -0.5352924815866609, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 1, + rot_correction: 0.0, + vert_correction: -0.1628392174657417, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 2, + rot_correction: 0.0, + vert_correction: -0.5119050696099369, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 3, + rot_correction: 0.0, + vert_correction: -0.13962634015954636, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 4, + rot_correction: 0.0, + vert_correction: -0.4886921905584123, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 5, + rot_correction: 0.0, + vert_correction: -0.11641346285335104, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 6, + rot_correction: 0.0, + vert_correction: -0.4654793115068877, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 7, + rot_correction: 0.0, + vert_correction: -0.09302604738596851, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 8, + rot_correction: 0.0, + vert_correction: -0.44209189953016365, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 9, + rot_correction: 0.0, + vert_correction: -0.06981317007977318, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 10, + rot_correction: 0.0, + vert_correction: -0.4188790204786391, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 11, + rot_correction: 0.0, + vert_correction: -0.046600292773577856, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 12, + rot_correction: 0.0, + vert_correction: -0.39566614142711454, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 13, + rot_correction: 0.0, + vert_correction: -0.023212879051524585, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 14, + rot_correction: 0.0, + vert_correction: -0.3722787294503905, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 15, + rot_correction: 0.0, + vert_correction: 0.0, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 16, + rot_correction: 0.0, + vert_correction: -0.3490658503988659, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 17, + rot_correction: 0.0, + vert_correction: 0.023212879051524585, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 18, + rot_correction: 0.0, + vert_correction: -0.32585297134734137, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 19, + rot_correction: 0.0, + vert_correction: 0.046600292773577856, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 20, + rot_correction: 0.0, + vert_correction: -0.30246555937061725, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 21, + rot_correction: 0.0, + vert_correction: 0.06981317007977318, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 22, + rot_correction: 0.0, + vert_correction: -0.2792526803190927, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 23, + rot_correction: 0.0, + vert_correction: 0.09302604738596851, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 24, + rot_correction: 0.0, + vert_correction: -0.25603980126756815, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 25, + rot_correction: 0.0, + vert_correction: 0.11641346285335104, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 26, + rot_correction: 0.0, + vert_correction: -0.23265238929084414, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 27, + rot_correction: 0.0, + vert_correction: 0.13962634015954636, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 28, + rot_correction: 0.0, + vert_correction: -0.20943951023931956, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 29, + rot_correction: 0.0, + vert_correction: 0.1628392174657417, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 30, + rot_correction: 0.0, + vert_correction: -0.18622663118779495, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 31, + rot_correction: 0.0, + vert_correction: 0.18622663118779495, + vert_offset_correction: 0.0, } num_lasers: 32 distance_resolution: 0.002 diff --git a/nebula_decoders/calibration/velodyne/HDL64e_s2.yaml b/nebula_decoders/calibration/velodyne/HDL64e_s2.yaml index 3bc719cd0..8c1c190dc 100644 --- a/nebula_decoders/calibration/velodyne/HDL64e_s2.yaml +++ b/nebula_decoders/calibration/velodyne/HDL64e_s2.yaml @@ -1,817 +1,817 @@ lasers: - - { - dist_correction: 1.5195264000000002, - dist_correction_x: 1.5500304, - dist_correction_y: 1.5231381, - focal_distance: 12.0, - focal_slope: 1.4, - horiz_offset_correction: 0.025999999, - laser_id: 0, - max_intensity: 235.0, - min_intensity: 30.0, - rot_correction: -0.1248942899601548, - vert_correction: -0.15304134919741974, - vert_offset_correction: 0.19548199, - } - - { - dist_correction: 1.5145139, - dist_correction_x: 1.5256960000000002, - dist_correction_y: 1.5491043, - focal_distance: 5.0, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 1, - min_intensity: 40.0, - rot_correction: -0.06924466398252106, - vert_correction: -0.1458455539136526, - vert_offset_correction: 0.19601112, - } - - { - dist_correction: 1.4963768, - dist_correction_x: 1.5571011, - dist_correction_y: 1.5456782999999998, - focal_distance: 5.0, - focal_slope: 0.89999998, - horiz_offset_correction: 0.025999999, - laser_id: 2, - min_intensity: 60.0, - rot_correction: 0.0824016906676694, - vert_correction: 0.04339494149708345, - vert_offset_correction: 0.20969539999999998, - } - - { - dist_correction: 1.3771207, - dist_correction_x: 1.4103835, - dist_correction_y: 1.4343457000000002, - focal_distance: 9.5, - focal_slope: 1.1, - horiz_offset_correction: -0.025999999, - laser_id: 3, - min_intensity: 20.0, - rot_correction: 0.137808349360133, - vert_correction: 0.05196082373432465, - vert_offset_correction: 0.21031273, - } - - { - dist_correction: 1.2947885, - dist_correction_x: 1.3720455999999999, - dist_correction_y: 1.4025244000000001, - focal_distance: 10.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 4, - min_intensity: 50.0, - rot_correction: -0.011199603626188263, - vert_correction: -0.1358262679404349, - vert_offset_correction: 0.19674603999999998, - } - - { - dist_correction: 1.4395787000000002, - dist_correction_x: 1.4801956, - dist_correction_y: 1.5074649, - focal_distance: 7.0, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 5, - min_intensity: 30.0, - rot_correction: 0.045795414990398894, - vert_correction: -0.12678532627942263, - vert_offset_correction: 0.19740747, - } - - { - dist_correction: 1.3618773, - dist_correction_x: 1.4004077000000001, - dist_correction_y: 1.3900876, - focal_distance: 5.0, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 6, - min_intensity: 65.0, - rot_correction: -0.031646046452444135, - vert_correction: -0.1895564226946273, - vert_offset_correction: 0.19277746, - } - - { - dist_correction: 1.5325716, - dist_correction_x: 1.5337143, - dist_correction_y: 1.5452948000000002, - focal_distance: 6.0, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 7, - min_intensity: 10.0, - rot_correction: 0.023408326257150665, - vert_correction: -0.18086723120040343, - vert_offset_correction: 0.19342419, - } - - { - dist_correction: 1.3743323, - dist_correction_x: 1.4474606, - dist_correction_y: 1.4533472, - focal_distance: 6.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 8, - min_intensity: 30.0, - rot_correction: 0.10065885915180103, - vert_correction: -0.11973897655818674, - vert_offset_correction: 0.19792192, - } - - { - dist_correction: 1.4969112000000002, - dist_correction_x: 1.4754176, - dist_correction_y: 1.4888799000000001, - focal_distance: 5.0, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 9, - min_intensity: 10.0, - rot_correction: 0.15996423607269877, - vert_correction: -0.10924820210484752, - vert_offset_correction: 0.19868624000000001, - } - - { - dist_correction: 1.434263, - dist_correction_x: 1.4957901000000002, - dist_correction_y: 1.5191892999999999, - focal_distance: 5.0, - focal_slope: 0.89999998, - horiz_offset_correction: 0.025999999, - laser_id: 10, - min_intensity: 35.0, - rot_correction: 0.08313316164783874, - vert_correction: -0.17135657256846043, - vert_offset_correction: 0.19412970999999998, - } - - { - dist_correction: 1.5500841, - dist_correction_x: 1.542697, - dist_correction_y: 1.5716737, - focal_distance: 8.0, - focal_slope: 1.2, - horiz_offset_correction: -0.025999999, - laser_id: 11, - min_intensity: 30.0, - rot_correction: 0.13862572370075624, - vert_correction: -0.1630088948849621, - vert_offset_correction: 0.19474705, - } - - { - dist_correction: 1.3725992, - dist_correction_x: 1.4353555, - dist_correction_y: 1.3932405, - focal_distance: 11.0, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 12, - min_intensity: 50.0, - rot_correction: -0.1255805045528199, - vert_correction: -0.04526314018308893, - vert_offset_correction: 0.20331627000000002, - } - - { - dist_correction: 1.3111591000000002, - dist_correction_x: 1.3470857, - dist_correction_y: 1.3652054000000002, - focal_distance: 6.0, - focal_slope: 0.69999999, - horiz_offset_correction: -0.025999999, - laser_id: 13, - min_intensity: 30.0, - rot_correction: -0.06716508498014805, - vert_correction: -0.03587557613263058, - vert_offset_correction: 0.20399239000000002, - } - - { - dist_correction: 1.5360803, - dist_correction_x: 1.5528035, - dist_correction_y: 1.5666801000000001, - focal_distance: 8.0, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 14, - min_intensity: 20.0, - rot_correction: -0.14578889529014513, - vert_correction: -0.09893566067472198, - vert_offset_correction: 0.19943586, - } - - { - dist_correction: 1.4755448999999998, - dist_correction_x: 1.5032428, - dist_correction_y: 1.5326752, - focal_distance: 5.0, - focal_slope: 0.89999998, - horiz_offset_correction: -0.025999999, - laser_id: 15, - min_intensity: 30.0, - rot_correction: -0.08892898296002069, - vert_correction: -0.09062974348423608, - vert_offset_correction: 0.20003851, - } - - { - dist_correction: 1.4410587000000001, - dist_correction_x: 1.4870845, - dist_correction_y: 1.4627965, - focal_distance: 18.0, - focal_slope: 0.5, - horiz_offset_correction: 0.025999999, - laser_id: 16, - min_intensity: 40.0, - rot_correction: -0.013006177528832626, - vert_correction: -0.02770725895504266, - vert_offset_correction: 0.20458033, - } - - { - dist_correction: 1.4434521, - dist_correction_x: 1.4897508, - dist_correction_y: 1.4791382, - focal_distance: 11.0, - focal_slope: 0.80000001, - horiz_offset_correction: -0.025999999, - laser_id: 17, - min_intensity: 55.0, - rot_correction: 0.04596628970548614, - vert_correction: -0.02014825541794774, - vert_offset_correction: 0.20512417, - } - - { - dist_correction: 1.3243448000000002, - dist_correction_x: 1.3816666000000002, - dist_correction_y: 1.3647719, - focal_distance: 12.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 18, - min_intensity: 10.0, - rot_correction: -0.03237303019110658, - vert_correction: -0.08210824496987311, - vert_offset_correction: 0.20065581999999998, - } - - { - dist_correction: 1.4565853999999998, - dist_correction_x: 1.4340645, - dist_correction_y: 1.4550516, - focal_distance: 20.0, - focal_slope: 0.69999999, - horiz_offset_correction: -0.025999999, - laser_id: 19, - min_intensity: 30.0, - rot_correction: 0.02431275238487562, - vert_correction: -0.0727614640280461, - vert_offset_correction: 0.20133196000000003, - } - - { - dist_correction: 1.3313776, - dist_correction_x: 1.3819601000000001, - dist_correction_y: 1.3847791, - focal_distance: 5.0, - focal_slope: 0.89999998, - horiz_offset_correction: 0.025999999, - laser_id: 20, - min_intensity: 45.0, - rot_correction: 0.10029393174916004, - vert_correction: -0.009929893699589059, - vert_offset_correction: 0.20585909000000002, - } - - { - dist_correction: 1.3787535, - dist_correction_x: 1.3978789, - dist_correction_y: 1.4257806, - focal_distance: 10.0, - focal_slope: 1.1, - horiz_offset_correction: -0.025999999, - laser_id: 21, - min_intensity: 35.0, - rot_correction: 0.15867894419560363, - vert_correction: -0.0037977317325845416, - vert_offset_correction: 0.20630005, - } - - { - dist_correction: 1.3419412, - dist_correction_x: 1.4059189, - dist_correction_y: 1.4113303, - focal_distance: 11.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 22, - min_intensity: 40.0, - rot_correction: 0.08044522544540282, - vert_correction: -0.06482699129962814, - vert_offset_correction: 0.20190518999999998, - } - - { - dist_correction: 1.4338304, - dist_correction_x: 1.4212059, - dist_correction_y: 1.4900565000000001, - focal_distance: 11.0, - focal_slope: 1.1, - horiz_offset_correction: -0.025999999, - laser_id: 23, - min_intensity: 55.0, - rot_correction: 0.13867708175932542, - vert_correction: -0.05566171063737453, - vert_offset_correction: 0.20256662, - } - - { - dist_correction: 1.4930911, - dist_correction_x: 1.5572188, - dist_correction_y: 1.5182672, - focal_distance: 5.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 24, - min_intensity: 25.0, - rot_correction: -0.12505298227706313, - vert_correction: 0.06113007152996804, - vert_offset_correction: 0.21097416, - } - - { - dist_correction: 1.4367653000000002, - dist_correction_x: 1.4614236, - dist_correction_y: 1.4587589, - focal_distance: 3.0, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 25, - min_intensity: 50.0, - rot_correction: -0.06814826559971075, - vert_correction: 0.06988221181432357, - vert_offset_correction: 0.21160620000000002, - } - - { - dist_correction: 1.5279892000000002, - dist_correction_x: 1.5686107999999999, - dist_correction_y: 1.55737, - focal_distance: 7.5, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 26, - min_intensity: 30.0, - rot_correction: -0.14531660046790917, - vert_correction: 0.00887576771486082, - vert_offset_correction: 0.20721134, - } - - { - dist_correction: 1.5077638, - dist_correction_x: 1.5453738000000001, - dist_correction_y: 1.5483368, - focal_distance: 4.0, - focal_slope: 0.89999998, - horiz_offset_correction: -0.025999999, - laser_id: 27, - min_intensity: 30.0, - rot_correction: -0.08904354811745085, - vert_correction: 0.017050959569839413, - vert_offset_correction: 0.20779928000000003, - } - - { - dist_correction: 1.3627797000000001, - dist_correction_x: 1.4232985, - dist_correction_y: 1.4116524000000001, - focal_distance: 4.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 28, - min_intensity: 50.0, - rot_correction: -0.012061568860271928, - vert_correction: 0.07842048992411524, - vert_offset_correction: 0.21222351, - } - - { - dist_correction: 1.3749608, - dist_correction_x: 1.4045798, - dist_correction_y: 1.4006630999999998, - focal_distance: 4.0, - focal_slope: 1.1, - horiz_offset_correction: -0.025999999, - laser_id: 29, - min_intensity: 40.0, - rot_correction: 0.043892943273872005, - vert_correction: 0.08674443287511571, - vert_offset_correction: 0.21282616000000001, - } - - { - dist_correction: 1.2940709000000001, - dist_correction_x: 1.392794, - dist_correction_y: 1.3225565000000001, - focal_distance: 8.0, - focal_slope: 0.89999998, - horiz_offset_correction: 0.025999999, - laser_id: 30, - min_intensity: 90.0, - rot_correction: -0.033068739374902546, - vert_correction: 0.02522388232225749, - vert_offset_correction: 0.20838722, - } - - { - dist_correction: 1.3907666, - dist_correction_x: 1.4365166, - dist_correction_y: 1.4501437000000001, - focal_distance: 9.0, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 31, - min_intensity: 5.0, - rot_correction: 0.025535290948715324, - vert_correction: 0.034414332377654115, - vert_offset_correction: 0.20904865, - } - - { - dist_correction: 1.3461819, - dist_correction_x: 1.3678523000000002, - dist_correction_y: 1.3552880999999999, - focal_distance: 11.0, - focal_slope: 1.5, - horiz_offset_correction: 0.025999999, - laser_id: 32, - min_intensity: 45.0, - rot_correction: -0.13309965698710405, - vert_correction: -0.39666389380060213, - vert_offset_correction: 0.10812234999999999, - } - - { - dist_correction: 1.2487466, - dist_correction_x: 1.2929747, - dist_correction_y: 1.3438803, - focal_distance: 5.0, - focal_slope: 0.89999998, - horiz_offset_correction: -0.025999999, - laser_id: 33, - min_intensity: 35.0, - rot_correction: -0.07241159183553281, - vert_correction: -0.39021216204755743, - vert_offset_correction: 0.10859233, - } - - { - dist_correction: 1.5016498000000003, - dist_correction_x: 1.5384890999999998, - dist_correction_y: 1.5506186, - focal_distance: 4.5, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 34, - min_intensity: 20.0, - rot_correction: 0.08292710807634829, - vert_correction: -0.2010672181773803, - vert_offset_correction: 0.12148494, - } - - { - dist_correction: 1.2495708, - dist_correction_x: 1.2891127, - dist_correction_y: 1.2943669, - focal_distance: 11.0, - focal_slope: 1.3, - horiz_offset_correction: -0.025999999, - laser_id: 35, - min_intensity: 25.0, - rot_correction: 0.14006506182829093, - vert_correction: -0.19103771853737994, - vert_offset_correction: 0.12213274, - } - - { - dist_correction: 1.2674536, - dist_correction_x: 1.3298663, - dist_correction_y: 1.3577469, - focal_distance: 6.0, - focal_slope: 0.89999998, - horiz_offset_correction: 0.025999999, - laser_id: 36, - min_intensity: 35.0, - rot_correction: -0.012004346320883118, - vert_correction: -0.3819670695815035, - vert_offset_correction: 0.10918932, - } - - { - dist_correction: 1.2481956, - dist_correction_x: 1.28627, - dist_correction_y: 1.29235, - focal_distance: 14.5, - focal_slope: 1.5, - horiz_offset_correction: -0.025999999, - laser_id: 37, - min_intensity: 30.0, - rot_correction: 0.04832190474636683, - vert_correction: -0.3718940414299584, - vert_offset_correction: 0.10991334, - } - - { - dist_correction: 1.4516722, - dist_correction_x: 1.4842308, - dist_correction_y: 1.4868384000000001, - focal_distance: 4.0, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 38, - min_intensity: 55.0, - rot_correction: -0.03583078923869515, - vert_correction: -0.4336284663746853, - vert_offset_correction: 0.1053787, - } - - { - dist_correction: 1.3843003999999999, - dist_correction_x: 1.4010727, - dist_correction_y: 1.4332015999999999, - focal_distance: 6.5, - focal_slope: 1.3, - horiz_offset_correction: -0.025999999, - laser_id: 39, - min_intensity: 40.0, - rot_correction: 0.026883486237381612, - vert_correction: -0.4261966798867682, - vert_offset_correction: 0.10593759000000001, - } - - { - dist_correction: 1.244738, - dist_correction_x: 1.3131859000000001, - dist_correction_y: 1.354245, - focal_distance: 6.5, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 40, - min_intensity: 25.0, - rot_correction: 0.1076316048478218, - vert_correction: -0.3640637439139335, - vert_offset_correction: 0.11047223, - } - - { - dist_correction: 1.3284543, - dist_correction_x: 1.3295518000000002, - dist_correction_y: 1.3809489, - focal_distance: 12.5, - focal_slope: 1.7, - horiz_offset_correction: -0.025999999, - laser_id: 41, - min_intensity: 50.0, - rot_correction: 0.1679293847080498, - vert_correction: -0.3511493721000192, - vert_offset_correction: 0.11138678, - } - - { - dist_correction: 1.4055542, - dist_correction_x: 1.4426663, - dist_correction_y: 1.430847, - focal_distance: 1.5, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 42, - min_intensity: 10.0, - rot_correction: 0.0861156692854385, - vert_correction: -0.4163231777753111, - vert_offset_correction: 0.10667431000000001, - } - - { - dist_correction: 1.3529747, - dist_correction_x: 1.3834917999999998, - dist_correction_y: 1.4029074, - focal_distance: 6.0, - focal_slope: 1.2, - horiz_offset_correction: -0.025999999, - laser_id: 43, - min_intensity: 35.0, - rot_correction: 0.15024020221305323, - vert_correction: -0.4046365927302973, - vert_offset_correction: 0.10753805, - } - - { - dist_correction: 1.2407380000000001, - dist_correction_x: 1.3171521000000002, - dist_correction_y: 1.2836400000000001, - focal_distance: 15.0, - focal_slope: 1.6, - horiz_offset_correction: 0.025999999, - laser_id: 44, - max_intensity: 220.0, - rot_correction: -0.12998527227122358, - vert_correction: -0.28892197890806653, - vert_offset_correction: 0.11568009, - } - - { - dist_correction: 1.5288051999999999, - dist_correction_x: 1.5904514, - dist_correction_y: 1.6288455, - focal_distance: 10.0, - focal_slope: 0.89999998, - horiz_offset_correction: -0.025999999, - laser_id: 45, - rot_correction: -0.07009281894983248, - vert_correction: -0.28120381879648226, - vert_offset_correction: 0.11620087, - } - - { - dist_correction: 1.5423979, - dist_correction_x: 1.5919412, - dist_correction_y: 1.610177, - focal_distance: 13.0, - focal_slope: 1.7, - horiz_offset_correction: 0.025999999, - laser_id: 46, - rot_correction: -0.1533711640661691, - vert_correction: -0.34156398894148127, - vert_offset_correction: 0.11205999, - } - - { - dist_correction: 1.3086252999999999, - dist_correction_x: 1.3737134, - dist_correction_y: 1.4177727, - focal_distance: 5.5, - focal_slope: 0.89999998, - horiz_offset_correction: -0.025999999, - laser_id: 47, - rot_correction: -0.0927890927600715, - vert_correction: -0.3348332488542128, - vert_offset_correction: 0.11252997, - } - - { - dist_correction: 1.3405330000000002, - dist_correction_x: 1.4512436, - dist_correction_y: 1.4471467999999998, - focal_distance: 13.5, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 48, - rot_correction: -0.012004348415278218, - vert_correction: -0.2738300470529015, - vert_offset_correction: 0.11669625, - } - - { - dist_correction: 1.2994545, - dist_correction_x: 1.3971343999999999, - dist_correction_y: 1.36849, - focal_distance: 14.0, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 49, - rot_correction: 0.047471358677980184, - vert_correction: -0.2649030020882158, - vert_offset_correction: 0.11729325, - } - - { - dist_correction: 1.4499762999999999, - dist_correction_x: 1.5111346, - dist_correction_y: 1.542395, - focal_distance: 13.0, - focal_slope: 1.2, - horiz_offset_correction: 0.025999999, - laser_id: 50, - rot_correction: -0.03378136079915033, - vert_correction: -0.32678797913421975, - vert_offset_correction: 0.11308886, - } - - { - dist_correction: 1.3516956, - dist_correction_x: 1.4231836999999998, - dist_correction_y: 1.4301146, - focal_distance: 13.0, - focal_slope: 1.1, - horiz_offset_correction: -0.025999999, - laser_id: 51, - rot_correction: 0.025334358173250228, - vert_correction: -0.3179609589889659, - vert_offset_correction: 0.11369856, - } - - { - dist_correction: 1.2374236, - dist_correction_x: 1.308008, - dist_correction_y: 1.3549429000000002, - focal_distance: 5.0, - focal_slope: 0.89999998, - horiz_offset_correction: 0.025999999, - laser_id: 52, - rot_correction: 0.10481975724981128, - vert_correction: -0.25478428121685354, - vert_offset_correction: 0.11796646000000001, - } - - { - dist_correction: 1.3730562000000002, - dist_correction_x: 1.403678, - dist_correction_y: 1.4347415000000001, - focal_distance: 13.0, - focal_slope: 1.4, - horiz_offset_correction: -0.025999999, - laser_id: 53, - rot_correction: 0.16311715242247551, - vert_correction: -0.24576616497179882, - vert_offset_correction: 0.11856346000000001, - } - - { - dist_correction: 1.4445888, - dist_correction_x: 1.5025624, - dist_correction_y: 1.5189749000000001, - focal_distance: 10.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 54, - rot_correction: 0.08384971878954978, - vert_correction: -0.31000962288931516, - vert_offset_correction: 0.11424474999999999, - } - - { - dist_correction: 1.3861449, - dist_correction_x: 1.4228815000000001, - dist_correction_y: 1.4620186000000002, - focal_distance: 15.0, - focal_slope: 1.6, - horiz_offset_correction: -0.025999999, - laser_id: 55, - rot_correction: 0.14374613400834294, - vert_correction: -0.2986601307360315, - vert_offset_correction: 0.11501958000000001, - } - - { - dist_correction: 1.4635341, - dist_correction_x: 1.5232283000000002, - dist_correction_y: 1.5063837000000002, - focal_distance: 13.0, - focal_slope: 1.3, - horiz_offset_correction: 0.025999999, - laser_id: 56, - rot_correction: -0.12741928396895377, - vert_correction: -0.18393445537456576, - vert_offset_correction: 0.12259002000000001, - } - - { - dist_correction: 1.3715826000000002, - dist_correction_x: 1.4186972, - dist_correction_y: 1.4328435, - focal_distance: 3.5, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 57, - rot_correction: -0.06853129555735342, - vert_correction: -0.1744342722087932, - vert_offset_correction: 0.12319972, - } - - { - dist_correction: 1.4644831999999999, - dist_correction_x: 1.5095984000000002, - dist_correction_y: 1.5149265, - focal_distance: 11.0, - focal_slope: 1.4, - horiz_offset_correction: 0.025999999, - laser_id: 58, - rot_correction: -0.1497316045423758, - vert_correction: -0.23400086557751998, - vert_offset_correction: 0.11933828, - } - - { - dist_correction: 1.3074548, - dist_correction_x: 1.3521214000000001, - dist_correction_y: 1.3830151000000002, - focal_distance: 5.0, - focal_slope: 0.89999998, - horiz_offset_correction: -0.025999999, - laser_id: 59, - rot_correction: -0.08973572126418226, - vert_correction: -0.22644383426247983, - vert_offset_correction: 0.11983367, - } - - { - dist_correction: 1.4378391, - dist_correction_x: 1.4799687000000001, - dist_correction_y: 1.4889211, - focal_distance: 5.0, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 60, - rot_correction: -0.011751946229237658, - vert_correction: -0.1678843098347878, - vert_offset_correction: 0.12361888, - } - - { - dist_correction: 1.3585466, - dist_correction_x: 1.4135242, - dist_correction_y: 1.4170488, - focal_distance: 2.0, - focal_slope: 0.89999998, - horiz_offset_correction: -0.025999999, - laser_id: 61, - rot_correction: 0.04489272721060892, - vert_correction: -0.158331168143522, - vert_offset_correction: 0.12422858, - } - - { - dist_correction: 1.4478067, - dist_correction_x: 1.5442529, - dist_correction_y: 1.5512207, - focal_distance: 10.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 62, - rot_correction: -0.0340408982402389, - vert_correction: -0.21671681763514258, - vert_offset_correction: 0.12046877, - } - - { - dist_correction: 1.4329738, - dist_correction_x: 1.4817114, - dist_correction_y: 1.4954124, - focal_distance: 9.0, - focal_slope: 0.80000001, - horiz_offset_correction: -0.025999999, - laser_id: 63, - rot_correction: 0.024857907722065305, - vert_correction: -0.2106649408137298, - vert_offset_correction: 0.12086253, + - { + dist_correction: 1.5195264000000002, + dist_correction_x: 1.5500304, + dist_correction_y: 1.5231381, + focal_distance: 12.0, + focal_slope: 1.4, + horiz_offset_correction: 0.025999999, + laser_id: 0, + max_intensity: 235.0, + min_intensity: 30.0, + rot_correction: -0.1248942899601548, + vert_correction: -0.15304134919741974, + vert_offset_correction: 0.19548199, + } + - { + dist_correction: 1.5145139, + dist_correction_x: 1.5256960000000002, + dist_correction_y: 1.5491043, + focal_distance: 5.0, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 1, + min_intensity: 40.0, + rot_correction: -0.06924466398252106, + vert_correction: -0.1458455539136526, + vert_offset_correction: 0.19601112, + } + - { + dist_correction: 1.4963768, + dist_correction_x: 1.5571011, + dist_correction_y: 1.5456782999999998, + focal_distance: 5.0, + focal_slope: 0.89999998, + horiz_offset_correction: 0.025999999, + laser_id: 2, + min_intensity: 60.0, + rot_correction: 0.0824016906676694, + vert_correction: 0.04339494149708345, + vert_offset_correction: 0.20969539999999998, + } + - { + dist_correction: 1.3771207, + dist_correction_x: 1.4103835, + dist_correction_y: 1.4343457000000002, + focal_distance: 9.5, + focal_slope: 1.1, + horiz_offset_correction: -0.025999999, + laser_id: 3, + min_intensity: 20.0, + rot_correction: 0.137808349360133, + vert_correction: 0.05196082373432465, + vert_offset_correction: 0.21031273, + } + - { + dist_correction: 1.2947885, + dist_correction_x: 1.3720455999999999, + dist_correction_y: 1.4025244000000001, + focal_distance: 10.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 4, + min_intensity: 50.0, + rot_correction: -0.011199603626188263, + vert_correction: -0.1358262679404349, + vert_offset_correction: 0.19674603999999998, + } + - { + dist_correction: 1.4395787000000002, + dist_correction_x: 1.4801956, + dist_correction_y: 1.5074649, + focal_distance: 7.0, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 5, + min_intensity: 30.0, + rot_correction: 0.045795414990398894, + vert_correction: -0.12678532627942263, + vert_offset_correction: 0.19740747, + } + - { + dist_correction: 1.3618773, + dist_correction_x: 1.4004077000000001, + dist_correction_y: 1.3900876, + focal_distance: 5.0, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 6, + min_intensity: 65.0, + rot_correction: -0.031646046452444135, + vert_correction: -0.1895564226946273, + vert_offset_correction: 0.19277746, + } + - { + dist_correction: 1.5325716, + dist_correction_x: 1.5337143, + dist_correction_y: 1.5452948000000002, + focal_distance: 6.0, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 7, + min_intensity: 10.0, + rot_correction: 0.023408326257150665, + vert_correction: -0.18086723120040343, + vert_offset_correction: 0.19342419, + } + - { + dist_correction: 1.3743323, + dist_correction_x: 1.4474606, + dist_correction_y: 1.4533472, + focal_distance: 6.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 8, + min_intensity: 30.0, + rot_correction: 0.10065885915180103, + vert_correction: -0.11973897655818674, + vert_offset_correction: 0.19792192, + } + - { + dist_correction: 1.4969112000000002, + dist_correction_x: 1.4754176, + dist_correction_y: 1.4888799000000001, + focal_distance: 5.0, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 9, + min_intensity: 10.0, + rot_correction: 0.15996423607269877, + vert_correction: -0.10924820210484752, + vert_offset_correction: 0.19868624000000001, + } + - { + dist_correction: 1.434263, + dist_correction_x: 1.4957901000000002, + dist_correction_y: 1.5191892999999999, + focal_distance: 5.0, + focal_slope: 0.89999998, + horiz_offset_correction: 0.025999999, + laser_id: 10, + min_intensity: 35.0, + rot_correction: 0.08313316164783874, + vert_correction: -0.17135657256846043, + vert_offset_correction: 0.19412970999999998, + } + - { + dist_correction: 1.5500841, + dist_correction_x: 1.542697, + dist_correction_y: 1.5716737, + focal_distance: 8.0, + focal_slope: 1.2, + horiz_offset_correction: -0.025999999, + laser_id: 11, + min_intensity: 30.0, + rot_correction: 0.13862572370075624, + vert_correction: -0.1630088948849621, + vert_offset_correction: 0.19474705, + } + - { + dist_correction: 1.3725992, + dist_correction_x: 1.4353555, + dist_correction_y: 1.3932405, + focal_distance: 11.0, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 12, + min_intensity: 50.0, + rot_correction: -0.1255805045528199, + vert_correction: -0.04526314018308893, + vert_offset_correction: 0.20331627000000002, + } + - { + dist_correction: 1.3111591000000002, + dist_correction_x: 1.3470857, + dist_correction_y: 1.3652054000000002, + focal_distance: 6.0, + focal_slope: 0.69999999, + horiz_offset_correction: -0.025999999, + laser_id: 13, + min_intensity: 30.0, + rot_correction: -0.06716508498014805, + vert_correction: -0.03587557613263058, + vert_offset_correction: 0.20399239000000002, + } + - { + dist_correction: 1.5360803, + dist_correction_x: 1.5528035, + dist_correction_y: 1.5666801000000001, + focal_distance: 8.0, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 14, + min_intensity: 20.0, + rot_correction: -0.14578889529014513, + vert_correction: -0.09893566067472198, + vert_offset_correction: 0.19943586, + } + - { + dist_correction: 1.4755448999999998, + dist_correction_x: 1.5032428, + dist_correction_y: 1.5326752, + focal_distance: 5.0, + focal_slope: 0.89999998, + horiz_offset_correction: -0.025999999, + laser_id: 15, + min_intensity: 30.0, + rot_correction: -0.08892898296002069, + vert_correction: -0.09062974348423608, + vert_offset_correction: 0.20003851, + } + - { + dist_correction: 1.4410587000000001, + dist_correction_x: 1.4870845, + dist_correction_y: 1.4627965, + focal_distance: 18.0, + focal_slope: 0.5, + horiz_offset_correction: 0.025999999, + laser_id: 16, + min_intensity: 40.0, + rot_correction: -0.013006177528832626, + vert_correction: -0.02770725895504266, + vert_offset_correction: 0.20458033, + } + - { + dist_correction: 1.4434521, + dist_correction_x: 1.4897508, + dist_correction_y: 1.4791382, + focal_distance: 11.0, + focal_slope: 0.80000001, + horiz_offset_correction: -0.025999999, + laser_id: 17, + min_intensity: 55.0, + rot_correction: 0.04596628970548614, + vert_correction: -0.02014825541794774, + vert_offset_correction: 0.20512417, + } + - { + dist_correction: 1.3243448000000002, + dist_correction_x: 1.3816666000000002, + dist_correction_y: 1.3647719, + focal_distance: 12.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 18, + min_intensity: 10.0, + rot_correction: -0.03237303019110658, + vert_correction: -0.08210824496987311, + vert_offset_correction: 0.20065581999999998, + } + - { + dist_correction: 1.4565853999999998, + dist_correction_x: 1.4340645, + dist_correction_y: 1.4550516, + focal_distance: 20.0, + focal_slope: 0.69999999, + horiz_offset_correction: -0.025999999, + laser_id: 19, + min_intensity: 30.0, + rot_correction: 0.02431275238487562, + vert_correction: -0.0727614640280461, + vert_offset_correction: 0.20133196000000003, + } + - { + dist_correction: 1.3313776, + dist_correction_x: 1.3819601000000001, + dist_correction_y: 1.3847791, + focal_distance: 5.0, + focal_slope: 0.89999998, + horiz_offset_correction: 0.025999999, + laser_id: 20, + min_intensity: 45.0, + rot_correction: 0.10029393174916004, + vert_correction: -0.009929893699589059, + vert_offset_correction: 0.20585909000000002, + } + - { + dist_correction: 1.3787535, + dist_correction_x: 1.3978789, + dist_correction_y: 1.4257806, + focal_distance: 10.0, + focal_slope: 1.1, + horiz_offset_correction: -0.025999999, + laser_id: 21, + min_intensity: 35.0, + rot_correction: 0.15867894419560363, + vert_correction: -0.0037977317325845416, + vert_offset_correction: 0.20630005, + } + - { + dist_correction: 1.3419412, + dist_correction_x: 1.4059189, + dist_correction_y: 1.4113303, + focal_distance: 11.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 22, + min_intensity: 40.0, + rot_correction: 0.08044522544540282, + vert_correction: -0.06482699129962814, + vert_offset_correction: 0.20190518999999998, + } + - { + dist_correction: 1.4338304, + dist_correction_x: 1.4212059, + dist_correction_y: 1.4900565000000001, + focal_distance: 11.0, + focal_slope: 1.1, + horiz_offset_correction: -0.025999999, + laser_id: 23, + min_intensity: 55.0, + rot_correction: 0.13867708175932542, + vert_correction: -0.05566171063737453, + vert_offset_correction: 0.20256662, + } + - { + dist_correction: 1.4930911, + dist_correction_x: 1.5572188, + dist_correction_y: 1.5182672, + focal_distance: 5.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 24, + min_intensity: 25.0, + rot_correction: -0.12505298227706313, + vert_correction: 0.06113007152996804, + vert_offset_correction: 0.21097416, + } + - { + dist_correction: 1.4367653000000002, + dist_correction_x: 1.4614236, + dist_correction_y: 1.4587589, + focal_distance: 3.0, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 25, + min_intensity: 50.0, + rot_correction: -0.06814826559971075, + vert_correction: 0.06988221181432357, + vert_offset_correction: 0.21160620000000002, + } + - { + dist_correction: 1.5279892000000002, + dist_correction_x: 1.5686107999999999, + dist_correction_y: 1.55737, + focal_distance: 7.5, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 26, + min_intensity: 30.0, + rot_correction: -0.14531660046790917, + vert_correction: 0.00887576771486082, + vert_offset_correction: 0.20721134, + } + - { + dist_correction: 1.5077638, + dist_correction_x: 1.5453738000000001, + dist_correction_y: 1.5483368, + focal_distance: 4.0, + focal_slope: 0.89999998, + horiz_offset_correction: -0.025999999, + laser_id: 27, + min_intensity: 30.0, + rot_correction: -0.08904354811745085, + vert_correction: 0.017050959569839413, + vert_offset_correction: 0.20779928000000003, + } + - { + dist_correction: 1.3627797000000001, + dist_correction_x: 1.4232985, + dist_correction_y: 1.4116524000000001, + focal_distance: 4.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 28, + min_intensity: 50.0, + rot_correction: -0.012061568860271928, + vert_correction: 0.07842048992411524, + vert_offset_correction: 0.21222351, + } + - { + dist_correction: 1.3749608, + dist_correction_x: 1.4045798, + dist_correction_y: 1.4006630999999998, + focal_distance: 4.0, + focal_slope: 1.1, + horiz_offset_correction: -0.025999999, + laser_id: 29, + min_intensity: 40.0, + rot_correction: 0.043892943273872005, + vert_correction: 0.08674443287511571, + vert_offset_correction: 0.21282616000000001, + } + - { + dist_correction: 1.2940709000000001, + dist_correction_x: 1.392794, + dist_correction_y: 1.3225565000000001, + focal_distance: 8.0, + focal_slope: 0.89999998, + horiz_offset_correction: 0.025999999, + laser_id: 30, + min_intensity: 90.0, + rot_correction: -0.033068739374902546, + vert_correction: 0.02522388232225749, + vert_offset_correction: 0.20838722, + } + - { + dist_correction: 1.3907666, + dist_correction_x: 1.4365166, + dist_correction_y: 1.4501437000000001, + focal_distance: 9.0, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 31, + min_intensity: 5.0, + rot_correction: 0.025535290948715324, + vert_correction: 0.034414332377654115, + vert_offset_correction: 0.20904865, + } + - { + dist_correction: 1.3461819, + dist_correction_x: 1.3678523000000002, + dist_correction_y: 1.3552880999999999, + focal_distance: 11.0, + focal_slope: 1.5, + horiz_offset_correction: 0.025999999, + laser_id: 32, + min_intensity: 45.0, + rot_correction: -0.13309965698710405, + vert_correction: -0.39666389380060213, + vert_offset_correction: 0.10812234999999999, + } + - { + dist_correction: 1.2487466, + dist_correction_x: 1.2929747, + dist_correction_y: 1.3438803, + focal_distance: 5.0, + focal_slope: 0.89999998, + horiz_offset_correction: -0.025999999, + laser_id: 33, + min_intensity: 35.0, + rot_correction: -0.07241159183553281, + vert_correction: -0.39021216204755743, + vert_offset_correction: 0.10859233, + } + - { + dist_correction: 1.5016498000000003, + dist_correction_x: 1.5384890999999998, + dist_correction_y: 1.5506186, + focal_distance: 4.5, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 34, + min_intensity: 20.0, + rot_correction: 0.08292710807634829, + vert_correction: -0.2010672181773803, + vert_offset_correction: 0.12148494, + } + - { + dist_correction: 1.2495708, + dist_correction_x: 1.2891127, + dist_correction_y: 1.2943669, + focal_distance: 11.0, + focal_slope: 1.3, + horiz_offset_correction: -0.025999999, + laser_id: 35, + min_intensity: 25.0, + rot_correction: 0.14006506182829093, + vert_correction: -0.19103771853737994, + vert_offset_correction: 0.12213274, + } + - { + dist_correction: 1.2674536, + dist_correction_x: 1.3298663, + dist_correction_y: 1.3577469, + focal_distance: 6.0, + focal_slope: 0.89999998, + horiz_offset_correction: 0.025999999, + laser_id: 36, + min_intensity: 35.0, + rot_correction: -0.012004346320883118, + vert_correction: -0.3819670695815035, + vert_offset_correction: 0.10918932, + } + - { + dist_correction: 1.2481956, + dist_correction_x: 1.28627, + dist_correction_y: 1.29235, + focal_distance: 14.5, + focal_slope: 1.5, + horiz_offset_correction: -0.025999999, + laser_id: 37, + min_intensity: 30.0, + rot_correction: 0.04832190474636683, + vert_correction: -0.3718940414299584, + vert_offset_correction: 0.10991334, + } + - { + dist_correction: 1.4516722, + dist_correction_x: 1.4842308, + dist_correction_y: 1.4868384000000001, + focal_distance: 4.0, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 38, + min_intensity: 55.0, + rot_correction: -0.03583078923869515, + vert_correction: -0.4336284663746853, + vert_offset_correction: 0.1053787, + } + - { + dist_correction: 1.3843003999999999, + dist_correction_x: 1.4010727, + dist_correction_y: 1.4332015999999999, + focal_distance: 6.5, + focal_slope: 1.3, + horiz_offset_correction: -0.025999999, + laser_id: 39, + min_intensity: 40.0, + rot_correction: 0.026883486237381612, + vert_correction: -0.4261966798867682, + vert_offset_correction: 0.10593759000000001, + } + - { + dist_correction: 1.244738, + dist_correction_x: 1.3131859000000001, + dist_correction_y: 1.354245, + focal_distance: 6.5, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 40, + min_intensity: 25.0, + rot_correction: 0.1076316048478218, + vert_correction: -0.3640637439139335, + vert_offset_correction: 0.11047223, + } + - { + dist_correction: 1.3284543, + dist_correction_x: 1.3295518000000002, + dist_correction_y: 1.3809489, + focal_distance: 12.5, + focal_slope: 1.7, + horiz_offset_correction: -0.025999999, + laser_id: 41, + min_intensity: 50.0, + rot_correction: 0.1679293847080498, + vert_correction: -0.3511493721000192, + vert_offset_correction: 0.11138678, + } + - { + dist_correction: 1.4055542, + dist_correction_x: 1.4426663, + dist_correction_y: 1.430847, + focal_distance: 1.5, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 42, + min_intensity: 10.0, + rot_correction: 0.0861156692854385, + vert_correction: -0.4163231777753111, + vert_offset_correction: 0.10667431000000001, + } + - { + dist_correction: 1.3529747, + dist_correction_x: 1.3834917999999998, + dist_correction_y: 1.4029074, + focal_distance: 6.0, + focal_slope: 1.2, + horiz_offset_correction: -0.025999999, + laser_id: 43, + min_intensity: 35.0, + rot_correction: 0.15024020221305323, + vert_correction: -0.4046365927302973, + vert_offset_correction: 0.10753805, + } + - { + dist_correction: 1.2407380000000001, + dist_correction_x: 1.3171521000000002, + dist_correction_y: 1.2836400000000001, + focal_distance: 15.0, + focal_slope: 1.6, + horiz_offset_correction: 0.025999999, + laser_id: 44, + max_intensity: 220.0, + rot_correction: -0.12998527227122358, + vert_correction: -0.28892197890806653, + vert_offset_correction: 0.11568009, + } + - { + dist_correction: 1.5288051999999999, + dist_correction_x: 1.5904514, + dist_correction_y: 1.6288455, + focal_distance: 10.0, + focal_slope: 0.89999998, + horiz_offset_correction: -0.025999999, + laser_id: 45, + rot_correction: -0.07009281894983248, + vert_correction: -0.28120381879648226, + vert_offset_correction: 0.11620087, + } + - { + dist_correction: 1.5423979, + dist_correction_x: 1.5919412, + dist_correction_y: 1.610177, + focal_distance: 13.0, + focal_slope: 1.7, + horiz_offset_correction: 0.025999999, + laser_id: 46, + rot_correction: -0.1533711640661691, + vert_correction: -0.34156398894148127, + vert_offset_correction: 0.11205999, + } + - { + dist_correction: 1.3086252999999999, + dist_correction_x: 1.3737134, + dist_correction_y: 1.4177727, + focal_distance: 5.5, + focal_slope: 0.89999998, + horiz_offset_correction: -0.025999999, + laser_id: 47, + rot_correction: -0.0927890927600715, + vert_correction: -0.3348332488542128, + vert_offset_correction: 0.11252997, + } + - { + dist_correction: 1.3405330000000002, + dist_correction_x: 1.4512436, + dist_correction_y: 1.4471467999999998, + focal_distance: 13.5, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 48, + rot_correction: -0.012004348415278218, + vert_correction: -0.2738300470529015, + vert_offset_correction: 0.11669625, + } + - { + dist_correction: 1.2994545, + dist_correction_x: 1.3971343999999999, + dist_correction_y: 1.36849, + focal_distance: 14.0, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 49, + rot_correction: 0.047471358677980184, + vert_correction: -0.2649030020882158, + vert_offset_correction: 0.11729325, + } + - { + dist_correction: 1.4499762999999999, + dist_correction_x: 1.5111346, + dist_correction_y: 1.542395, + focal_distance: 13.0, + focal_slope: 1.2, + horiz_offset_correction: 0.025999999, + laser_id: 50, + rot_correction: -0.03378136079915033, + vert_correction: -0.32678797913421975, + vert_offset_correction: 0.11308886, + } + - { + dist_correction: 1.3516956, + dist_correction_x: 1.4231836999999998, + dist_correction_y: 1.4301146, + focal_distance: 13.0, + focal_slope: 1.1, + horiz_offset_correction: -0.025999999, + laser_id: 51, + rot_correction: 0.025334358173250228, + vert_correction: -0.3179609589889659, + vert_offset_correction: 0.11369856, + } + - { + dist_correction: 1.2374236, + dist_correction_x: 1.308008, + dist_correction_y: 1.3549429000000002, + focal_distance: 5.0, + focal_slope: 0.89999998, + horiz_offset_correction: 0.025999999, + laser_id: 52, + rot_correction: 0.10481975724981128, + vert_correction: -0.25478428121685354, + vert_offset_correction: 0.11796646000000001, + } + - { + dist_correction: 1.3730562000000002, + dist_correction_x: 1.403678, + dist_correction_y: 1.4347415000000001, + focal_distance: 13.0, + focal_slope: 1.4, + horiz_offset_correction: -0.025999999, + laser_id: 53, + rot_correction: 0.16311715242247551, + vert_correction: -0.24576616497179882, + vert_offset_correction: 0.11856346000000001, + } + - { + dist_correction: 1.4445888, + dist_correction_x: 1.5025624, + dist_correction_y: 1.5189749000000001, + focal_distance: 10.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 54, + rot_correction: 0.08384971878954978, + vert_correction: -0.31000962288931516, + vert_offset_correction: 0.11424474999999999, + } + - { + dist_correction: 1.3861449, + dist_correction_x: 1.4228815000000001, + dist_correction_y: 1.4620186000000002, + focal_distance: 15.0, + focal_slope: 1.6, + horiz_offset_correction: -0.025999999, + laser_id: 55, + rot_correction: 0.14374613400834294, + vert_correction: -0.2986601307360315, + vert_offset_correction: 0.11501958000000001, + } + - { + dist_correction: 1.4635341, + dist_correction_x: 1.5232283000000002, + dist_correction_y: 1.5063837000000002, + focal_distance: 13.0, + focal_slope: 1.3, + horiz_offset_correction: 0.025999999, + laser_id: 56, + rot_correction: -0.12741928396895377, + vert_correction: -0.18393445537456576, + vert_offset_correction: 0.12259002000000001, + } + - { + dist_correction: 1.3715826000000002, + dist_correction_x: 1.4186972, + dist_correction_y: 1.4328435, + focal_distance: 3.5, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 57, + rot_correction: -0.06853129555735342, + vert_correction: -0.1744342722087932, + vert_offset_correction: 0.12319972, + } + - { + dist_correction: 1.4644831999999999, + dist_correction_x: 1.5095984000000002, + dist_correction_y: 1.5149265, + focal_distance: 11.0, + focal_slope: 1.4, + horiz_offset_correction: 0.025999999, + laser_id: 58, + rot_correction: -0.1497316045423758, + vert_correction: -0.23400086557751998, + vert_offset_correction: 0.11933828, + } + - { + dist_correction: 1.3074548, + dist_correction_x: 1.3521214000000001, + dist_correction_y: 1.3830151000000002, + focal_distance: 5.0, + focal_slope: 0.89999998, + horiz_offset_correction: -0.025999999, + laser_id: 59, + rot_correction: -0.08973572126418226, + vert_correction: -0.22644383426247983, + vert_offset_correction: 0.11983367, + } + - { + dist_correction: 1.4378391, + dist_correction_x: 1.4799687000000001, + dist_correction_y: 1.4889211, + focal_distance: 5.0, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 60, + rot_correction: -0.011751946229237658, + vert_correction: -0.1678843098347878, + vert_offset_correction: 0.12361888, + } + - { + dist_correction: 1.3585466, + dist_correction_x: 1.4135242, + dist_correction_y: 1.4170488, + focal_distance: 2.0, + focal_slope: 0.89999998, + horiz_offset_correction: -0.025999999, + laser_id: 61, + rot_correction: 0.04489272721060892, + vert_correction: -0.158331168143522, + vert_offset_correction: 0.12422858, + } + - { + dist_correction: 1.4478067, + dist_correction_x: 1.5442529, + dist_correction_y: 1.5512207, + focal_distance: 10.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 62, + rot_correction: -0.0340408982402389, + vert_correction: -0.21671681763514258, + vert_offset_correction: 0.12046877, + } + - { + dist_correction: 1.4329738, + dist_correction_x: 1.4817114, + dist_correction_y: 1.4954124, + focal_distance: 9.0, + focal_slope: 0.80000001, + horiz_offset_correction: -0.025999999, + laser_id: 63, + rot_correction: 0.024857907722065305, + vert_correction: -0.2106649408137298, + vert_offset_correction: 0.12086253, } num_lasers: 64 distance_resolution: 0.002 diff --git a/nebula_decoders/calibration/velodyne/HDL64e_s3.yaml b/nebula_decoders/calibration/velodyne/HDL64e_s3.yaml index a398407e9..df8f54e11 100755 --- a/nebula_decoders/calibration/velodyne/HDL64e_s3.yaml +++ b/nebula_decoders/calibration/velodyne/HDL64e_s3.yaml @@ -1,788 +1,788 @@ lasers: - - { - dist_correction: 1.4139490000000001, - dist_correction_x: 1.4198446999999998, - dist_correction_y: 1.4058145, - focal_distance: 10.5, - focal_slope: 1.85, - horiz_offset_correction: 0.025999999, - laser_id: 0, - min_intensity: 5, - rot_correction: -0.07648247457737148, - vert_correction: -0.1261818455292898, - vert_offset_correction: 0.21569468, - } - - { - dist_correction: 1.5094685, - dist_correction_x: 1.5403023, - dist_correction_y: 1.5012577999999999, - focal_distance: 15.0, - focal_slope: 1.2, - horiz_offset_correction: -0.025999999, - laser_id: 1, - min_intensity: 10, - rot_correction: -0.03932070772308096, - vert_correction: -0.11953745909742221, - vert_offset_correction: 0.21520962000000002, - } - - { - dist_correction: 1.4579400999999999, - dist_correction_x: 1.4846666, - dist_correction_y: 1.4228239, - focal_distance: 24.0, - focal_slope: 1.05, - horiz_offset_correction: 0.025999999, - laser_id: 2, - min_intensity: 30, - rot_correction: 0.06005350008746038, - vert_correction: 0.00356118725906175, - vert_offset_correction: 0.20631704, - } - - { - dist_correction: 1.5046124, - dist_correction_x: 1.5335535999999999, - dist_correction_y: 1.5401996, - focal_distance: 14.5, - focal_slope: 1.7, - horiz_offset_correction: -0.025999999, - laser_id: 3, - min_intensity: 10, - rot_correction: 0.09919490315516696, - vert_correction: 0.010306535403103584, - vert_offset_correction: 0.20583200000000001, - } - - { - dist_correction: 1.4370993, - dist_correction_x: 1.4714845, - dist_correction_y: 1.4524646, - focal_distance: 15.0, - focal_slope: 0.40000001, - horiz_offset_correction: 0.025999999, - laser_id: 4, - min_intensity: 30, - rot_correction: -0.00095355016485159, - vert_correction: -0.1144967440141401, - vert_offset_correction: 0.21484217000000003, - } - - { - dist_correction: 1.3536626999999999, - dist_correction_x: 1.3909094, - dist_correction_y: 1.3700326999999999, - focal_distance: 17.0, - focal_slope: 1.45, - horiz_offset_correction: -0.025999999, - laser_id: 5, - min_intensity: 30, - rot_correction: 0.03824387099052699, - vert_correction: -0.10803612329921503, - vert_offset_correction: 0.21437181, - } - - { - dist_correction: 1.4117873, - dist_correction_x: 1.4350795, - dist_correction_y: 1.3829624999999999, - focal_distance: 10.5, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 6, - min_intensity: 10, - rot_correction: -0.015297255529962315, - vert_correction: -0.14944538101702426, - vert_offset_correction: 0.21739968999999998, - } - - { - dist_correction: 1.4269646, - dist_correction_x: 1.451161, - dist_correction_y: 1.4328421, - focal_distance: 14.0, - focal_slope: 1.3, - horiz_offset_correction: -0.025999999, - laser_id: 7, - min_intensity: 10, - rot_correction: 0.024255809272700053, - vert_correction: -0.14344353231329066, - vert_offset_correction: 0.21695873, - } - - { - dist_correction: 1.3808284000000002, - dist_correction_x: 1.421472, - dist_correction_y: 1.3838283000000002, - focal_distance: 15.0, - focal_slope: 0.94999999, - horiz_offset_correction: 0.025999999, - laser_id: 8, - min_intensity: 30, - rot_correction: 0.07354442571180776, - vert_correction: -0.10278016723125998, - vert_offset_correction: 0.21398966000000003, - } - - { - dist_correction: 1.3644336000000001, - dist_correction_x: 1.3931616, - dist_correction_y: 1.3852122, - focal_distance: 12.5, - focal_slope: 1.95, - horiz_offset_correction: -0.025999999, - laser_id: 9, - min_intensity: 10, - rot_correction: 0.11317857886058363, - vert_correction: -0.09569590023202451, - vert_offset_correction: 0.21347521, - } - - { - dist_correction: 1.4102663000000002, - dist_correction_x: 1.4163402, - dist_correction_y: 1.3592377, - focal_distance: 12.5, - focal_slope: 1.95, - horiz_offset_correction: 0.025999999, - laser_id: 10, - min_intensity: 10, - rot_correction: 0.05954228616823424, - vert_correction: -0.1386345201601863, - vert_offset_correction: 0.21660597, - } - - { - dist_correction: 1.5019737000000002, - dist_correction_x: 1.532475, - dist_correction_y: 1.5237663000000001, - focal_distance: 13.0, - focal_slope: 1.9, - horiz_offset_correction: -0.025999999, - laser_id: 11, - min_intensity: 10, - rot_correction: 0.09906092120980835, - vert_correction: -0.13181073657049397, - vert_offset_correction: 0.21610622, - } - - { - dist_correction: 1.4399905000000002, - dist_correction_x: 1.4887962, - dist_correction_y: 1.4455237, - focal_distance: 14.5, - focal_slope: 1.7, - horiz_offset_correction: 0.025999999, - laser_id: 12, - max_intensity: 235, - rot_correction: -0.07574798243226695, - vert_correction: -0.054438932963427306, - vert_offset_correction: 0.21049141, - } - - { - dist_correction: 1.5207593, - dist_correction_x: 1.5401453, - dist_correction_y: 1.5190082, - focal_distance: 20.5, - focal_slope: 1.25, - horiz_offset_correction: -0.025999999, - laser_id: 13, - max_intensity: 240, - rot_correction: -0.037047761947550245, - vert_correction: -0.048730533448148504, - vert_offset_correction: 0.21007986, - } - - { - dist_correction: 1.4746239, - dist_correction_x: 1.5300989999999999, - dist_correction_y: 1.4663734, - focal_distance: 12.5, - focal_slope: 1.9, - horiz_offset_correction: 0.025999999, - laser_id: 14, - max_intensity: 245, - rot_correction: -0.0895955468906376, - vert_correction: -0.08961595328025192, - vert_offset_correction: 0.21303425, - } - - { - dist_correction: 1.4697629, - dist_correction_x: 1.5051735, - dist_correction_y: 1.4558601, - focal_distance: 19.5, - focal_slope: 0.94999999, - horiz_offset_correction: -0.025999999, - laser_id: 15, - max_intensity: 245, - rot_correction: -0.05072966149865084, - vert_correction: -0.0839353306800186, - vert_offset_correction: 0.21262267999999998, - } - - { - dist_correction: 1.4143376, - dist_correction_x: 1.4432597000000003, - dist_correction_y: 1.4038483, - focal_distance: 24.0, - focal_slope: 0.69999999, - horiz_offset_correction: 0.025999999, - laser_id: 16, - max_intensity: 245, - rot_correction: -0.001864320564407547, - vert_correction: -0.043427018903405855, - vert_offset_correction: 0.20969770000000001, - } - - { - dist_correction: 1.4815961, - dist_correction_x: 1.5173615, - dist_correction_y: 1.4871606, - focal_distance: 14.5, - focal_slope: 1.65, - horiz_offset_correction: -0.025999999, - laser_id: 17, - rot_correction: 0.03747852840556422, - vert_correction: -0.03648801216715539, - vert_offset_correction: 0.20919794, - } - - { - dist_correction: 1.420331, - dist_correction_x: 1.4755219, - dist_correction_y: 1.3919118000000001, - focal_distance: 17.5, - focal_slope: 1.4, - horiz_offset_correction: 0.025999999, - laser_id: 18, - rot_correction: -0.015194972429011364, - vert_correction: -0.07906187922560139, - vert_offset_correction: 0.21226994000000002, - } - - { - dist_correction: 1.4900717, - dist_correction_x: 1.5143349000000002, - dist_correction_y: 1.4829907, - focal_distance: 24.0, - focal_slope: 1.25, - horiz_offset_correction: -0.025999999, - laser_id: 19, - rot_correction: 0.02391977928648433, - vert_correction: -0.07255814015150577, - vert_offset_correction: 0.21179958, - } - - { - dist_correction: 1.4823865, - dist_correction_x: 1.5357741999999999, - dist_correction_y: 1.4956403, - focal_distance: 24.0, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 20, - rot_correction: 0.07264374331532833, - vert_correction: -0.031587736747464255, - vert_offset_correction: 0.20884519999999998, - } - - { - dist_correction: 1.5553201, - dist_correction_x: 1.5698593, - dist_correction_y: 1.5624425, - focal_distance: 15.5, - focal_slope: 1.55, - horiz_offset_correction: -0.025999999, - laser_id: 21, - rot_correction: 0.11143265968730214, - vert_correction: -0.025460288914769372, - vert_offset_correction: 0.20840424, - } - - { - dist_correction: 1.4437845999999999, - dist_correction_x: 1.4909378000000002, - dist_correction_y: 1.4347861, - focal_distance: 20.5, - focal_slope: 1.2, - horiz_offset_correction: 0.025999999, - laser_id: 22, - rot_correction: 0.05942554283989759, - vert_correction: -0.06665878416276627, - vert_offset_correction: 0.21137333000000003, - } - - { - dist_correction: 1.4939513, - dist_correction_x: 1.5194868, - dist_correction_y: 1.5106346, - focal_distance: 14.5, - focal_slope: 1.65, - horiz_offset_correction: -0.025999999, - laser_id: 23, - rot_correction: 0.09797042203986979, - vert_correction: -0.06055112836378901, - vert_offset_correction: 0.21093236999999998, - } - - { - dist_correction: 1.4521244999999998, - dist_correction_x: 1.4884882, - dist_correction_y: 1.4649333, - focal_distance: 11.5, - focal_slope: 2.0, - horiz_offset_correction: 0.025999999, - laser_id: 24, - rot_correction: -0.07658879305408597, - vert_correction: 0.015620435355027301, - vert_offset_correction: 0.20544985000000002, - } - - { - dist_correction: 1.5351622, - dist_correction_x: 1.524973, - dist_correction_y: 1.5029565, - focal_distance: 18.5, - focal_slope: 1.25, - horiz_offset_correction: -0.025999999, - laser_id: 25, - rot_correction: -0.0379098725675606, - vert_correction: 0.022567997346205196, - vert_offset_correction: 0.20495010000000002, - } - - { - dist_correction: 1.5321327, - dist_correction_x: 1.5833431999999998, - dist_correction_y: 1.5359726, - focal_distance: 13.0, - focal_slope: 1.9, - horiz_offset_correction: 0.025999999, - laser_id: 26, - rot_correction: -0.0904730670226138, - vert_correction: -0.019943931467746017, - vert_offset_correction: 0.20800737000000002, - } - - { - dist_correction: 1.5166023000000002, - dist_correction_x: 1.4874829, - dist_correction_y: 1.4625635, - focal_distance: 21.5, - focal_slope: 1.1, - horiz_offset_correction: -0.025999999, - laser_id: 27, - rot_correction: -0.051308328902808065, - vert_correction: -0.013200099491225388, - vert_offset_correction: 0.20752234000000003, - } - - { - dist_correction: 1.4549194, - dist_correction_x: 1.4688664, - dist_correction_y: 1.4194371000000001, - focal_distance: 13.5, - focal_slope: 1.83, - horiz_offset_correction: 0.025999999, - laser_id: 28, - rot_correction: -0.0019143155208309244, - vert_correction: 0.027266617424120905, - vert_offset_correction: 0.20461203000000003, - } - - { - dist_correction: 1.5617532, - dist_correction_x: 1.5887217999999999, - dist_correction_y: 1.5643922000000001, - focal_distance: 18.5, - focal_slope: 1.35, - horiz_offset_correction: -0.025999999, - laser_id: 29, - rot_correction: 0.03681404490741569, - vert_correction: 0.03421014630846329, - vert_offset_correction: 0.20411228, - } - - { - dist_correction: 1.5132924, - dist_correction_x: 1.5661812000000002, - dist_correction_y: 1.5102689, - focal_distance: 18.5, - focal_slope: 1.35, - horiz_offset_correction: 0.025999999, - laser_id: 30, - rot_correction: -0.015542064486559148, - vert_correction: -0.007885903531460533, - vert_offset_correction: 0.20714018, - } - - { - dist_correction: 1.5638524, - dist_correction_x: 1.5621136000000002, - dist_correction_y: 1.5383017, - focal_distance: 21.5, - focal_slope: 1.15, - horiz_offset_correction: -0.025999999, - laser_id: 31, - rot_correction: 0.023284423588222334, - vert_correction: -0.0015491891506552067, - vert_offset_correction: 0.20668451000000002, - } - - { - dist_correction: 1.3077792, - dist_correction_x: 1.3433452, - dist_correction_y: 1.2840973, - focal_distance: 10.5, - focal_slope: 2.0, - horiz_offset_correction: 0.025999999, - laser_id: 32, - rot_correction: -0.1278634161583795, - vert_correction: -0.39021216204755743, - vert_offset_correction: 0.15970787, - } - - { - dist_correction: 1.4303885, - dist_correction_x: 1.4429931999999999, - dist_correction_y: 1.4607234, - focal_distance: 0.25, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 33, - rot_correction: -0.066528586091226, - vert_correction: -0.38355018793281753, - vert_offset_correction: 0.15922519, - } - - { - dist_correction: 1.3746819, - dist_correction_x: 1.3873923, - dist_correction_y: 1.4089924999999999, - focal_distance: 0.25, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 34, - rot_correction: 0.08854290740283328, - vert_correction: -0.197138848550284, - vert_offset_correction: 0.14656122, - } - - { - dist_correction: 1.3814778, - dist_correction_x: 1.3932765, - dist_correction_y: 1.4301869, - focal_distance: 11.0, - focal_slope: 2.0, - horiz_offset_correction: -0.025999999, - laser_id: 35, - rot_correction: 0.14547956884148489, - vert_correction: -0.18768579625563228, - vert_offset_correction: 0.14595152, - } - - { - dist_correction: 1.4313307, - dist_correction_x: 1.4734517, - dist_correction_y: 1.4390849000000001, - focal_distance: 9.5, - focal_slope: 1.85, - horiz_offset_correction: 0.025999999, - laser_id: 36, - rot_correction: -0.005071588212420635, - vert_correction: -0.3750836655445631, - vert_offset_correction: 0.15861549, - } - - { - dist_correction: 1.3414835, - dist_correction_x: 1.3820609, - dist_correction_y: 1.355589, - focal_distance: 9.5, - focal_slope: 1.4, - horiz_offset_correction: -0.025999999, - laser_id: 37, - rot_correction: 0.05427589303135225, - vert_correction: -0.36762882325722723, - vert_offset_correction: 0.15808201, - } - - { - dist_correction: 1.4895827, - dist_correction_x: 1.5283238000000001, - dist_correction_y: 1.4803529, - focal_distance: 9.0, - focal_slope: 1.65, - horiz_offset_correction: 0.025999999, - laser_id: 38, - rot_correction: -0.028143856558087547, - vert_correction: -0.4285668719175616, - vert_offset_correction: 0.16254044, - } - - { - dist_correction: 1.3727733000000002, - dist_correction_x: 1.3623596, - dist_correction_y: 1.392661, - focal_distance: 0.25, - focal_slope: 1.15, - horiz_offset_correction: -0.025999999, - laser_id: 39, - rot_correction: 0.03172272051181349, - vert_correction: -0.4214410765541042, - vert_offset_correction: 0.16200695, - } - - { - dist_correction: 1.4348983999999998, - dist_correction_x: 1.4775407000000003, - dist_correction_y: 1.4712174999999998, - focal_distance: 0.25, - focal_slope: 0.92000002, - horiz_offset_correction: 0.025999999, - laser_id: 40, - rot_correction: 0.11411698480351568, - vert_correction: -0.3565455112681652, - vert_offset_correction: 0.15729448, - } - - { - dist_correction: 1.335618, - dist_correction_x: 1.3519691, - dist_correction_y: 1.3315152000000001, - focal_distance: 11.200000000000001, - focal_slope: 2.0, - horiz_offset_correction: -0.025999999, - laser_id: 41, - rot_correction: 0.1735498527902839, - vert_correction: -0.34717860842539194, - vert_offset_correction: 0.15663397, - } - - { - dist_correction: 1.4905824, - dist_correction_x: 1.488313, - dist_correction_y: 1.4948479000000001, - focal_distance: 0.25, - focal_slope: 1.1, - horiz_offset_correction: 0.025999999, - laser_id: 42, - rot_correction: 0.09564756333839054, - vert_correction: -0.4110102035460227, - vert_offset_correction: 0.16123213, - } - - { - dist_correction: 1.3288423, - dist_correction_x: 1.3409723, - dist_correction_y: 1.3440451, - focal_distance: 10.0, - focal_slope: 1.95, - horiz_offset_correction: -0.025999999, - laser_id: 43, - rot_correction: 0.15538288292189534, - vert_correction: -0.40083030888437793, - vert_offset_correction: 0.16048269, - } - - { - dist_correction: 1.3771290999999999, - dist_correction_x: 1.3773239000000002, - dist_correction_y: 1.3497290000000002, - focal_distance: 11.5, - focal_slope: 2.0, - horiz_offset_correction: 0.025999999, - laser_id: 44, - rot_correction: -0.12413605610123538, - vert_correction: -0.2840315837972709, - vert_offset_correction: 0.15228986, - } - - { - dist_correction: 1.3367807, - dist_correction_x: 1.370152, - dist_correction_y: 1.370934, - focal_distance: 0.25, - focal_slope: 0.44999999, - horiz_offset_correction: -0.025999999, - laser_id: 45, - rot_correction: -0.06413447432303407, - vert_correction: -0.27761533458791926, - vert_offset_correction: 0.15185799, - } - - { - dist_correction: 1.4788651, - dist_correction_x: 1.5014308, - dist_correction_y: 1.4727454, - focal_distance: 11.5, - focal_slope: 2.0, - horiz_offset_correction: 0.025999999, - laser_id: 46, - rot_correction: -0.14872602785785152, - vert_correction: -0.3359268721635124, - vert_offset_correction: 0.15584644, - } - - { - dist_correction: 1.3220766000000002, - dist_correction_x: 1.3654865, - dist_correction_y: 1.3739757000000001, - focal_distance: 0.25, - focal_slope: 0.94999999, - horiz_offset_correction: -0.025999999, - laser_id: 47, - rot_correction: -0.08707280959256145, - vert_correction: -0.33026751989087316, - vert_offset_correction: 0.15545268, - } - - { - dist_correction: 1.4612433999999999, - dist_correction_x: 1.5250436, - dist_correction_y: 1.4817635999999998, - focal_distance: 13.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 48, - rot_correction: -0.006799911150716457, - vert_correction: -0.26851710773019805, - vert_offset_correction: 0.15124829, - } - - { - dist_correction: 1.3407353000000002, - dist_correction_x: 1.3478844, - dist_correction_y: 1.3154279, - focal_distance: 13.5, - focal_slope: 1.8, - horiz_offset_correction: -0.025999999, - laser_id: 49, - rot_correction: 0.05242808851765633, - vert_correction: -0.26051854302098837, - vert_offset_correction: 0.1507148, - } - - { - dist_correction: 1.3465115, - dist_correction_x: 1.3874431999999999, - dist_correction_y: 1.3508052000000002, - focal_distance: 12.0, - focal_slope: 1.85, - horiz_offset_correction: 0.025999999, - laser_id: 50, - rot_correction: -0.028383715411859876, - vert_correction: -0.3216451745070007, - vert_offset_correction: 0.15485568000000002, - } - - { - dist_correction: 1.3629696999999998, - dist_correction_x: 1.4037315000000001, - dist_correction_y: 1.3869237, - focal_distance: 12.0, - focal_slope: 1.1, - horiz_offset_correction: -0.025999999, - laser_id: 51, - rot_correction: 0.031843273893907245, - vert_correction: -0.3135280670349956, - vert_offset_correction: 0.15429679000000002, - } - - { - dist_correction: 1.4472754, - dist_correction_x: 1.4817390000000001, - dist_correction_y: 1.4782272, - focal_distance: 2.0, - focal_slope: 1.0, - horiz_offset_correction: 0.025999999, - laser_id: 52, - rot_correction: 0.10955275158734502, - vert_correction: -0.24941678290173272, - vert_offset_correction: 0.14997807999999999, - } - - { - dist_correction: 1.3800671, - dist_correction_x: 1.3796414, - dist_correction_y: 1.3943782, - focal_distance: 11.200000000000001, - focal_slope: 2.0, - horiz_offset_correction: -0.025999999, - laser_id: 53, - rot_correction: 0.16876716543828738, - vert_correction: -0.2409525119882134, - vert_offset_correction: 0.14941919, - } - - { - dist_correction: 1.5190169, - dist_correction_x: 1.5619051, - dist_correction_y: 1.5511705, - focal_distance: 2.5, - focal_slope: 1.05, - horiz_offset_correction: 0.025999999, - laser_id: 54, - rot_correction: 0.09037283276367176, - vert_correction: -0.30313513748485243, - vert_offset_correction: 0.15358547, - } - - { - dist_correction: 1.3803656000000002, - dist_correction_x: 1.3960698, - dist_correction_y: 1.386106, - focal_distance: 12.5, - focal_slope: 1.9, - horiz_offset_correction: -0.025999999, - laser_id: 55, - rot_correction: 0.14871534295217081, - vert_correction: -0.29323634555253386, - vert_offset_correction: 0.15291226, - } - - { - dist_correction: 1.5827696, - dist_correction_x: 1.6050609, - dist_correction_y: 1.5844797, - focal_distance: 10.0, - focal_slope: 1.95, - horiz_offset_correction: 0.025999999, - laser_id: 56, - rot_correction: -0.12100867217308608, - vert_correction: -0.17760463486977288, - vert_offset_correction: 0.14530372, - } - - { - dist_correction: 1.3843919, - dist_correction_x: 1.3915251000000002, - dist_correction_y: 1.4156927, - focal_distance: 0.25, - focal_slope: 0.94999999, - horiz_offset_correction: -0.025999999, - laser_id: 57, - rot_correction: -0.06431965899265843, - vert_correction: -0.17006926832673774, - vert_offset_correction: 0.14482104, - } - - { - dist_correction: 1.5491273, - dist_correction_x: 1.5298964000000002, - dist_correction_y: 1.5107637, - focal_distance: 11.5, - focal_slope: 2.0, - horiz_offset_correction: 0.025999999, - laser_id: 58, - rot_correction: -0.14486168214370612, - vert_correction: -0.22974121500510264, - vert_offset_correction: 0.14868247, - } - - { - dist_correction: 1.3646004, - dist_correction_x: 1.3803583000000001, - dist_correction_y: 1.4061511, - focal_distance: 0.25, - focal_slope: 1.0, - horiz_offset_correction: -0.025999999, - laser_id: 59, - rot_correction: -0.0852480451703211, - vert_correction: -0.22391891879349718, - vert_offset_correction: 0.14830141, - } - - { - dist_correction: 1.5239935, - dist_correction_x: 1.560786, - dist_correction_y: 1.5632524, - focal_distance: 5.0, - focal_slope: 1.15, - horiz_offset_correction: 0.025999999, - laser_id: 60, - rot_correction: -0.005967226432828876, - vert_correction: -0.16231529056824404, - vert_offset_correction: 0.14432566, - } - - { - dist_correction: 1.4112029000000001, - dist_correction_x: 1.4223886, - dist_correction_y: 1.4542918, - focal_distance: 2.5, - focal_slope: 1.05, - horiz_offset_correction: -0.025999999, - laser_id: 61, - rot_correction: 0.050600613599087636, - vert_correction: -0.15314424682880032, - vert_offset_correction: 0.14374136, - } - - { - dist_correction: 1.5013637, - dist_correction_x: 1.5208610999999999, - dist_correction_y: 1.5006433000000001, - focal_distance: 16.5, - focal_slope: 1.25, - horiz_offset_correction: 0.025999999, - laser_id: 62, - rot_correction: -0.027436902217920986, - vert_correction: -0.21457119711920336, - vert_offset_correction: 0.14769171, - } - - { - dist_correction: 1.4423058, - dist_correction_x: 1.4454633000000001, - dist_correction_y: 1.4321198000000002, - focal_distance: 9.0, - focal_slope: 1.45, - horiz_offset_correction: -0.025999999, - laser_id: 63, - rot_correction: 0.0290479702718764, - vert_correction: -0.2079266762969834, - vert_offset_correction: 0.14725984, + - { + dist_correction: 1.4139490000000001, + dist_correction_x: 1.4198446999999998, + dist_correction_y: 1.4058145, + focal_distance: 10.5, + focal_slope: 1.85, + horiz_offset_correction: 0.025999999, + laser_id: 0, + min_intensity: 5, + rot_correction: -0.07648247457737148, + vert_correction: -0.1261818455292898, + vert_offset_correction: 0.21569468, + } + - { + dist_correction: 1.5094685, + dist_correction_x: 1.5403023, + dist_correction_y: 1.5012577999999999, + focal_distance: 15.0, + focal_slope: 1.2, + horiz_offset_correction: -0.025999999, + laser_id: 1, + min_intensity: 10, + rot_correction: -0.03932070772308096, + vert_correction: -0.11953745909742221, + vert_offset_correction: 0.21520962000000002, + } + - { + dist_correction: 1.4579400999999999, + dist_correction_x: 1.4846666, + dist_correction_y: 1.4228239, + focal_distance: 24.0, + focal_slope: 1.05, + horiz_offset_correction: 0.025999999, + laser_id: 2, + min_intensity: 30, + rot_correction: 0.06005350008746038, + vert_correction: 0.00356118725906175, + vert_offset_correction: 0.20631704, + } + - { + dist_correction: 1.5046124, + dist_correction_x: 1.5335535999999999, + dist_correction_y: 1.5401996, + focal_distance: 14.5, + focal_slope: 1.7, + horiz_offset_correction: -0.025999999, + laser_id: 3, + min_intensity: 10, + rot_correction: 0.09919490315516696, + vert_correction: 0.010306535403103584, + vert_offset_correction: 0.20583200000000001, + } + - { + dist_correction: 1.4370993, + dist_correction_x: 1.4714845, + dist_correction_y: 1.4524646, + focal_distance: 15.0, + focal_slope: 0.40000001, + horiz_offset_correction: 0.025999999, + laser_id: 4, + min_intensity: 30, + rot_correction: -0.00095355016485159, + vert_correction: -0.1144967440141401, + vert_offset_correction: 0.21484217000000003, + } + - { + dist_correction: 1.3536626999999999, + dist_correction_x: 1.3909094, + dist_correction_y: 1.3700326999999999, + focal_distance: 17.0, + focal_slope: 1.45, + horiz_offset_correction: -0.025999999, + laser_id: 5, + min_intensity: 30, + rot_correction: 0.03824387099052699, + vert_correction: -0.10803612329921503, + vert_offset_correction: 0.21437181, + } + - { + dist_correction: 1.4117873, + dist_correction_x: 1.4350795, + dist_correction_y: 1.3829624999999999, + focal_distance: 10.5, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 6, + min_intensity: 10, + rot_correction: -0.015297255529962315, + vert_correction: -0.14944538101702426, + vert_offset_correction: 0.21739968999999998, + } + - { + dist_correction: 1.4269646, + dist_correction_x: 1.451161, + dist_correction_y: 1.4328421, + focal_distance: 14.0, + focal_slope: 1.3, + horiz_offset_correction: -0.025999999, + laser_id: 7, + min_intensity: 10, + rot_correction: 0.024255809272700053, + vert_correction: -0.14344353231329066, + vert_offset_correction: 0.21695873, + } + - { + dist_correction: 1.3808284000000002, + dist_correction_x: 1.421472, + dist_correction_y: 1.3838283000000002, + focal_distance: 15.0, + focal_slope: 0.94999999, + horiz_offset_correction: 0.025999999, + laser_id: 8, + min_intensity: 30, + rot_correction: 0.07354442571180776, + vert_correction: -0.10278016723125998, + vert_offset_correction: 0.21398966000000003, + } + - { + dist_correction: 1.3644336000000001, + dist_correction_x: 1.3931616, + dist_correction_y: 1.3852122, + focal_distance: 12.5, + focal_slope: 1.95, + horiz_offset_correction: -0.025999999, + laser_id: 9, + min_intensity: 10, + rot_correction: 0.11317857886058363, + vert_correction: -0.09569590023202451, + vert_offset_correction: 0.21347521, + } + - { + dist_correction: 1.4102663000000002, + dist_correction_x: 1.4163402, + dist_correction_y: 1.3592377, + focal_distance: 12.5, + focal_slope: 1.95, + horiz_offset_correction: 0.025999999, + laser_id: 10, + min_intensity: 10, + rot_correction: 0.05954228616823424, + vert_correction: -0.1386345201601863, + vert_offset_correction: 0.21660597, + } + - { + dist_correction: 1.5019737000000002, + dist_correction_x: 1.532475, + dist_correction_y: 1.5237663000000001, + focal_distance: 13.0, + focal_slope: 1.9, + horiz_offset_correction: -0.025999999, + laser_id: 11, + min_intensity: 10, + rot_correction: 0.09906092120980835, + vert_correction: -0.13181073657049397, + vert_offset_correction: 0.21610622, + } + - { + dist_correction: 1.4399905000000002, + dist_correction_x: 1.4887962, + dist_correction_y: 1.4455237, + focal_distance: 14.5, + focal_slope: 1.7, + horiz_offset_correction: 0.025999999, + laser_id: 12, + max_intensity: 235, + rot_correction: -0.07574798243226695, + vert_correction: -0.054438932963427306, + vert_offset_correction: 0.21049141, + } + - { + dist_correction: 1.5207593, + dist_correction_x: 1.5401453, + dist_correction_y: 1.5190082, + focal_distance: 20.5, + focal_slope: 1.25, + horiz_offset_correction: -0.025999999, + laser_id: 13, + max_intensity: 240, + rot_correction: -0.037047761947550245, + vert_correction: -0.048730533448148504, + vert_offset_correction: 0.21007986, + } + - { + dist_correction: 1.4746239, + dist_correction_x: 1.5300989999999999, + dist_correction_y: 1.4663734, + focal_distance: 12.5, + focal_slope: 1.9, + horiz_offset_correction: 0.025999999, + laser_id: 14, + max_intensity: 245, + rot_correction: -0.0895955468906376, + vert_correction: -0.08961595328025192, + vert_offset_correction: 0.21303425, + } + - { + dist_correction: 1.4697629, + dist_correction_x: 1.5051735, + dist_correction_y: 1.4558601, + focal_distance: 19.5, + focal_slope: 0.94999999, + horiz_offset_correction: -0.025999999, + laser_id: 15, + max_intensity: 245, + rot_correction: -0.05072966149865084, + vert_correction: -0.0839353306800186, + vert_offset_correction: 0.21262267999999998, + } + - { + dist_correction: 1.4143376, + dist_correction_x: 1.4432597000000003, + dist_correction_y: 1.4038483, + focal_distance: 24.0, + focal_slope: 0.69999999, + horiz_offset_correction: 0.025999999, + laser_id: 16, + max_intensity: 245, + rot_correction: -0.001864320564407547, + vert_correction: -0.043427018903405855, + vert_offset_correction: 0.20969770000000001, + } + - { + dist_correction: 1.4815961, + dist_correction_x: 1.5173615, + dist_correction_y: 1.4871606, + focal_distance: 14.5, + focal_slope: 1.65, + horiz_offset_correction: -0.025999999, + laser_id: 17, + rot_correction: 0.03747852840556422, + vert_correction: -0.03648801216715539, + vert_offset_correction: 0.20919794, + } + - { + dist_correction: 1.420331, + dist_correction_x: 1.4755219, + dist_correction_y: 1.3919118000000001, + focal_distance: 17.5, + focal_slope: 1.4, + horiz_offset_correction: 0.025999999, + laser_id: 18, + rot_correction: -0.015194972429011364, + vert_correction: -0.07906187922560139, + vert_offset_correction: 0.21226994000000002, + } + - { + dist_correction: 1.4900717, + dist_correction_x: 1.5143349000000002, + dist_correction_y: 1.4829907, + focal_distance: 24.0, + focal_slope: 1.25, + horiz_offset_correction: -0.025999999, + laser_id: 19, + rot_correction: 0.02391977928648433, + vert_correction: -0.07255814015150577, + vert_offset_correction: 0.21179958, + } + - { + dist_correction: 1.4823865, + dist_correction_x: 1.5357741999999999, + dist_correction_y: 1.4956403, + focal_distance: 24.0, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 20, + rot_correction: 0.07264374331532833, + vert_correction: -0.031587736747464255, + vert_offset_correction: 0.20884519999999998, + } + - { + dist_correction: 1.5553201, + dist_correction_x: 1.5698593, + dist_correction_y: 1.5624425, + focal_distance: 15.5, + focal_slope: 1.55, + horiz_offset_correction: -0.025999999, + laser_id: 21, + rot_correction: 0.11143265968730214, + vert_correction: -0.025460288914769372, + vert_offset_correction: 0.20840424, + } + - { + dist_correction: 1.4437845999999999, + dist_correction_x: 1.4909378000000002, + dist_correction_y: 1.4347861, + focal_distance: 20.5, + focal_slope: 1.2, + horiz_offset_correction: 0.025999999, + laser_id: 22, + rot_correction: 0.05942554283989759, + vert_correction: -0.06665878416276627, + vert_offset_correction: 0.21137333000000003, + } + - { + dist_correction: 1.4939513, + dist_correction_x: 1.5194868, + dist_correction_y: 1.5106346, + focal_distance: 14.5, + focal_slope: 1.65, + horiz_offset_correction: -0.025999999, + laser_id: 23, + rot_correction: 0.09797042203986979, + vert_correction: -0.06055112836378901, + vert_offset_correction: 0.21093236999999998, + } + - { + dist_correction: 1.4521244999999998, + dist_correction_x: 1.4884882, + dist_correction_y: 1.4649333, + focal_distance: 11.5, + focal_slope: 2.0, + horiz_offset_correction: 0.025999999, + laser_id: 24, + rot_correction: -0.07658879305408597, + vert_correction: 0.015620435355027301, + vert_offset_correction: 0.20544985000000002, + } + - { + dist_correction: 1.5351622, + dist_correction_x: 1.524973, + dist_correction_y: 1.5029565, + focal_distance: 18.5, + focal_slope: 1.25, + horiz_offset_correction: -0.025999999, + laser_id: 25, + rot_correction: -0.0379098725675606, + vert_correction: 0.022567997346205196, + vert_offset_correction: 0.20495010000000002, + } + - { + dist_correction: 1.5321327, + dist_correction_x: 1.5833431999999998, + dist_correction_y: 1.5359726, + focal_distance: 13.0, + focal_slope: 1.9, + horiz_offset_correction: 0.025999999, + laser_id: 26, + rot_correction: -0.0904730670226138, + vert_correction: -0.019943931467746017, + vert_offset_correction: 0.20800737000000002, + } + - { + dist_correction: 1.5166023000000002, + dist_correction_x: 1.4874829, + dist_correction_y: 1.4625635, + focal_distance: 21.5, + focal_slope: 1.1, + horiz_offset_correction: -0.025999999, + laser_id: 27, + rot_correction: -0.051308328902808065, + vert_correction: -0.013200099491225388, + vert_offset_correction: 0.20752234000000003, + } + - { + dist_correction: 1.4549194, + dist_correction_x: 1.4688664, + dist_correction_y: 1.4194371000000001, + focal_distance: 13.5, + focal_slope: 1.83, + horiz_offset_correction: 0.025999999, + laser_id: 28, + rot_correction: -0.0019143155208309244, + vert_correction: 0.027266617424120905, + vert_offset_correction: 0.20461203000000003, + } + - { + dist_correction: 1.5617532, + dist_correction_x: 1.5887217999999999, + dist_correction_y: 1.5643922000000001, + focal_distance: 18.5, + focal_slope: 1.35, + horiz_offset_correction: -0.025999999, + laser_id: 29, + rot_correction: 0.03681404490741569, + vert_correction: 0.03421014630846329, + vert_offset_correction: 0.20411228, + } + - { + dist_correction: 1.5132924, + dist_correction_x: 1.5661812000000002, + dist_correction_y: 1.5102689, + focal_distance: 18.5, + focal_slope: 1.35, + horiz_offset_correction: 0.025999999, + laser_id: 30, + rot_correction: -0.015542064486559148, + vert_correction: -0.007885903531460533, + vert_offset_correction: 0.20714018, + } + - { + dist_correction: 1.5638524, + dist_correction_x: 1.5621136000000002, + dist_correction_y: 1.5383017, + focal_distance: 21.5, + focal_slope: 1.15, + horiz_offset_correction: -0.025999999, + laser_id: 31, + rot_correction: 0.023284423588222334, + vert_correction: -0.0015491891506552067, + vert_offset_correction: 0.20668451000000002, + } + - { + dist_correction: 1.3077792, + dist_correction_x: 1.3433452, + dist_correction_y: 1.2840973, + focal_distance: 10.5, + focal_slope: 2.0, + horiz_offset_correction: 0.025999999, + laser_id: 32, + rot_correction: -0.1278634161583795, + vert_correction: -0.39021216204755743, + vert_offset_correction: 0.15970787, + } + - { + dist_correction: 1.4303885, + dist_correction_x: 1.4429931999999999, + dist_correction_y: 1.4607234, + focal_distance: 0.25, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 33, + rot_correction: -0.066528586091226, + vert_correction: -0.38355018793281753, + vert_offset_correction: 0.15922519, + } + - { + dist_correction: 1.3746819, + dist_correction_x: 1.3873923, + dist_correction_y: 1.4089924999999999, + focal_distance: 0.25, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 34, + rot_correction: 0.08854290740283328, + vert_correction: -0.197138848550284, + vert_offset_correction: 0.14656122, + } + - { + dist_correction: 1.3814778, + dist_correction_x: 1.3932765, + dist_correction_y: 1.4301869, + focal_distance: 11.0, + focal_slope: 2.0, + horiz_offset_correction: -0.025999999, + laser_id: 35, + rot_correction: 0.14547956884148489, + vert_correction: -0.18768579625563228, + vert_offset_correction: 0.14595152, + } + - { + dist_correction: 1.4313307, + dist_correction_x: 1.4734517, + dist_correction_y: 1.4390849000000001, + focal_distance: 9.5, + focal_slope: 1.85, + horiz_offset_correction: 0.025999999, + laser_id: 36, + rot_correction: -0.005071588212420635, + vert_correction: -0.3750836655445631, + vert_offset_correction: 0.15861549, + } + - { + dist_correction: 1.3414835, + dist_correction_x: 1.3820609, + dist_correction_y: 1.355589, + focal_distance: 9.5, + focal_slope: 1.4, + horiz_offset_correction: -0.025999999, + laser_id: 37, + rot_correction: 0.05427589303135225, + vert_correction: -0.36762882325722723, + vert_offset_correction: 0.15808201, + } + - { + dist_correction: 1.4895827, + dist_correction_x: 1.5283238000000001, + dist_correction_y: 1.4803529, + focal_distance: 9.0, + focal_slope: 1.65, + horiz_offset_correction: 0.025999999, + laser_id: 38, + rot_correction: -0.028143856558087547, + vert_correction: -0.4285668719175616, + vert_offset_correction: 0.16254044, + } + - { + dist_correction: 1.3727733000000002, + dist_correction_x: 1.3623596, + dist_correction_y: 1.392661, + focal_distance: 0.25, + focal_slope: 1.15, + horiz_offset_correction: -0.025999999, + laser_id: 39, + rot_correction: 0.03172272051181349, + vert_correction: -0.4214410765541042, + vert_offset_correction: 0.16200695, + } + - { + dist_correction: 1.4348983999999998, + dist_correction_x: 1.4775407000000003, + dist_correction_y: 1.4712174999999998, + focal_distance: 0.25, + focal_slope: 0.92000002, + horiz_offset_correction: 0.025999999, + laser_id: 40, + rot_correction: 0.11411698480351568, + vert_correction: -0.3565455112681652, + vert_offset_correction: 0.15729448, + } + - { + dist_correction: 1.335618, + dist_correction_x: 1.3519691, + dist_correction_y: 1.3315152000000001, + focal_distance: 11.200000000000001, + focal_slope: 2.0, + horiz_offset_correction: -0.025999999, + laser_id: 41, + rot_correction: 0.1735498527902839, + vert_correction: -0.34717860842539194, + vert_offset_correction: 0.15663397, + } + - { + dist_correction: 1.4905824, + dist_correction_x: 1.488313, + dist_correction_y: 1.4948479000000001, + focal_distance: 0.25, + focal_slope: 1.1, + horiz_offset_correction: 0.025999999, + laser_id: 42, + rot_correction: 0.09564756333839054, + vert_correction: -0.4110102035460227, + vert_offset_correction: 0.16123213, + } + - { + dist_correction: 1.3288423, + dist_correction_x: 1.3409723, + dist_correction_y: 1.3440451, + focal_distance: 10.0, + focal_slope: 1.95, + horiz_offset_correction: -0.025999999, + laser_id: 43, + rot_correction: 0.15538288292189534, + vert_correction: -0.40083030888437793, + vert_offset_correction: 0.16048269, + } + - { + dist_correction: 1.3771290999999999, + dist_correction_x: 1.3773239000000002, + dist_correction_y: 1.3497290000000002, + focal_distance: 11.5, + focal_slope: 2.0, + horiz_offset_correction: 0.025999999, + laser_id: 44, + rot_correction: -0.12413605610123538, + vert_correction: -0.2840315837972709, + vert_offset_correction: 0.15228986, + } + - { + dist_correction: 1.3367807, + dist_correction_x: 1.370152, + dist_correction_y: 1.370934, + focal_distance: 0.25, + focal_slope: 0.44999999, + horiz_offset_correction: -0.025999999, + laser_id: 45, + rot_correction: -0.06413447432303407, + vert_correction: -0.27761533458791926, + vert_offset_correction: 0.15185799, + } + - { + dist_correction: 1.4788651, + dist_correction_x: 1.5014308, + dist_correction_y: 1.4727454, + focal_distance: 11.5, + focal_slope: 2.0, + horiz_offset_correction: 0.025999999, + laser_id: 46, + rot_correction: -0.14872602785785152, + vert_correction: -0.3359268721635124, + vert_offset_correction: 0.15584644, + } + - { + dist_correction: 1.3220766000000002, + dist_correction_x: 1.3654865, + dist_correction_y: 1.3739757000000001, + focal_distance: 0.25, + focal_slope: 0.94999999, + horiz_offset_correction: -0.025999999, + laser_id: 47, + rot_correction: -0.08707280959256145, + vert_correction: -0.33026751989087316, + vert_offset_correction: 0.15545268, + } + - { + dist_correction: 1.4612433999999999, + dist_correction_x: 1.5250436, + dist_correction_y: 1.4817635999999998, + focal_distance: 13.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 48, + rot_correction: -0.006799911150716457, + vert_correction: -0.26851710773019805, + vert_offset_correction: 0.15124829, + } + - { + dist_correction: 1.3407353000000002, + dist_correction_x: 1.3478844, + dist_correction_y: 1.3154279, + focal_distance: 13.5, + focal_slope: 1.8, + horiz_offset_correction: -0.025999999, + laser_id: 49, + rot_correction: 0.05242808851765633, + vert_correction: -0.26051854302098837, + vert_offset_correction: 0.1507148, + } + - { + dist_correction: 1.3465115, + dist_correction_x: 1.3874431999999999, + dist_correction_y: 1.3508052000000002, + focal_distance: 12.0, + focal_slope: 1.85, + horiz_offset_correction: 0.025999999, + laser_id: 50, + rot_correction: -0.028383715411859876, + vert_correction: -0.3216451745070007, + vert_offset_correction: 0.15485568000000002, + } + - { + dist_correction: 1.3629696999999998, + dist_correction_x: 1.4037315000000001, + dist_correction_y: 1.3869237, + focal_distance: 12.0, + focal_slope: 1.1, + horiz_offset_correction: -0.025999999, + laser_id: 51, + rot_correction: 0.031843273893907245, + vert_correction: -0.3135280670349956, + vert_offset_correction: 0.15429679000000002, + } + - { + dist_correction: 1.4472754, + dist_correction_x: 1.4817390000000001, + dist_correction_y: 1.4782272, + focal_distance: 2.0, + focal_slope: 1.0, + horiz_offset_correction: 0.025999999, + laser_id: 52, + rot_correction: 0.10955275158734502, + vert_correction: -0.24941678290173272, + vert_offset_correction: 0.14997807999999999, + } + - { + dist_correction: 1.3800671, + dist_correction_x: 1.3796414, + dist_correction_y: 1.3943782, + focal_distance: 11.200000000000001, + focal_slope: 2.0, + horiz_offset_correction: -0.025999999, + laser_id: 53, + rot_correction: 0.16876716543828738, + vert_correction: -0.2409525119882134, + vert_offset_correction: 0.14941919, + } + - { + dist_correction: 1.5190169, + dist_correction_x: 1.5619051, + dist_correction_y: 1.5511705, + focal_distance: 2.5, + focal_slope: 1.05, + horiz_offset_correction: 0.025999999, + laser_id: 54, + rot_correction: 0.09037283276367176, + vert_correction: -0.30313513748485243, + vert_offset_correction: 0.15358547, + } + - { + dist_correction: 1.3803656000000002, + dist_correction_x: 1.3960698, + dist_correction_y: 1.386106, + focal_distance: 12.5, + focal_slope: 1.9, + horiz_offset_correction: -0.025999999, + laser_id: 55, + rot_correction: 0.14871534295217081, + vert_correction: -0.29323634555253386, + vert_offset_correction: 0.15291226, + } + - { + dist_correction: 1.5827696, + dist_correction_x: 1.6050609, + dist_correction_y: 1.5844797, + focal_distance: 10.0, + focal_slope: 1.95, + horiz_offset_correction: 0.025999999, + laser_id: 56, + rot_correction: -0.12100867217308608, + vert_correction: -0.17760463486977288, + vert_offset_correction: 0.14530372, + } + - { + dist_correction: 1.3843919, + dist_correction_x: 1.3915251000000002, + dist_correction_y: 1.4156927, + focal_distance: 0.25, + focal_slope: 0.94999999, + horiz_offset_correction: -0.025999999, + laser_id: 57, + rot_correction: -0.06431965899265843, + vert_correction: -0.17006926832673774, + vert_offset_correction: 0.14482104, + } + - { + dist_correction: 1.5491273, + dist_correction_x: 1.5298964000000002, + dist_correction_y: 1.5107637, + focal_distance: 11.5, + focal_slope: 2.0, + horiz_offset_correction: 0.025999999, + laser_id: 58, + rot_correction: -0.14486168214370612, + vert_correction: -0.22974121500510264, + vert_offset_correction: 0.14868247, + } + - { + dist_correction: 1.3646004, + dist_correction_x: 1.3803583000000001, + dist_correction_y: 1.4061511, + focal_distance: 0.25, + focal_slope: 1.0, + horiz_offset_correction: -0.025999999, + laser_id: 59, + rot_correction: -0.0852480451703211, + vert_correction: -0.22391891879349718, + vert_offset_correction: 0.14830141, + } + - { + dist_correction: 1.5239935, + dist_correction_x: 1.560786, + dist_correction_y: 1.5632524, + focal_distance: 5.0, + focal_slope: 1.15, + horiz_offset_correction: 0.025999999, + laser_id: 60, + rot_correction: -0.005967226432828876, + vert_correction: -0.16231529056824404, + vert_offset_correction: 0.14432566, + } + - { + dist_correction: 1.4112029000000001, + dist_correction_x: 1.4223886, + dist_correction_y: 1.4542918, + focal_distance: 2.5, + focal_slope: 1.05, + horiz_offset_correction: -0.025999999, + laser_id: 61, + rot_correction: 0.050600613599087636, + vert_correction: -0.15314424682880032, + vert_offset_correction: 0.14374136, + } + - { + dist_correction: 1.5013637, + dist_correction_x: 1.5208610999999999, + dist_correction_y: 1.5006433000000001, + focal_distance: 16.5, + focal_slope: 1.25, + horiz_offset_correction: 0.025999999, + laser_id: 62, + rot_correction: -0.027436902217920986, + vert_correction: -0.21457119711920336, + vert_offset_correction: 0.14769171, + } + - { + dist_correction: 1.4423058, + dist_correction_x: 1.4454633000000001, + dist_correction_y: 1.4321198000000002, + focal_distance: 9.0, + focal_slope: 1.45, + horiz_offset_correction: -0.025999999, + laser_id: 63, + rot_correction: 0.0290479702718764, + vert_correction: -0.2079266762969834, + vert_offset_correction: 0.14725984, } num_lasers: 64 distance_resolution: 0.002 diff --git a/nebula_decoders/calibration/velodyne/HDL64e_utexas.yaml b/nebula_decoders/calibration/velodyne/HDL64e_utexas.yaml index 3b474f225..6a6156031 100644 --- a/nebula_decoders/calibration/velodyne/HDL64e_utexas.yaml +++ b/nebula_decoders/calibration/velodyne/HDL64e_utexas.yaml @@ -1,900 +1,900 @@ # University of Texas HDL-64E calibration parameters lasers: - - { - dist_correction: 0.100000001490116, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 0, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0698131695389748, - two_pt_correction_available: false, - vert_correction: -0.124932751059532, - vert_offset_correction: 0, - } - - { - dist_correction: 0.280000001192093, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 1, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0392699092626572, - two_pt_correction_available: false, - vert_correction: -0.118993431329727, - vert_offset_correction: 0, - } - - { - dist_correction: 0.319999992847443, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 2, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0698131695389748, - two_pt_correction_available: false, - vert_correction: 0.0055470340885222, - vert_offset_correction: 0, - } - - { - dist_correction: 0.230000004172325, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 3, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.104719758033752, - two_pt_correction_available: false, - vert_correction: 0.0114863449707627, - vert_offset_correction: 0, - } - - { - dist_correction: 0.0700000002980232, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 4, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.013962633907795, - two_pt_correction_available: false, - vert_correction: -0.113056324422359, - vert_offset_correction: 0, - } - - { - dist_correction: 0.0900000035762787, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 5, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0392699092626572, - two_pt_correction_available: false, - vert_correction: -0.107121199369431, - vert_offset_correction: 0, - } - - { - dist_correction: 0.119999997317791, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 6, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0, - two_pt_correction_available: false, - vert_correction: -0.148716226220131, - vert_offset_correction: 0, - } - - { - dist_correction: 0.200000002980232, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 7, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0226892791688442, - two_pt_correction_available: false, - vert_correction: -0.142765983939171, - vert_offset_correction: 0, - } - - { - dist_correction: 0.129999995231628, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 8, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0820304751396179, - two_pt_correction_available: false, - vert_correction: -0.101187855005264, - vert_offset_correction: 0, - } - - { - dist_correction: 0.159999996423721, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 9, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.113446399569511, - two_pt_correction_available: false, - vert_correction: -0.0952560678124428, - vert_offset_correction: 0, - } - - { - dist_correction: 0.159999996423721, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 10, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0698131695389748, - two_pt_correction_available: false, - vert_correction: -0.136818811297417, - vert_offset_correction: 0, - } - - { - dist_correction: 0.159999996423721, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 11, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.104719758033752, - two_pt_correction_available: false, - vert_correction: -0.130874469876289, - vert_offset_correction: 0, - } - - { - dist_correction: 0.129999995231628, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 12, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.068067841231823, - two_pt_correction_available: false, - vert_correction: -0.05375986546278, - vert_offset_correction: 0, - } - - { - dist_correction: 0.200000002980232, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 13, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0349065847694874, - two_pt_correction_available: false, - vert_correction: -0.0478330813348293, - vert_offset_correction: 0, - } - - { - dist_correction: 0.170000001788139, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 14, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0837758108973503, - two_pt_correction_available: false, - vert_correction: -0.0893256440758705, - vert_offset_correction: 0, - } - - { - dist_correction: 0.239999994635582, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 15, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0479965545237064, - two_pt_correction_available: false, - vert_correction: -0.0833963677287102, - vert_offset_correction: 0, - } - - { - dist_correction: 0.180000007152557, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 16, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.00872664619237185, - two_pt_correction_available: false, - vert_correction: -0.0419059917330742, - vert_offset_correction: 0, - } - - { - dist_correction: 0.0599999986588955, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 17, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0392699092626572, - two_pt_correction_available: false, - vert_correction: -0.035978376865387, - vert_offset_correction: 0, - } - - { - dist_correction: 0.140000000596046, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 18, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0, - two_pt_correction_available: false, - vert_correction: -0.0774680152535439, - vert_offset_correction: 0, - } - - { - dist_correction: 0.150000005960464, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 19, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0305432621389627, - two_pt_correction_available: false, - vert_correction: -0.0715404152870178, - vert_offset_correction: 0, - } - - { - dist_correction: 0.219999998807907, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 20, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0855211317539215, - two_pt_correction_available: false, - vert_correction: -0.0300500374287367, - vert_offset_correction: 0, - } - - { - dist_correction: 0.140000000596046, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 21, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.109083078801632, - two_pt_correction_available: false, - vert_correction: -0.024120757356286, - vert_offset_correction: 0, - } - - { - dist_correction: 0.0799999982118607, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 22, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0698131695389748, - two_pt_correction_available: false, - vert_correction: -0.0656133219599724, - vert_offset_correction: 0, - } - - { - dist_correction: 0.159999996423721, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 23, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.104719758033752, - two_pt_correction_available: false, - vert_correction: -0.0596865378320217, - vert_offset_correction: 0, - } - - { - dist_correction: 0.119999997317791, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 24, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0610865242779255, - two_pt_correction_available: false, - vert_correction: 0.0174280721694231, - vert_offset_correction: 0, - } - - { - dist_correction: 0.219999998807907, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 25, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0349065847694874, - two_pt_correction_available: false, - vert_correction: 0.0233724191784859, - vert_offset_correction: 0, - } - - { - dist_correction: 0.159999996423721, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 26, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0785398185253143, - two_pt_correction_available: false, - vert_correction: -0.0181903336197138, - vert_offset_correction: 0, - } - - { - dist_correction: 0.259999990463257, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 27, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0471238903701305, - two_pt_correction_available: false, - vert_correction: -0.0122585473582149, - vert_offset_correction: 0, - } - - { - dist_correction: 0.140000000596046, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 28, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0104719763621688, - two_pt_correction_available: false, - vert_correction: 0.0293195936828852, - vert_offset_correction: 0, - } - - { - dist_correction: 0.219999998807907, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 29, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0349065847694874, - two_pt_correction_available: false, - vert_correction: 0.0352698266506195, - vert_offset_correction: 0, - } - - { - dist_correction: 0.209999993443489, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 30, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.00436332309618592, - two_pt_correction_available: false, - vert_correction: -0.00632520206272602, - vert_offset_correction: 0, - } - - { - dist_correction: 0.140000000596046, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 31, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0296705979853868, - two_pt_correction_available: false, - vert_correction: -0.000390077300835401, - vert_offset_correction: 0, - } - - { - dist_correction: 0.119999997317791, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 32, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.122173048555851, - two_pt_correction_available: false, - vert_correction: -0.396850973367691, - vert_offset_correction: 0, - } - - { - dist_correction: 0.0199999995529652, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 33, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0610865242779255, - two_pt_correction_available: false, - vert_correction: -0.387918144464493, - vert_offset_correction: 0, - } - - { - dist_correction: 0.100000001490116, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 34, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0959931090474129, - two_pt_correction_available: false, - vert_correction: -0.200955957174301, - vert_offset_correction: 0, - } - - { - dist_correction: 0.230000004172325, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 35, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.148352980613708, - two_pt_correction_available: false, - vert_correction: -0.192023113369942, - vert_offset_correction: 0, - } - - { - dist_correction: 0.170000001788139, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 36, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.00872664619237185, - two_pt_correction_available: false, - vert_correction: -0.378992766141891, - vert_offset_correction: 0, - } - - { - dist_correction: 0.150000005960464, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 37, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0610865242779255, - two_pt_correction_available: false, - vert_correction: -0.370074152946472, - vert_offset_correction: 0, - } - - { - dist_correction: 0.0500000007450581, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 38, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0174532923847437, - two_pt_correction_available: false, - vert_correction: -0.43128889799118, - vert_offset_correction: 0, - } - - { - dist_correction: 0.270000010728836, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 39, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0349065847694874, - two_pt_correction_available: false, - vert_correction: -0.423701733350754, - vert_offset_correction: 0, - } - - { - dist_correction: 0.180000007152557, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 40, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.122173048555851, - two_pt_correction_available: false, - vert_correction: -0.361161530017853, - vert_offset_correction: 0, - } - - { - dist_correction: 0.189999997615814, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 41, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.174532920122147, - two_pt_correction_available: false, - vert_correction: -0.352254241704941, - vert_offset_correction: 0, - } - - { - dist_correction: 0.100000001490116, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 42, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.104719758033752, - two_pt_correction_available: false, - vert_correction: -0.414742022752762, - vert_offset_correction: 0, - } - - { - dist_correction: 0.200000002980232, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 43, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.165806278586388, - two_pt_correction_available: false, - vert_correction: -0.405792057514191, - vert_offset_correction: 0, - } - - { - dist_correction: 0.219999998807907, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 44, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.113446399569511, - two_pt_correction_available: false, - vert_correction: -0.28999200463295, - vert_offset_correction: 0, - } - - { - dist_correction: 0.200000002980232, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 45, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0567231997847557, - two_pt_correction_available: false, - vert_correction: -0.281101644039154, - vert_offset_correction: 0, - } - - { - dist_correction: 0.150000005960464, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 46, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.13962633907795, - two_pt_correction_available: false, - vert_correction: -0.343351542949677, - vert_offset_correction: 0, - } - - { - dist_correction: 0.219999998807907, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 47, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0872664600610733, - two_pt_correction_available: false, - vert_correction: -0.334452718496323, - vert_offset_correction: 0, - } - - { - dist_correction: 0.0599999986588955, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 48, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0, - two_pt_correction_available: false, - vert_correction: -0.272210210561752, - vert_offset_correction: 0, - } - - { - dist_correction: 0.129999995231628, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 49, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0558505356311798, - two_pt_correction_available: false, - vert_correction: -0.26331701874733, - vert_offset_correction: 0, - } - - { - dist_correction: 0.00999999977648258, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 50, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0174532923847437, - two_pt_correction_available: false, - vert_correction: -0.323895305395126, - vert_offset_correction: 0, - } - - { - dist_correction: 0.150000005960464, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 51, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0349065847694874, - two_pt_correction_available: false, - vert_correction: -0.316663861274719, - vert_offset_correction: 0, - } - - { - dist_correction: 0.200000002980232, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 52, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.122173048555851, - two_pt_correction_available: false, - vert_correction: -0.254421383142471, - vert_offset_correction: 0, - } - - { - dist_correction: 0.239999994635582, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 53, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.165806278586388, - two_pt_correction_available: false, - vert_correction: -0.245522528886795, - vert_offset_correction: 0, - } - - { - dist_correction: 0.180000007152557, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 54, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.104719758033752, - two_pt_correction_available: false, - vert_correction: -0.307772427797318, - vert_offset_correction: 0, - } - - { - dist_correction: 0.219999998807907, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 55, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.157079637050629, - two_pt_correction_available: false, - vert_correction: -0.298882067203522, - vert_offset_correction: 0, - } - - { - dist_correction: 0.140000000596046, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 56, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.104719758033752, - two_pt_correction_available: false, - vert_correction: -0.183082059025764, - vert_offset_correction: 0, - } - - { - dist_correction: 0.319999992847443, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 57, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0610865242779255, - two_pt_correction_available: false, - vert_correction: -0.17413204908371, - vert_offset_correction: 0, - } - - { - dist_correction: 0.200000002980232, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 58, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.13962633907795, - two_pt_correction_available: false, - vert_correction: -0.236619830131531, - vert_offset_correction: 0, - } - - { - dist_correction: 0.25, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 59, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0785398185253143, - two_pt_correction_available: false, - vert_correction: -0.22771255671978, - vert_offset_correction: 0, - } - - { - dist_correction: 0.170000001788139, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 60, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0, - two_pt_correction_available: false, - vert_correction: -0.16517236828804, - vert_offset_correction: 0, - } - - { - dist_correction: 0.230000004172325, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 61, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0436332300305367, - two_pt_correction_available: false, - vert_correction: -0.156202226877213, - vert_offset_correction: 0, - } - - { - dist_correction: 0.150000005960464, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 62, - max_intensity: 255, - min_intensity: 0, - rot_correction: -0.0174532923847437, - two_pt_correction_available: false, - vert_correction: -0.218799933791161, - vert_offset_correction: 0, - } - - { - dist_correction: 0.230000004172325, - dist_correction_x: 0, - dist_correction_y: 0, - focal_distance: 0, - focal_slope: 0, - laser_id: 63, - max_intensity: 255, - min_intensity: 0, - rot_correction: 0.0314159244298935, - two_pt_correction_available: false, - vert_correction: -0.209881335496902, - vert_offset_correction: 0, + - { + dist_correction: 0.100000001490116, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 0, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0698131695389748, + two_pt_correction_available: false, + vert_correction: -0.124932751059532, + vert_offset_correction: 0, + } + - { + dist_correction: 0.280000001192093, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 1, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0392699092626572, + two_pt_correction_available: false, + vert_correction: -0.118993431329727, + vert_offset_correction: 0, + } + - { + dist_correction: 0.319999992847443, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 2, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0698131695389748, + two_pt_correction_available: false, + vert_correction: 0.0055470340885222, + vert_offset_correction: 0, + } + - { + dist_correction: 0.230000004172325, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 3, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.104719758033752, + two_pt_correction_available: false, + vert_correction: 0.0114863449707627, + vert_offset_correction: 0, + } + - { + dist_correction: 0.0700000002980232, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 4, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.013962633907795, + two_pt_correction_available: false, + vert_correction: -0.113056324422359, + vert_offset_correction: 0, + } + - { + dist_correction: 0.0900000035762787, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 5, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0392699092626572, + two_pt_correction_available: false, + vert_correction: -0.107121199369431, + vert_offset_correction: 0, + } + - { + dist_correction: 0.119999997317791, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 6, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0, + two_pt_correction_available: false, + vert_correction: -0.148716226220131, + vert_offset_correction: 0, + } + - { + dist_correction: 0.200000002980232, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 7, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0226892791688442, + two_pt_correction_available: false, + vert_correction: -0.142765983939171, + vert_offset_correction: 0, + } + - { + dist_correction: 0.129999995231628, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 8, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0820304751396179, + two_pt_correction_available: false, + vert_correction: -0.101187855005264, + vert_offset_correction: 0, + } + - { + dist_correction: 0.159999996423721, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 9, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.113446399569511, + two_pt_correction_available: false, + vert_correction: -0.0952560678124428, + vert_offset_correction: 0, + } + - { + dist_correction: 0.159999996423721, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 10, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0698131695389748, + two_pt_correction_available: false, + vert_correction: -0.136818811297417, + vert_offset_correction: 0, + } + - { + dist_correction: 0.159999996423721, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 11, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.104719758033752, + two_pt_correction_available: false, + vert_correction: -0.130874469876289, + vert_offset_correction: 0, + } + - { + dist_correction: 0.129999995231628, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 12, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.068067841231823, + two_pt_correction_available: false, + vert_correction: -0.05375986546278, + vert_offset_correction: 0, + } + - { + dist_correction: 0.200000002980232, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 13, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0349065847694874, + two_pt_correction_available: false, + vert_correction: -0.0478330813348293, + vert_offset_correction: 0, + } + - { + dist_correction: 0.170000001788139, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 14, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0837758108973503, + two_pt_correction_available: false, + vert_correction: -0.0893256440758705, + vert_offset_correction: 0, + } + - { + dist_correction: 0.239999994635582, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 15, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0479965545237064, + two_pt_correction_available: false, + vert_correction: -0.0833963677287102, + vert_offset_correction: 0, + } + - { + dist_correction: 0.180000007152557, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 16, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.00872664619237185, + two_pt_correction_available: false, + vert_correction: -0.0419059917330742, + vert_offset_correction: 0, + } + - { + dist_correction: 0.0599999986588955, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 17, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0392699092626572, + two_pt_correction_available: false, + vert_correction: -0.035978376865387, + vert_offset_correction: 0, + } + - { + dist_correction: 0.140000000596046, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 18, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0, + two_pt_correction_available: false, + vert_correction: -0.0774680152535439, + vert_offset_correction: 0, + } + - { + dist_correction: 0.150000005960464, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 19, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0305432621389627, + two_pt_correction_available: false, + vert_correction: -0.0715404152870178, + vert_offset_correction: 0, + } + - { + dist_correction: 0.219999998807907, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 20, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0855211317539215, + two_pt_correction_available: false, + vert_correction: -0.0300500374287367, + vert_offset_correction: 0, + } + - { + dist_correction: 0.140000000596046, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 21, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.109083078801632, + two_pt_correction_available: false, + vert_correction: -0.024120757356286, + vert_offset_correction: 0, + } + - { + dist_correction: 0.0799999982118607, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 22, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0698131695389748, + two_pt_correction_available: false, + vert_correction: -0.0656133219599724, + vert_offset_correction: 0, + } + - { + dist_correction: 0.159999996423721, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 23, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.104719758033752, + two_pt_correction_available: false, + vert_correction: -0.0596865378320217, + vert_offset_correction: 0, + } + - { + dist_correction: 0.119999997317791, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 24, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0610865242779255, + two_pt_correction_available: false, + vert_correction: 0.0174280721694231, + vert_offset_correction: 0, + } + - { + dist_correction: 0.219999998807907, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 25, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0349065847694874, + two_pt_correction_available: false, + vert_correction: 0.0233724191784859, + vert_offset_correction: 0, + } + - { + dist_correction: 0.159999996423721, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 26, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0785398185253143, + two_pt_correction_available: false, + vert_correction: -0.0181903336197138, + vert_offset_correction: 0, + } + - { + dist_correction: 0.259999990463257, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 27, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0471238903701305, + two_pt_correction_available: false, + vert_correction: -0.0122585473582149, + vert_offset_correction: 0, + } + - { + dist_correction: 0.140000000596046, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 28, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0104719763621688, + two_pt_correction_available: false, + vert_correction: 0.0293195936828852, + vert_offset_correction: 0, + } + - { + dist_correction: 0.219999998807907, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 29, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0349065847694874, + two_pt_correction_available: false, + vert_correction: 0.0352698266506195, + vert_offset_correction: 0, + } + - { + dist_correction: 0.209999993443489, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 30, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.00436332309618592, + two_pt_correction_available: false, + vert_correction: -0.00632520206272602, + vert_offset_correction: 0, + } + - { + dist_correction: 0.140000000596046, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 31, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0296705979853868, + two_pt_correction_available: false, + vert_correction: -0.000390077300835401, + vert_offset_correction: 0, + } + - { + dist_correction: 0.119999997317791, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 32, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.122173048555851, + two_pt_correction_available: false, + vert_correction: -0.396850973367691, + vert_offset_correction: 0, + } + - { + dist_correction: 0.0199999995529652, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 33, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0610865242779255, + two_pt_correction_available: false, + vert_correction: -0.387918144464493, + vert_offset_correction: 0, + } + - { + dist_correction: 0.100000001490116, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 34, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0959931090474129, + two_pt_correction_available: false, + vert_correction: -0.200955957174301, + vert_offset_correction: 0, + } + - { + dist_correction: 0.230000004172325, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 35, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.148352980613708, + two_pt_correction_available: false, + vert_correction: -0.192023113369942, + vert_offset_correction: 0, + } + - { + dist_correction: 0.170000001788139, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 36, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.00872664619237185, + two_pt_correction_available: false, + vert_correction: -0.378992766141891, + vert_offset_correction: 0, + } + - { + dist_correction: 0.150000005960464, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 37, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0610865242779255, + two_pt_correction_available: false, + vert_correction: -0.370074152946472, + vert_offset_correction: 0, + } + - { + dist_correction: 0.0500000007450581, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 38, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0174532923847437, + two_pt_correction_available: false, + vert_correction: -0.43128889799118, + vert_offset_correction: 0, + } + - { + dist_correction: 0.270000010728836, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 39, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0349065847694874, + two_pt_correction_available: false, + vert_correction: -0.423701733350754, + vert_offset_correction: 0, + } + - { + dist_correction: 0.180000007152557, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 40, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.122173048555851, + two_pt_correction_available: false, + vert_correction: -0.361161530017853, + vert_offset_correction: 0, + } + - { + dist_correction: 0.189999997615814, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 41, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.174532920122147, + two_pt_correction_available: false, + vert_correction: -0.352254241704941, + vert_offset_correction: 0, + } + - { + dist_correction: 0.100000001490116, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 42, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.104719758033752, + two_pt_correction_available: false, + vert_correction: -0.414742022752762, + vert_offset_correction: 0, + } + - { + dist_correction: 0.200000002980232, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 43, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.165806278586388, + two_pt_correction_available: false, + vert_correction: -0.405792057514191, + vert_offset_correction: 0, + } + - { + dist_correction: 0.219999998807907, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 44, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.113446399569511, + two_pt_correction_available: false, + vert_correction: -0.28999200463295, + vert_offset_correction: 0, + } + - { + dist_correction: 0.200000002980232, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 45, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0567231997847557, + two_pt_correction_available: false, + vert_correction: -0.281101644039154, + vert_offset_correction: 0, + } + - { + dist_correction: 0.150000005960464, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 46, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.13962633907795, + two_pt_correction_available: false, + vert_correction: -0.343351542949677, + vert_offset_correction: 0, + } + - { + dist_correction: 0.219999998807907, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 47, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0872664600610733, + two_pt_correction_available: false, + vert_correction: -0.334452718496323, + vert_offset_correction: 0, + } + - { + dist_correction: 0.0599999986588955, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 48, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0, + two_pt_correction_available: false, + vert_correction: -0.272210210561752, + vert_offset_correction: 0, + } + - { + dist_correction: 0.129999995231628, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 49, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0558505356311798, + two_pt_correction_available: false, + vert_correction: -0.26331701874733, + vert_offset_correction: 0, + } + - { + dist_correction: 0.00999999977648258, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 50, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0174532923847437, + two_pt_correction_available: false, + vert_correction: -0.323895305395126, + vert_offset_correction: 0, + } + - { + dist_correction: 0.150000005960464, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 51, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0349065847694874, + two_pt_correction_available: false, + vert_correction: -0.316663861274719, + vert_offset_correction: 0, + } + - { + dist_correction: 0.200000002980232, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 52, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.122173048555851, + two_pt_correction_available: false, + vert_correction: -0.254421383142471, + vert_offset_correction: 0, + } + - { + dist_correction: 0.239999994635582, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 53, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.165806278586388, + two_pt_correction_available: false, + vert_correction: -0.245522528886795, + vert_offset_correction: 0, + } + - { + dist_correction: 0.180000007152557, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 54, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.104719758033752, + two_pt_correction_available: false, + vert_correction: -0.307772427797318, + vert_offset_correction: 0, + } + - { + dist_correction: 0.219999998807907, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 55, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.157079637050629, + two_pt_correction_available: false, + vert_correction: -0.298882067203522, + vert_offset_correction: 0, + } + - { + dist_correction: 0.140000000596046, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 56, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.104719758033752, + two_pt_correction_available: false, + vert_correction: -0.183082059025764, + vert_offset_correction: 0, + } + - { + dist_correction: 0.319999992847443, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 57, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0610865242779255, + two_pt_correction_available: false, + vert_correction: -0.17413204908371, + vert_offset_correction: 0, + } + - { + dist_correction: 0.200000002980232, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 58, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.13962633907795, + two_pt_correction_available: false, + vert_correction: -0.236619830131531, + vert_offset_correction: 0, + } + - { + dist_correction: 0.25, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 59, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0785398185253143, + two_pt_correction_available: false, + vert_correction: -0.22771255671978, + vert_offset_correction: 0, + } + - { + dist_correction: 0.170000001788139, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 60, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0, + two_pt_correction_available: false, + vert_correction: -0.16517236828804, + vert_offset_correction: 0, + } + - { + dist_correction: 0.230000004172325, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 61, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0436332300305367, + two_pt_correction_available: false, + vert_correction: -0.156202226877213, + vert_offset_correction: 0, + } + - { + dist_correction: 0.150000005960464, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 62, + max_intensity: 255, + min_intensity: 0, + rot_correction: -0.0174532923847437, + two_pt_correction_available: false, + vert_correction: -0.218799933791161, + vert_offset_correction: 0, + } + - { + dist_correction: 0.230000004172325, + dist_correction_x: 0, + dist_correction_y: 0, + focal_distance: 0, + focal_slope: 0, + laser_id: 63, + max_intensity: 255, + min_intensity: 0, + rot_correction: 0.0314159244298935, + two_pt_correction_available: false, + vert_correction: -0.209881335496902, + vert_offset_correction: 0, } num_lasers: 64 distance_resolution: 0.002 diff --git a/nebula_decoders/calibration/velodyne/VLP16.yaml b/nebula_decoders/calibration/velodyne/VLP16.yaml index b2e57adca..e545e40a0 100644 --- a/nebula_decoders/calibration/velodyne/VLP16.yaml +++ b/nebula_decoders/calibration/velodyne/VLP16.yaml @@ -1,195 +1,195 @@ lasers: - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 0, - rot_correction: 0.0, - vert_correction: -0.2617993877991494, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 1, - rot_correction: 0.0, - vert_correction: 0.017453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 2, - rot_correction: 0.0, - vert_correction: -0.22689280275926285, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 3, - rot_correction: 0.0, - vert_correction: 0.05235987755982989, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 4, - rot_correction: 0.0, - vert_correction: -0.19198621771937624, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 5, - rot_correction: 0.0, - vert_correction: 0.08726646259971647, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 6, - rot_correction: 0.0, - vert_correction: -0.15707963267948966, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 7, - rot_correction: 0.0, - vert_correction: 0.12217304763960307, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 8, - rot_correction: 0.0, - vert_correction: -0.12217304763960307, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 9, - rot_correction: 0.0, - vert_correction: 0.15707963267948966, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 10, - rot_correction: 0.0, - vert_correction: -0.08726646259971647, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 11, - rot_correction: 0.0, - vert_correction: 0.19198621771937624, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 12, - rot_correction: 0.0, - vert_correction: -0.05235987755982989, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 13, - rot_correction: 0.0, - vert_correction: 0.22689280275926285, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 14, - rot_correction: 0.0, - vert_correction: -0.017453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 15, - rot_correction: 0.0, - vert_correction: 0.2617993877991494, - vert_offset_correction: 0.0, + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 0, + rot_correction: 0.0, + vert_correction: -0.2617993877991494, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 1, + rot_correction: 0.0, + vert_correction: 0.017453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 2, + rot_correction: 0.0, + vert_correction: -0.22689280275926285, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 3, + rot_correction: 0.0, + vert_correction: 0.05235987755982989, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 4, + rot_correction: 0.0, + vert_correction: -0.19198621771937624, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 5, + rot_correction: 0.0, + vert_correction: 0.08726646259971647, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 6, + rot_correction: 0.0, + vert_correction: -0.15707963267948966, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 7, + rot_correction: 0.0, + vert_correction: 0.12217304763960307, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 8, + rot_correction: 0.0, + vert_correction: -0.12217304763960307, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 9, + rot_correction: 0.0, + vert_correction: 0.15707963267948966, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 10, + rot_correction: 0.0, + vert_correction: -0.08726646259971647, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 11, + rot_correction: 0.0, + vert_correction: 0.19198621771937624, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 12, + rot_correction: 0.0, + vert_correction: -0.05235987755982989, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 13, + rot_correction: 0.0, + vert_correction: 0.22689280275926285, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 14, + rot_correction: 0.0, + vert_correction: -0.017453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 15, + rot_correction: 0.0, + vert_correction: 0.2617993877991494, + vert_offset_correction: 0.0, } num_lasers: 16 distance_resolution: 0.002 diff --git a/nebula_decoders/calibration/velodyne/VLP16_hires.yaml b/nebula_decoders/calibration/velodyne/VLP16_hires.yaml index 1a9eb9b0a..9a8c97e63 100644 --- a/nebula_decoders/calibration/velodyne/VLP16_hires.yaml +++ b/nebula_decoders/calibration/velodyne/VLP16_hires.yaml @@ -1,195 +1,195 @@ lasers: - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 0, - rot_correction: 0.0, - vert_correction: -0.17453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 1, - rot_correction: 0.0, - vert_correction: 0.011635528346628864, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 2, - rot_correction: 0.0, - vert_correction: -0.15126186850617523, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 3, - rot_correction: 0.0, - vert_correction: 0.03490658503988659, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 4, - rot_correction: 0.0, - vert_correction: -0.1279908118129175, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 5, - rot_correction: 0.0, - vert_correction: 0.05817764173314432, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 6, - rot_correction: 0.0, - vert_correction: -0.10471975511965977, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 7, - rot_correction: 0.0, - vert_correction: 0.08144869842640205, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 8, - rot_correction: 0.0, - vert_correction: -0.08144869842640205, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 9, - rot_correction: 0.0, - vert_correction: 0.10471975511965977, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 10, - rot_correction: 0.0, - vert_correction: -0.05817764173314432, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 11, - rot_correction: 0.0, - vert_correction: 0.1279908118129175, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 12, - rot_correction: 0.0, - vert_correction: -0.03490658503988659, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 13, - rot_correction: 0.0, - vert_correction: 0.15126186850617523, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 14, - rot_correction: 0.0, - vert_correction: -0.011635528346628864, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 15, - rot_correction: 0.0, - vert_correction: 0.17453292519943295, - vert_offset_correction: 0.0, + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 0, + rot_correction: 0.0, + vert_correction: -0.17453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 1, + rot_correction: 0.0, + vert_correction: 0.011635528346628864, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 2, + rot_correction: 0.0, + vert_correction: -0.15126186850617523, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 3, + rot_correction: 0.0, + vert_correction: 0.03490658503988659, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 4, + rot_correction: 0.0, + vert_correction: -0.1279908118129175, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 5, + rot_correction: 0.0, + vert_correction: 0.05817764173314432, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 6, + rot_correction: 0.0, + vert_correction: -0.10471975511965977, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 7, + rot_correction: 0.0, + vert_correction: 0.08144869842640205, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 8, + rot_correction: 0.0, + vert_correction: -0.08144869842640205, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 9, + rot_correction: 0.0, + vert_correction: 0.10471975511965977, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 10, + rot_correction: 0.0, + vert_correction: -0.05817764173314432, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 11, + rot_correction: 0.0, + vert_correction: 0.1279908118129175, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 12, + rot_correction: 0.0, + vert_correction: -0.03490658503988659, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 13, + rot_correction: 0.0, + vert_correction: 0.15126186850617523, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 14, + rot_correction: 0.0, + vert_correction: -0.011635528346628864, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 15, + rot_correction: 0.0, + vert_correction: 0.17453292519943295, + vert_offset_correction: 0.0, } num_lasers: 16 distance_resolution: 0.002 diff --git a/nebula_decoders/calibration/velodyne/VLP32.yaml b/nebula_decoders/calibration/velodyne/VLP32.yaml index de3ddd829..32e7681dc 100644 --- a/nebula_decoders/calibration/velodyne/VLP32.yaml +++ b/nebula_decoders/calibration/velodyne/VLP32.yaml @@ -1,387 +1,387 @@ lasers: - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 0, - rot_correction: -0.024434609527920613, - vert_correction: -0.4363323129985824, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 1, - rot_correction: 0.07330382858376185, - vert_correction: -0.017453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 2, - rot_correction: -0.024434609527920613, - vert_correction: -0.029094638630745476, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 3, - rot_correction: 0.024434609527920613, - vert_correction: -0.2729520417193932, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 4, - rot_correction: -0.024434609527920613, - vert_correction: -0.19739673840055869, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 5, - rot_correction: 0.024434609527920613, - vert_correction: 0.0, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 6, - rot_correction: -0.07330382858376185, - vert_correction: -0.011641346110802179, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 7, - rot_correction: 0.024434609527920613, - vert_correction: -0.15433946575385857, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 8, - rot_correction: -0.024434609527920613, - vert_correction: -0.12660618393966866, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 9, - rot_correction: 0.07330382858376185, - vert_correction: 0.005811946409141118, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 10, - rot_correction: -0.024434609527920613, - vert_correction: -0.005811946409141118, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 11, - rot_correction: 0.024434609527920613, - vert_correction: -0.10730284241261137, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 12, - rot_correction: -0.07330382858376185, - vert_correction: -0.0930784090088576, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 13, - rot_correction: 0.024434609527920613, - vert_correction: 0.02326523892908441, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 14, - rot_correction: -0.07330382858376185, - vert_correction: 0.011641346110802179, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 15, - rot_correction: 0.024434609527920613, - vert_correction: -0.06981317007977318, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 16, - rot_correction: -0.024434609527920613, - vert_correction: -0.08145451619057535, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 17, - rot_correction: 0.07330382858376185, - vert_correction: 0.029094638630745476, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 18, - rot_correction: -0.024434609527920613, - vert_correction: 0.017453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 19, - rot_correction: 0.07330382858376185, - vert_correction: -0.06400122367063206, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 20, - rot_correction: -0.07330382858376185, - vert_correction: -0.058171823968971005, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 21, - rot_correction: 0.024434609527920613, - vert_correction: 0.058171823968971005, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 22, - rot_correction: -0.024434609527920613, - vert_correction: 0.04071853144902771, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 23, - rot_correction: 0.024434609527920613, - vert_correction: -0.04654793115068877, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 24, - rot_correction: -0.024434609527920613, - vert_correction: -0.05235987755982989, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 25, - rot_correction: 0.024434609527920613, - vert_correction: 0.12217304763960307, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 26, - rot_correction: -0.024434609527920613, - vert_correction: 0.08145451619057535, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 27, - rot_correction: 0.07330382858376185, - vert_correction: -0.04071853144902771, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 28, - rot_correction: -0.07330382858376185, - vert_correction: -0.03490658503988659, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 29, - rot_correction: 0.024434609527920613, - vert_correction: 0.2617993877991494, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 30, - rot_correction: -0.024434609527920613, - vert_correction: 0.18034487160857407, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 31, - rot_correction: 0.024434609527920613, - vert_correction: -0.02326523892908441, - vert_offset_correction: 0.0, + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 0, + rot_correction: -0.024434609527920613, + vert_correction: -0.4363323129985824, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 1, + rot_correction: 0.07330382858376185, + vert_correction: -0.017453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 2, + rot_correction: -0.024434609527920613, + vert_correction: -0.029094638630745476, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 3, + rot_correction: 0.024434609527920613, + vert_correction: -0.2729520417193932, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 4, + rot_correction: -0.024434609527920613, + vert_correction: -0.19739673840055869, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 5, + rot_correction: 0.024434609527920613, + vert_correction: 0.0, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 6, + rot_correction: -0.07330382858376185, + vert_correction: -0.011641346110802179, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 7, + rot_correction: 0.024434609527920613, + vert_correction: -0.15433946575385857, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 8, + rot_correction: -0.024434609527920613, + vert_correction: -0.12660618393966866, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 9, + rot_correction: 0.07330382858376185, + vert_correction: 0.005811946409141118, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 10, + rot_correction: -0.024434609527920613, + vert_correction: -0.005811946409141118, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 11, + rot_correction: 0.024434609527920613, + vert_correction: -0.10730284241261137, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 12, + rot_correction: -0.07330382858376185, + vert_correction: -0.0930784090088576, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 13, + rot_correction: 0.024434609527920613, + vert_correction: 0.02326523892908441, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 14, + rot_correction: -0.07330382858376185, + vert_correction: 0.011641346110802179, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 15, + rot_correction: 0.024434609527920613, + vert_correction: -0.06981317007977318, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 16, + rot_correction: -0.024434609527920613, + vert_correction: -0.08145451619057535, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 17, + rot_correction: 0.07330382858376185, + vert_correction: 0.029094638630745476, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 18, + rot_correction: -0.024434609527920613, + vert_correction: 0.017453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 19, + rot_correction: 0.07330382858376185, + vert_correction: -0.06400122367063206, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 20, + rot_correction: -0.07330382858376185, + vert_correction: -0.058171823968971005, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 21, + rot_correction: 0.024434609527920613, + vert_correction: 0.058171823968971005, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 22, + rot_correction: -0.024434609527920613, + vert_correction: 0.04071853144902771, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 23, + rot_correction: 0.024434609527920613, + vert_correction: -0.04654793115068877, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 24, + rot_correction: -0.024434609527920613, + vert_correction: -0.05235987755982989, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 25, + rot_correction: 0.024434609527920613, + vert_correction: 0.12217304763960307, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 26, + rot_correction: -0.024434609527920613, + vert_correction: 0.08145451619057535, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 27, + rot_correction: 0.07330382858376185, + vert_correction: -0.04071853144902771, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 28, + rot_correction: -0.07330382858376185, + vert_correction: -0.03490658503988659, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 29, + rot_correction: 0.024434609527920613, + vert_correction: 0.2617993877991494, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 30, + rot_correction: -0.024434609527920613, + vert_correction: 0.18034487160857407, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 31, + rot_correction: 0.024434609527920613, + vert_correction: -0.02326523892908441, + vert_offset_correction: 0.0, } num_lasers: 32 distance_resolution: 0.004 diff --git a/nebula_decoders/calibration/velodyne/VLP32MR.yaml b/nebula_decoders/calibration/velodyne/VLP32MR.yaml index de3ddd829..32e7681dc 100644 --- a/nebula_decoders/calibration/velodyne/VLP32MR.yaml +++ b/nebula_decoders/calibration/velodyne/VLP32MR.yaml @@ -1,387 +1,387 @@ lasers: - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 0, - rot_correction: -0.024434609527920613, - vert_correction: -0.4363323129985824, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 1, - rot_correction: 0.07330382858376185, - vert_correction: -0.017453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 2, - rot_correction: -0.024434609527920613, - vert_correction: -0.029094638630745476, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 3, - rot_correction: 0.024434609527920613, - vert_correction: -0.2729520417193932, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 4, - rot_correction: -0.024434609527920613, - vert_correction: -0.19739673840055869, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 5, - rot_correction: 0.024434609527920613, - vert_correction: 0.0, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 6, - rot_correction: -0.07330382858376185, - vert_correction: -0.011641346110802179, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 7, - rot_correction: 0.024434609527920613, - vert_correction: -0.15433946575385857, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 8, - rot_correction: -0.024434609527920613, - vert_correction: -0.12660618393966866, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 9, - rot_correction: 0.07330382858376185, - vert_correction: 0.005811946409141118, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 10, - rot_correction: -0.024434609527920613, - vert_correction: -0.005811946409141118, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 11, - rot_correction: 0.024434609527920613, - vert_correction: -0.10730284241261137, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 12, - rot_correction: -0.07330382858376185, - vert_correction: -0.0930784090088576, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 13, - rot_correction: 0.024434609527920613, - vert_correction: 0.02326523892908441, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 14, - rot_correction: -0.07330382858376185, - vert_correction: 0.011641346110802179, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 15, - rot_correction: 0.024434609527920613, - vert_correction: -0.06981317007977318, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 16, - rot_correction: -0.024434609527920613, - vert_correction: -0.08145451619057535, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 17, - rot_correction: 0.07330382858376185, - vert_correction: 0.029094638630745476, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 18, - rot_correction: -0.024434609527920613, - vert_correction: 0.017453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 19, - rot_correction: 0.07330382858376185, - vert_correction: -0.06400122367063206, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 20, - rot_correction: -0.07330382858376185, - vert_correction: -0.058171823968971005, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 21, - rot_correction: 0.024434609527920613, - vert_correction: 0.058171823968971005, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 22, - rot_correction: -0.024434609527920613, - vert_correction: 0.04071853144902771, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 23, - rot_correction: 0.024434609527920613, - vert_correction: -0.04654793115068877, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 24, - rot_correction: -0.024434609527920613, - vert_correction: -0.05235987755982989, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 25, - rot_correction: 0.024434609527920613, - vert_correction: 0.12217304763960307, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 26, - rot_correction: -0.024434609527920613, - vert_correction: 0.08145451619057535, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 27, - rot_correction: 0.07330382858376185, - vert_correction: -0.04071853144902771, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 28, - rot_correction: -0.07330382858376185, - vert_correction: -0.03490658503988659, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 29, - rot_correction: 0.024434609527920613, - vert_correction: 0.2617993877991494, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 30, - rot_correction: -0.024434609527920613, - vert_correction: 0.18034487160857407, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - horiz_offset_correction: 0.0, - laser_id: 31, - rot_correction: 0.024434609527920613, - vert_correction: -0.02326523892908441, - vert_offset_correction: 0.0, + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 0, + rot_correction: -0.024434609527920613, + vert_correction: -0.4363323129985824, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 1, + rot_correction: 0.07330382858376185, + vert_correction: -0.017453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 2, + rot_correction: -0.024434609527920613, + vert_correction: -0.029094638630745476, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 3, + rot_correction: 0.024434609527920613, + vert_correction: -0.2729520417193932, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 4, + rot_correction: -0.024434609527920613, + vert_correction: -0.19739673840055869, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 5, + rot_correction: 0.024434609527920613, + vert_correction: 0.0, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 6, + rot_correction: -0.07330382858376185, + vert_correction: -0.011641346110802179, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 7, + rot_correction: 0.024434609527920613, + vert_correction: -0.15433946575385857, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 8, + rot_correction: -0.024434609527920613, + vert_correction: -0.12660618393966866, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 9, + rot_correction: 0.07330382858376185, + vert_correction: 0.005811946409141118, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 10, + rot_correction: -0.024434609527920613, + vert_correction: -0.005811946409141118, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 11, + rot_correction: 0.024434609527920613, + vert_correction: -0.10730284241261137, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 12, + rot_correction: -0.07330382858376185, + vert_correction: -0.0930784090088576, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 13, + rot_correction: 0.024434609527920613, + vert_correction: 0.02326523892908441, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 14, + rot_correction: -0.07330382858376185, + vert_correction: 0.011641346110802179, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 15, + rot_correction: 0.024434609527920613, + vert_correction: -0.06981317007977318, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 16, + rot_correction: -0.024434609527920613, + vert_correction: -0.08145451619057535, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 17, + rot_correction: 0.07330382858376185, + vert_correction: 0.029094638630745476, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 18, + rot_correction: -0.024434609527920613, + vert_correction: 0.017453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 19, + rot_correction: 0.07330382858376185, + vert_correction: -0.06400122367063206, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 20, + rot_correction: -0.07330382858376185, + vert_correction: -0.058171823968971005, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 21, + rot_correction: 0.024434609527920613, + vert_correction: 0.058171823968971005, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 22, + rot_correction: -0.024434609527920613, + vert_correction: 0.04071853144902771, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 23, + rot_correction: 0.024434609527920613, + vert_correction: -0.04654793115068877, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 24, + rot_correction: -0.024434609527920613, + vert_correction: -0.05235987755982989, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 25, + rot_correction: 0.024434609527920613, + vert_correction: 0.12217304763960307, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 26, + rot_correction: -0.024434609527920613, + vert_correction: 0.08145451619057535, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 27, + rot_correction: 0.07330382858376185, + vert_correction: -0.04071853144902771, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 28, + rot_correction: -0.07330382858376185, + vert_correction: -0.03490658503988659, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 29, + rot_correction: 0.024434609527920613, + vert_correction: 0.2617993877991494, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 30, + rot_correction: -0.024434609527920613, + vert_correction: 0.18034487160857407, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + horiz_offset_correction: 0.0, + laser_id: 31, + rot_correction: 0.024434609527920613, + vert_correction: -0.02326523892908441, + vert_offset_correction: 0.0, } num_lasers: 32 distance_resolution: 0.004 diff --git a/nebula_decoders/calibration/velodyne/VLS128.yaml b/nebula_decoders/calibration/velodyne/VLS128.yaml index dc7057b83..8c783c4a2 100644 --- a/nebula_decoders/calibration/velodyne/VLS128.yaml +++ b/nebula_decoders/calibration/velodyne/VLS128.yaml @@ -1,1411 +1,1411 @@ lasers: - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 0, - rot_correction: -0.1108982206717197, - vert_correction: -0.2049365607691742, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 1, - rot_correction: -0.07937757438070212, - vert_correction: -0.034732052114687155, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 2, - rot_correction: -0.04768239516448509, - vert_correction: 0.059341194567807204, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 3, - rot_correction: -0.015899949485668342, - vert_correction: -0.09232791743050003, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 4, - rot_correction: 0.015899949485668342, - vert_correction: -0.013613568165555772, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 5, - rot_correction: 0.04768239516448509, - vert_correction: 0.0804596785169386, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 6, - rot_correction: 0.07937757438070212, - vert_correction: -0.07120943348136864, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 7, - rot_correction: 0.1108982206717197, - vert_correction: 0.022863813201125717, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 8, - rot_correction: -0.1108982206717197, - vert_correction: -0.11344640137963143, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 9, - rot_correction: -0.07937757438070212, - vert_correction: -0.01937315469713706, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 10, - rot_correction: -0.04768239516448509, - vert_correction: 0.0747000919853573, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 11, - rot_correction: -0.015899949485668342, - vert_correction: -0.07696902001294993, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 12, - rot_correction: 0.015899949485668342, - vert_correction: 0.0017453292519943296, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 13, - rot_correction: 0.04768239516448509, - vert_correction: 0.11309733552923257, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 14, - rot_correction: 0.07937757438070212, - vert_correction: -0.05585053606381855, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 15, - rot_correction: 0.1108982206717197, - vert_correction: 0.03822271061867582, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 16, - rot_correction: -0.1108982206717197, - vert_correction: -0.06736970912698112, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 17, - rot_correction: -0.07937757438070212, - vert_correction: 0.026703537555513242, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 18, - rot_correction: -0.04768239516448509, - vert_correction: -0.16133823605435582, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 19, - rot_correction: -0.015899949485668342, - vert_correction: -0.030892327760299633, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 20, - rot_correction: 0.015899949485668342, - vert_correction: 0.04782202150464463, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 21, - rot_correction: 0.04768239516448509, - vert_correction: -0.10384709049366261, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 22, - rot_correction: 0.07937757438070212, - vert_correction: -0.009773843811168246, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 23, - rot_correction: 0.1108982206717197, - vert_correction: 0.08429940287132612, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 24, - rot_correction: -0.1108982206717197, - vert_correction: -0.05201081170943102, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 25, - rot_correction: -0.07937757438070212, - vert_correction: 0.04206243497306335, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 26, - rot_correction: -0.04768239516448509, - vert_correction: -0.1096066770252439, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 27, - rot_correction: -0.015899949485668342, - vert_correction: -0.015533430342749533, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 28, - rot_correction: 0.015899949485668342, - vert_correction: 0.06318091892219473, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 29, - rot_correction: 0.04768239516448509, - vert_correction: -0.08848819307611251, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 30, - rot_correction: 0.07937757438070212, - vert_correction: 0.005585053606381855, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 31, - rot_correction: 0.1108982206717197, - vert_correction: 0.1322959573011702, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 32, - rot_correction: -0.1108982206717197, - vert_correction: -0.005934119456780721, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 33, - rot_correction: -0.07937757438070212, - vert_correction: 0.09040805525330627, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 34, - rot_correction: -0.04768239516448509, - vert_correction: -0.0635299847725936, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 35, - rot_correction: -0.015899949485668342, - vert_correction: 0.030543261909900768, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 36, - rot_correction: 0.015899949485668342, - vert_correction: -0.4363323129985824, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 37, - rot_correction: 0.04768239516448509, - vert_correction: -0.04241150082346221, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 38, - rot_correction: 0.07937757438070212, - vert_correction: 0.05166174585903215, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 39, - rot_correction: 0.1108982206717197, - vert_correction: -0.10000736613927509, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 40, - rot_correction: -0.1108982206717197, - vert_correction: 0.00942477796076938, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 41, - rot_correction: -0.07937757438070212, - vert_correction: 0.16929693744344995, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 42, - rot_correction: -0.04768239516448509, - vert_correction: -0.04817108735504349, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 43, - rot_correction: -0.015899949485668342, - vert_correction: 0.04590215932745086, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 44, - rot_correction: 0.015899949485668342, - vert_correction: -0.13351768777756623, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 45, - rot_correction: 0.04768239516448509, - vert_correction: -0.027052603405912107, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 46, - rot_correction: 0.07937757438070212, - vert_correction: 0.06702064327658225, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 47, - rot_correction: 0.1108982206717197, - vert_correction: -0.08464846872172498, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 48, - rot_correction: -0.1108982206717197, - vert_correction: 0.05550147021341968, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 49, - rot_correction: -0.07937757438070212, - vert_correction: -0.09616764178488756, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 50, - rot_correction: -0.04768239516448509, - vert_correction: -0.0020943951023931952, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 51, - rot_correction: -0.015899949485668342, - vert_correction: 0.10000736613927509, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 52, - rot_correction: 0.015899949485668342, - vert_correction: -0.07504915783575616, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 53, - rot_correction: 0.04768239516448509, - vert_correction: 0.019024088846738195, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 54, - rot_correction: 0.07937757438070212, - vert_correction: -0.2799857186049304, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 55, - rot_correction: 0.1108982206717197, - vert_correction: -0.038571776469074684, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 56, - rot_correction: -0.1108982206717197, - vert_correction: 0.07086036763096977, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 57, - rot_correction: -0.07937757438070212, - vert_correction: -0.08080874436733745, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 58, - rot_correction: -0.04768239516448509, - vert_correction: 0.013264502315156905, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 59, - rot_correction: -0.015899949485668342, - vert_correction: 0.2617993877991494, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 60, - rot_correction: 0.015899949485668342, - vert_correction: -0.05969026041820607, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 61, - rot_correction: 0.04768239516448509, - vert_correction: 0.03438298626428829, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 62, - rot_correction: 0.07937757438070212, - vert_correction: -0.11955505376161157, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 63, - rot_correction: 0.1108982206717197, - vert_correction: -0.023212879051524585, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 64, - rot_correction: -0.1108982206717197, - vert_correction: -0.09808750396208132, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 65, - rot_correction: -0.07937757438070212, - vert_correction: -0.004014257279586958, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 66, - rot_correction: -0.04768239516448509, - vert_correction: 0.0947713783832921, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 67, - rot_correction: -0.015899949485668342, - vert_correction: -0.06161012259539983, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 68, - rot_correction: 0.015899949485668342, - vert_correction: 0.01710422666954443, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 69, - rot_correction: 0.04768239516448509, - vert_correction: -0.34177037412552963, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 70, - rot_correction: 0.07937757438070212, - vert_correction: -0.040491638646268445, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 71, - rot_correction: 0.1108982206717197, - vert_correction: 0.053581608036225914, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 72, - rot_correction: -0.1108982206717197, - vert_correction: -0.08272860654453122, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 73, - rot_correction: -0.07937757438070212, - vert_correction: 0.011344640137963142, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 74, - rot_correction: -0.04768239516448509, - vert_correction: 0.20507618710933373, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 75, - rot_correction: -0.015899949485668342, - vert_correction: -0.046251225177849735, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 76, - rot_correction: 0.015899949485668342, - vert_correction: 0.03246312408709453, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 77, - rot_correction: 0.04768239516448509, - vert_correction: -0.12479104151759457, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 78, - rot_correction: 0.07937757438070212, - vert_correction: -0.025132741228718343, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 79, - rot_correction: 0.1108982206717197, - vert_correction: 0.06894050545377602, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 80, - rot_correction: -0.1108982206717197, - vert_correction: -0.03665191429188092, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 81, - rot_correction: -0.07937757438070212, - vert_correction: 0.05742133239061344, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 82, - rot_correction: -0.04768239516448509, - vert_correction: -0.0942477796076938, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 83, - rot_correction: -0.015899949485668342, - vert_correction: -0.00017453292519943296, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 84, - rot_correction: 0.015899949485668342, - vert_correction: 0.07853981633974483, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 85, - rot_correction: 0.04768239516448509, - vert_correction: -0.07312929565856241, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 86, - rot_correction: 0.07937757438070212, - vert_correction: 0.020943951023931952, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 87, - rot_correction: 0.1108982206717197, - vert_correction: -0.23675391303303078, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 88, - rot_correction: -0.1108982206717197, - vert_correction: -0.02129301687433082, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 89, - rot_correction: -0.07937757438070212, - vert_correction: 0.07278022980816354, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 90, - rot_correction: -0.04768239516448509, - vert_correction: -0.07888888219014369, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 91, - rot_correction: -0.015899949485668342, - vert_correction: 0.015184364492350668, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 92, - rot_correction: 0.015899949485668342, - vert_correction: 0.10611601852125524, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 93, - rot_correction: 0.04768239516448509, - vert_correction: -0.05777039824101231, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 94, - rot_correction: 0.07937757438070212, - vert_correction: 0.03630284844148206, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 95, - rot_correction: 0.1108982206717197, - vert_correction: -0.11606439525762292, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 96, - rot_correction: -0.1108982206717197, - vert_correction: 0.024783675378319478, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 97, - rot_correction: -0.07937757438070212, - vert_correction: -0.18057176441133332, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 98, - rot_correction: -0.04768239516448509, - vert_correction: -0.032812189937493394, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 99, - rot_correction: -0.015899949485668342, - vert_correction: 0.061261056745000965, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 100, - rot_correction: 0.015899949485668342, - vert_correction: -0.10576695267085637, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 101, - rot_correction: 0.04768239516448509, - vert_correction: -0.011693705988362009, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 102, - rot_correction: 0.07937757438070212, - vert_correction: 0.08237954069413235, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 103, - rot_correction: 0.1108982206717197, - vert_correction: -0.06928957130417489, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 104, - rot_correction: -0.1108982206717197, - vert_correction: 0.04014257279586958, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 105, - rot_correction: -0.07937757438070212, - vert_correction: -0.11152653920243766, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 106, - rot_correction: -0.04768239516448509, - vert_correction: -0.017453292519943295, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 107, - rot_correction: -0.015899949485668342, - vert_correction: 0.07661995416255106, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 108, - rot_correction: 0.015899949485668342, - vert_correction: -0.09040805525330627, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 109, - rot_correction: 0.04768239516448509, - vert_correction: 0.003665191429188092, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 110, - rot_correction: 0.07937757438070212, - vert_correction: 0.12182398178920421, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 111, - rot_correction: 0.1108982206717197, - vert_correction: -0.05393067388662478, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 112, - rot_correction: -0.1108982206717197, - vert_correction: 0.08691739674931762, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 113, - rot_correction: -0.07937757438070212, - vert_correction: -0.06544984694978735, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 114, - rot_correction: -0.04768239516448509, - vert_correction: 0.028623399732707003, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 115, - rot_correction: -0.015899949485668342, - vert_correction: -0.1457698991265664, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 116, - rot_correction: 0.015899949485668342, - vert_correction: -0.044331363000655974, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 117, - rot_correction: 0.04768239516448509, - vert_correction: 0.04974188368183839, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 118, - rot_correction: 0.07937757438070212, - vert_correction: -0.10192722831646885, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 119, - rot_correction: 0.1108982206717197, - vert_correction: -0.007853981633974483, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 120, - rot_correction: -0.1108982206717197, - vert_correction: 0.14713125594312199, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 121, - rot_correction: -0.07937757438070212, - vert_correction: -0.05009094953223726, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 122, - rot_correction: -0.04768239516448509, - vert_correction: 0.0439822971502571, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 123, - rot_correction: -0.015899949485668342, - vert_correction: -0.10768681484805014, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 124, - rot_correction: 0.015899949485668342, - vert_correction: -0.02897246558310587, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 125, - rot_correction: 0.04768239516448509, - vert_correction: 0.0651007810993885, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 126, - rot_correction: 0.07937757438070212, - vert_correction: -0.08656833089891874, - vert_offset_correction: 0.0, - } - - { - dist_correction: 0.0, - dist_correction_x: 0.0, - dist_correction_y: 0.0, - focal_distance: 0.0, - focal_slope: 0.0, - laser_id: 127, - rot_correction: 0.1108982206717197, - vert_correction: 0.007504915783575617, - vert_offset_correction: 0.0, + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 0, + rot_correction: -0.1108982206717197, + vert_correction: -0.2049365607691742, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 1, + rot_correction: -0.07937757438070212, + vert_correction: -0.034732052114687155, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 2, + rot_correction: -0.04768239516448509, + vert_correction: 0.059341194567807204, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 3, + rot_correction: -0.015899949485668342, + vert_correction: -0.09232791743050003, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 4, + rot_correction: 0.015899949485668342, + vert_correction: -0.013613568165555772, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 5, + rot_correction: 0.04768239516448509, + vert_correction: 0.0804596785169386, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 6, + rot_correction: 0.07937757438070212, + vert_correction: -0.07120943348136864, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 7, + rot_correction: 0.1108982206717197, + vert_correction: 0.022863813201125717, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 8, + rot_correction: -0.1108982206717197, + vert_correction: -0.11344640137963143, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 9, + rot_correction: -0.07937757438070212, + vert_correction: -0.01937315469713706, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 10, + rot_correction: -0.04768239516448509, + vert_correction: 0.0747000919853573, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 11, + rot_correction: -0.015899949485668342, + vert_correction: -0.07696902001294993, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 12, + rot_correction: 0.015899949485668342, + vert_correction: 0.0017453292519943296, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 13, + rot_correction: 0.04768239516448509, + vert_correction: 0.11309733552923257, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 14, + rot_correction: 0.07937757438070212, + vert_correction: -0.05585053606381855, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 15, + rot_correction: 0.1108982206717197, + vert_correction: 0.03822271061867582, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 16, + rot_correction: -0.1108982206717197, + vert_correction: -0.06736970912698112, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 17, + rot_correction: -0.07937757438070212, + vert_correction: 0.026703537555513242, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 18, + rot_correction: -0.04768239516448509, + vert_correction: -0.16133823605435582, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 19, + rot_correction: -0.015899949485668342, + vert_correction: -0.030892327760299633, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 20, + rot_correction: 0.015899949485668342, + vert_correction: 0.04782202150464463, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 21, + rot_correction: 0.04768239516448509, + vert_correction: -0.10384709049366261, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 22, + rot_correction: 0.07937757438070212, + vert_correction: -0.009773843811168246, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 23, + rot_correction: 0.1108982206717197, + vert_correction: 0.08429940287132612, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 24, + rot_correction: -0.1108982206717197, + vert_correction: -0.05201081170943102, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 25, + rot_correction: -0.07937757438070212, + vert_correction: 0.04206243497306335, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 26, + rot_correction: -0.04768239516448509, + vert_correction: -0.1096066770252439, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 27, + rot_correction: -0.015899949485668342, + vert_correction: -0.015533430342749533, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 28, + rot_correction: 0.015899949485668342, + vert_correction: 0.06318091892219473, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 29, + rot_correction: 0.04768239516448509, + vert_correction: -0.08848819307611251, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 30, + rot_correction: 0.07937757438070212, + vert_correction: 0.005585053606381855, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 31, + rot_correction: 0.1108982206717197, + vert_correction: 0.1322959573011702, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 32, + rot_correction: -0.1108982206717197, + vert_correction: -0.005934119456780721, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 33, + rot_correction: -0.07937757438070212, + vert_correction: 0.09040805525330627, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 34, + rot_correction: -0.04768239516448509, + vert_correction: -0.0635299847725936, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 35, + rot_correction: -0.015899949485668342, + vert_correction: 0.030543261909900768, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 36, + rot_correction: 0.015899949485668342, + vert_correction: -0.4363323129985824, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 37, + rot_correction: 0.04768239516448509, + vert_correction: -0.04241150082346221, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 38, + rot_correction: 0.07937757438070212, + vert_correction: 0.05166174585903215, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 39, + rot_correction: 0.1108982206717197, + vert_correction: -0.10000736613927509, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 40, + rot_correction: -0.1108982206717197, + vert_correction: 0.00942477796076938, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 41, + rot_correction: -0.07937757438070212, + vert_correction: 0.16929693744344995, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 42, + rot_correction: -0.04768239516448509, + vert_correction: -0.04817108735504349, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 43, + rot_correction: -0.015899949485668342, + vert_correction: 0.04590215932745086, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 44, + rot_correction: 0.015899949485668342, + vert_correction: -0.13351768777756623, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 45, + rot_correction: 0.04768239516448509, + vert_correction: -0.027052603405912107, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 46, + rot_correction: 0.07937757438070212, + vert_correction: 0.06702064327658225, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 47, + rot_correction: 0.1108982206717197, + vert_correction: -0.08464846872172498, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 48, + rot_correction: -0.1108982206717197, + vert_correction: 0.05550147021341968, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 49, + rot_correction: -0.07937757438070212, + vert_correction: -0.09616764178488756, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 50, + rot_correction: -0.04768239516448509, + vert_correction: -0.0020943951023931952, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 51, + rot_correction: -0.015899949485668342, + vert_correction: 0.10000736613927509, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 52, + rot_correction: 0.015899949485668342, + vert_correction: -0.07504915783575616, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 53, + rot_correction: 0.04768239516448509, + vert_correction: 0.019024088846738195, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 54, + rot_correction: 0.07937757438070212, + vert_correction: -0.2799857186049304, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 55, + rot_correction: 0.1108982206717197, + vert_correction: -0.038571776469074684, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 56, + rot_correction: -0.1108982206717197, + vert_correction: 0.07086036763096977, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 57, + rot_correction: -0.07937757438070212, + vert_correction: -0.08080874436733745, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 58, + rot_correction: -0.04768239516448509, + vert_correction: 0.013264502315156905, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 59, + rot_correction: -0.015899949485668342, + vert_correction: 0.2617993877991494, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 60, + rot_correction: 0.015899949485668342, + vert_correction: -0.05969026041820607, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 61, + rot_correction: 0.04768239516448509, + vert_correction: 0.03438298626428829, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 62, + rot_correction: 0.07937757438070212, + vert_correction: -0.11955505376161157, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 63, + rot_correction: 0.1108982206717197, + vert_correction: -0.023212879051524585, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 64, + rot_correction: -0.1108982206717197, + vert_correction: -0.09808750396208132, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 65, + rot_correction: -0.07937757438070212, + vert_correction: -0.004014257279586958, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 66, + rot_correction: -0.04768239516448509, + vert_correction: 0.0947713783832921, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 67, + rot_correction: -0.015899949485668342, + vert_correction: -0.06161012259539983, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 68, + rot_correction: 0.015899949485668342, + vert_correction: 0.01710422666954443, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 69, + rot_correction: 0.04768239516448509, + vert_correction: -0.34177037412552963, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 70, + rot_correction: 0.07937757438070212, + vert_correction: -0.040491638646268445, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 71, + rot_correction: 0.1108982206717197, + vert_correction: 0.053581608036225914, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 72, + rot_correction: -0.1108982206717197, + vert_correction: -0.08272860654453122, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 73, + rot_correction: -0.07937757438070212, + vert_correction: 0.011344640137963142, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 74, + rot_correction: -0.04768239516448509, + vert_correction: 0.20507618710933373, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 75, + rot_correction: -0.015899949485668342, + vert_correction: -0.046251225177849735, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 76, + rot_correction: 0.015899949485668342, + vert_correction: 0.03246312408709453, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 77, + rot_correction: 0.04768239516448509, + vert_correction: -0.12479104151759457, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 78, + rot_correction: 0.07937757438070212, + vert_correction: -0.025132741228718343, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 79, + rot_correction: 0.1108982206717197, + vert_correction: 0.06894050545377602, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 80, + rot_correction: -0.1108982206717197, + vert_correction: -0.03665191429188092, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 81, + rot_correction: -0.07937757438070212, + vert_correction: 0.05742133239061344, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 82, + rot_correction: -0.04768239516448509, + vert_correction: -0.0942477796076938, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 83, + rot_correction: -0.015899949485668342, + vert_correction: -0.00017453292519943296, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 84, + rot_correction: 0.015899949485668342, + vert_correction: 0.07853981633974483, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 85, + rot_correction: 0.04768239516448509, + vert_correction: -0.07312929565856241, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 86, + rot_correction: 0.07937757438070212, + vert_correction: 0.020943951023931952, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 87, + rot_correction: 0.1108982206717197, + vert_correction: -0.23675391303303078, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 88, + rot_correction: -0.1108982206717197, + vert_correction: -0.02129301687433082, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 89, + rot_correction: -0.07937757438070212, + vert_correction: 0.07278022980816354, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 90, + rot_correction: -0.04768239516448509, + vert_correction: -0.07888888219014369, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 91, + rot_correction: -0.015899949485668342, + vert_correction: 0.015184364492350668, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 92, + rot_correction: 0.015899949485668342, + vert_correction: 0.10611601852125524, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 93, + rot_correction: 0.04768239516448509, + vert_correction: -0.05777039824101231, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 94, + rot_correction: 0.07937757438070212, + vert_correction: 0.03630284844148206, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 95, + rot_correction: 0.1108982206717197, + vert_correction: -0.11606439525762292, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 96, + rot_correction: -0.1108982206717197, + vert_correction: 0.024783675378319478, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 97, + rot_correction: -0.07937757438070212, + vert_correction: -0.18057176441133332, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 98, + rot_correction: -0.04768239516448509, + vert_correction: -0.032812189937493394, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 99, + rot_correction: -0.015899949485668342, + vert_correction: 0.061261056745000965, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 100, + rot_correction: 0.015899949485668342, + vert_correction: -0.10576695267085637, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 101, + rot_correction: 0.04768239516448509, + vert_correction: -0.011693705988362009, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 102, + rot_correction: 0.07937757438070212, + vert_correction: 0.08237954069413235, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 103, + rot_correction: 0.1108982206717197, + vert_correction: -0.06928957130417489, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 104, + rot_correction: -0.1108982206717197, + vert_correction: 0.04014257279586958, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 105, + rot_correction: -0.07937757438070212, + vert_correction: -0.11152653920243766, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 106, + rot_correction: -0.04768239516448509, + vert_correction: -0.017453292519943295, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 107, + rot_correction: -0.015899949485668342, + vert_correction: 0.07661995416255106, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 108, + rot_correction: 0.015899949485668342, + vert_correction: -0.09040805525330627, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 109, + rot_correction: 0.04768239516448509, + vert_correction: 0.003665191429188092, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 110, + rot_correction: 0.07937757438070212, + vert_correction: 0.12182398178920421, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 111, + rot_correction: 0.1108982206717197, + vert_correction: -0.05393067388662478, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 112, + rot_correction: -0.1108982206717197, + vert_correction: 0.08691739674931762, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 113, + rot_correction: -0.07937757438070212, + vert_correction: -0.06544984694978735, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 114, + rot_correction: -0.04768239516448509, + vert_correction: 0.028623399732707003, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 115, + rot_correction: -0.015899949485668342, + vert_correction: -0.1457698991265664, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 116, + rot_correction: 0.015899949485668342, + vert_correction: -0.044331363000655974, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 117, + rot_correction: 0.04768239516448509, + vert_correction: 0.04974188368183839, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 118, + rot_correction: 0.07937757438070212, + vert_correction: -0.10192722831646885, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 119, + rot_correction: 0.1108982206717197, + vert_correction: -0.007853981633974483, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 120, + rot_correction: -0.1108982206717197, + vert_correction: 0.14713125594312199, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 121, + rot_correction: -0.07937757438070212, + vert_correction: -0.05009094953223726, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 122, + rot_correction: -0.04768239516448509, + vert_correction: 0.0439822971502571, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 123, + rot_correction: -0.015899949485668342, + vert_correction: -0.10768681484805014, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 124, + rot_correction: 0.015899949485668342, + vert_correction: -0.02897246558310587, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 125, + rot_correction: 0.04768239516448509, + vert_correction: 0.0651007810993885, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 126, + rot_correction: 0.07937757438070212, + vert_correction: -0.08656833089891874, + vert_offset_correction: 0.0, + } + - { + dist_correction: 0.0, + dist_correction_x: 0.0, + dist_correction_y: 0.0, + focal_distance: 0.0, + focal_slope: 0.0, + laser_id: 127, + rot_correction: 0.1108982206717197, + vert_correction: 0.007504915783575617, + vert_offset_correction: 0.0, } num_lasers: 128 distance_resolution: 0.007 diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp index 785fa59c3..71aed2985 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_DRIVER_BASE_H #define NEBULA_DRIVER_BASE_H diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp index 02d7cd535..7e70c9a27 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/hesai/hesai_common.hpp" diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp index da9a1b579..af68702a2 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/hesai/hesai_common.hpp" diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp index 619c5a8fe..fa9f5a810 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/hesai/hesai_common.hpp" diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index a277137d2..a8caf43f5 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp index aa807e567..4b1ab3147 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp index 153435bbe..04a2581d3 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_WS_HESAI_SCAN_DECODER_HPP #define NEBULA_WS_HESAI_SCAN_DECODER_HPP diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp index 78f8a11bc..a9cb1b197 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/nebula_common.hpp" @@ -5,7 +19,9 @@ #include "nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp" #include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" +#include #include +#include namespace nebula { @@ -178,4 +194,4 @@ class HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e3x.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e3x.hpp index 65155efb4..758f21a0d 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e3x.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e3x.hpp @@ -1,8 +1,24 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" #include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp" +#include + namespace nebula { namespace drivers @@ -208,7 +224,7 @@ class Pandar128E3X : public HesaiSensor static constexpr size_t MAX_SCAN_BUFFER_POINTS = 691200; int getPacketRelativePointTimeOffset( - uint32_t block_id, uint32_t channel_id, const packet_t & packet) + uint32_t block_id, uint32_t channel_id, const packet_t & packet) override { auto n_returns = hesai_packet::get_n_returns(packet.tail.return_mode); int block_offset_ns = 3148 - 27778 * 2 * (2 - block_id - 1) / n_returns; @@ -272,4 +288,4 @@ class Pandar128E3X : public HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e4x.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e4x.hpp index 41cee89b3..a3ff6c7a8 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e4x.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e4x.hpp @@ -1,9 +1,25 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" #include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp" #include "nebula_decoders/nebula_decoders_hesai/decoders/pandar_128e3x.hpp" +#include + namespace nebula { namespace drivers @@ -23,11 +39,11 @@ typedef Packet128E3X Packet128E4X; // FIXME(mojomex): // The OT128 datasheet has entirely different numbers (and more azimuth states). // With the current sensor version, the numbers from the new datasheet are incorrect -// (clouds do not sync to ToS but ToS+.052s) +// (clouds do not sync to ToS but ToS+.052s) class Pandar128E4X : public HesaiSensor { private: -enum OperationalState { HIGH_RESOLUTION = 0, STANDARD = 1 }; + enum OperationalState { HIGH_RESOLUTION = 0, STANDARD = 1 }; static constexpr int firing_time_offset_static_ns_[128] = { 49758, 43224, 36690, 30156, 21980, 15446, 8912, 2378, 49758, 43224, 36690, 30156, 2378, @@ -71,7 +87,7 @@ enum OperationalState { HIGH_RESOLUTION = 0, STANDARD = 1 }; static constexpr size_t MAX_SCAN_BUFFER_POINTS = 691200; int getPacketRelativePointTimeOffset( - uint32_t block_id, uint32_t channel_id, const packet_t & packet) + uint32_t block_id, uint32_t channel_id, const packet_t & packet) override { auto n_returns = hesai_packet::get_n_returns(packet.tail.return_mode); int block_offset_ns; @@ -120,4 +136,4 @@ enum OperationalState { HIGH_RESOLUTION = 0, STANDARD = 1 }; }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_40.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_40.hpp index 12003721e..61a040ca9 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_40.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_40.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" @@ -73,4 +87,4 @@ class Pandar40 : public HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_64.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_64.hpp index b7a6640f3..908cbdb0c 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_64.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_64.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" @@ -53,4 +67,4 @@ class Pandar64 : public HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_at128.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_at128.hpp index e3c85e857..dc5b1c8f3 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_at128.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_at128.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" @@ -85,4 +99,4 @@ class PandarAT128 }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt128.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt128.hpp index ac136bc20..59809c857 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt128.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt128.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" @@ -100,4 +114,4 @@ class PandarQT128 : public HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt64.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt64.hpp index 1b7c4e54d..ab4b076e6 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt64.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_qt64.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" @@ -62,4 +76,4 @@ class PandarQT64 : public HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32.hpp index c9a5e7326..d0254a199 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32.hpp @@ -1,8 +1,24 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" #include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_sensor.hpp" +#include + namespace nebula { namespace drivers @@ -74,4 +90,4 @@ class PandarXT32 : public HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32m.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32m.hpp index 080876470..9d4f6259a 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32m.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/pandar_xt32m.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp" @@ -56,4 +70,4 @@ class PandarXT32M : public HesaiSensor }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index 4c211efcc..875a6a495 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_HESAI_DRIVER_H #define NEBULA_HESAI_DRIVER_H diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector.hpp index 82d2a7047..afd22650d 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/robosense/robosense_common.hpp" @@ -54,4 +68,4 @@ class AngleCorrector }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector_calibration_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector_calibration_based.hpp index 8c8c75e20..41f28a592 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector_calibration_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector_calibration_based.hpp @@ -1,9 +1,24 @@ +// Copyright 2024 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 "nebula_common/robosense/robosense_common.hpp" #include "nebula_decoders/nebula_decoders_robosense/decoders/angle_corrector.hpp" #include +#include namespace nebula { @@ -82,4 +97,4 @@ class AngleCorrectorCalibrationBased : public AngleCorrector }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v3.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v3.hpp index 7f9f52aba..948f16271 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v3.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v3.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp" @@ -8,8 +22,11 @@ #include #include #include +#include +#include +#include -using namespace boost::endian; +using namespace boost::endian; // NOLINT(build/namespaces) namespace nebula { @@ -247,7 +264,7 @@ class BpearlV3 : public RobosenseSensor< return firing_time_offset_ns_single_[block_id][channel_id]; } - ReturnMode getReturnMode(const robosense_packet::bpearl_v3::InfoPacket & info_packet) + ReturnMode getReturnMode(const robosense_packet::bpearl_v3::InfoPacket & info_packet) override { switch (info_packet.return_mode.value()) { case DUAL_RETURN_FLAG: @@ -262,12 +279,12 @@ class BpearlV3 : public RobosenseSensor< } RobosenseCalibrationConfiguration getSensorCalibration( - const robosense_packet::bpearl_v3::InfoPacket & info_packet) + const robosense_packet::bpearl_v3::InfoPacket & info_packet) override { return info_packet.sensor_calibration.getCalibration(); } - bool getSyncStatus(const robosense_packet::bpearl_v3::InfoPacket & info_packet) + bool getSyncStatus(const robosense_packet::bpearl_v3::InfoPacket & info_packet) override { switch (info_packet.sync_status.value()) { case SYNC_STATUS_INVALID_FLAG: @@ -282,7 +299,7 @@ class BpearlV3 : public RobosenseSensor< } std::map getSensorInfo( - const robosense_packet::bpearl_v3::InfoPacket & info_packet) + const robosense_packet::bpearl_v3::InfoPacket & info_packet) override { std::map sensor_info; sensor_info["motor_speed"] = std::to_string(info_packet.motor_speed.value()); @@ -457,4 +474,4 @@ class BpearlV3 : public RobosenseSensor< } }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v4.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v4.hpp index 3fae7b769..231fe9e64 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v4.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v4.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp" @@ -8,8 +22,11 @@ #include #include #include +#include +#include +#include -using namespace boost::endian; +using namespace boost::endian; // NOLINT(build/namespaces) namespace nebula { @@ -217,7 +234,7 @@ class BpearlV4 : public RobosenseSensor< return firing_time_offset_ns_single_[block_id][channel_id]; } - ReturnMode getReturnMode(const robosense_packet::bpearl_v4::InfoPacket & info_packet) + ReturnMode getReturnMode(const robosense_packet::bpearl_v4::InfoPacket & info_packet) override { switch (info_packet.return_mode.value()) { case DUAL_RETURN_FLAG: @@ -234,12 +251,12 @@ class BpearlV4 : public RobosenseSensor< } RobosenseCalibrationConfiguration getSensorCalibration( - const robosense_packet::bpearl_v4::InfoPacket & info_packet) + const robosense_packet::bpearl_v4::InfoPacket & info_packet) override { return info_packet.sensor_calibration.getCalibration(); } - bool getSyncStatus(const robosense_packet::bpearl_v4::InfoPacket & info_packet) + bool getSyncStatus(const robosense_packet::bpearl_v4::InfoPacket & info_packet) override { switch (info_packet.time_sync_state.value()) { case SYNC_STATUS_INVALID_FLAG: @@ -254,7 +271,7 @@ class BpearlV4 : public RobosenseSensor< } std::map getSensorInfo( - const robosense_packet::bpearl_v4::InfoPacket & info_packet) + const robosense_packet::bpearl_v4::InfoPacket & info_packet) override { std::map sensor_info; sensor_info["motor_speed"] = std::to_string(info_packet.motor_speed_setting.value()); @@ -376,4 +393,4 @@ class BpearlV4 : public RobosenseSensor< } }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/helios.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/helios.hpp index ac0e123c7..5da0320e5 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/helios.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/helios.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp" @@ -8,8 +22,11 @@ #include #include #include +#include +#include +#include -using namespace boost::endian; +using namespace boost::endian; // NOLINT(build/namespaces) namespace nebula { @@ -256,7 +273,7 @@ class Helios return firing_time_offset_ns_single_[block_id][channel_id]; } - ReturnMode getReturnMode(const robosense_packet::helios::InfoPacket & info_packet) + ReturnMode getReturnMode(const robosense_packet::helios::InfoPacket & info_packet) override { switch (info_packet.return_mode.value()) { case DUAL_RETURN_FLAG: @@ -273,12 +290,12 @@ class Helios } RobosenseCalibrationConfiguration getSensorCalibration( - const robosense_packet::helios::InfoPacket & info_packet) + const robosense_packet::helios::InfoPacket & info_packet) override { return info_packet.sensor_calibration.getCalibration(); } - bool getSyncStatus(const robosense_packet::helios::InfoPacket & info_packet) + bool getSyncStatus(const robosense_packet::helios::InfoPacket & info_packet) override { switch (info_packet.sync_status.value()) { case SYNC_STATUS_INVALID_FLAG: @@ -293,7 +310,7 @@ class Helios } std::map getSensorInfo( - const robosense_packet::helios::InfoPacket & info_packet) + const robosense_packet::helios::InfoPacket & info_packet) override { std::map sensor_info; sensor_info["motor_speed"] = std::to_string(info_packet.motor_speed.value()); @@ -452,4 +469,4 @@ class Helios }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_decoder.hpp index 60d77ca44..ab00b9af5 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_decoder.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/robosense/robosense_common.hpp" @@ -6,8 +20,10 @@ #include -#include "robosense_msgs/msg/robosense_packet.hpp" -#include "robosense_msgs/msg/robosense_scan.hpp" +#include +#include +#include +#include namespace nebula { @@ -265,4 +281,4 @@ class RobosenseDecoder : public RobosenseScanDecoder }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder.hpp index 86b9bc4aa..8e6f4d4bd 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder.hpp @@ -1,13 +1,27 @@ +// Copyright 2024 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 "nebula_common/robosense/robosense_common.hpp" #include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder_base.hpp" -#include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp" #include #include -#include +#include +#include #include namespace nebula @@ -81,4 +95,4 @@ class RobosenseInfoDecoder : public RobosenseInfoDecoderBase }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder_base.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder_base.hpp index d97dc4e1c..87d8279f0 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder_base.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder_base.hpp @@ -1,5 +1,25 @@ +// Copyright 2024 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 { namespace drivers @@ -39,4 +59,4 @@ class RobosenseInfoDecoderBase }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp index 4d5f2db2d..b4a7d3061 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp @@ -1,12 +1,30 @@ +// Copyright 2024 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 "boost/endian/buffers.hpp" +#include + +#include #include #include +#include +#include #include -using namespace boost::endian; +using namespace boost::endian; // NOLINT(build/namespaces) namespace nebula { @@ -34,7 +52,6 @@ struct Timestamp } }; - struct Unit { big_uint16_buf_t distance; @@ -137,9 +154,8 @@ struct ChannelAngleCorrection [[nodiscard]] float getAngle() const { - return sign.value() == ANGLE_SIGN_FLAG - ? static_cast(angle.value()) / 100.0f - : static_cast(angle.value()) / -100.0f; + return sign.value() == ANGLE_SIGN_FLAG ? static_cast(angle.value()) / 100.0f + : static_cast(angle.value()) / -100.0f; } }; @@ -264,4 +280,4 @@ inline std::string get_float_value(const uint16_t & raw_angle) } // namespace robosense_packet } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_scan_decoder.hpp index 54778ac3a..b87f4f078 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_scan_decoder.hpp @@ -1,12 +1,23 @@ +// Copyright 2024 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 "nebula_common/point_types.hpp" -#include "nebula_common/robosense/robosense_common.hpp" - -#include "robosense_msgs/msg/robosense_packet.hpp" -#include "robosense_msgs/msg/robosense_scan.hpp" #include +#include namespace nebula { diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_sensor.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_sensor.hpp index 5e39598ee..b88e49181 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_sensor.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/decoders/robosense_sensor.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/nebula_common.hpp" @@ -5,7 +19,11 @@ #include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_packet.hpp" #include -#include +#include +#include +#include +#include +#include namespace nebula { @@ -128,4 +146,4 @@ class RobosenseSensor virtual std::map getSensorInfo(const info_t & info_packet) = 0; }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_driver.hpp index 80a9c1285..55ea8d31d 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_driver.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_common/nebula_common.hpp" @@ -5,16 +19,13 @@ #include "nebula_common/point_types.hpp" #include "nebula_common/robosense/robosense_common.hpp" #include "nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp" -#include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_decoder.hpp" - -#include "robosense_msgs/msg/robosense_packet.hpp" -#include "robosense_msgs/msg/robosense_scan.hpp" +#include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_scan_decoder.hpp" #include -#include -#include -#include +#include +#include +#include namespace nebula { @@ -38,7 +49,8 @@ class RobosenseDriver : NebulaDriverBase /// @param calibration_configuration CalibrationConfiguration for this driver explicit RobosenseDriver( const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration); + const std::shared_ptr & + calibration_configuration); /// @brief Get current status of this driver /// @return Current status @@ -53,7 +65,8 @@ class RobosenseDriver : NebulaDriverBase /// @brief Convert RobosenseScan message to point cloud /// @param robosense_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ParseCloudPacket(const std::vector & packet); + std::tuple ParseCloudPacket( + const std::vector & packet); }; } // namespace drivers diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_info_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_info_driver.hpp index 706d7942e..859e97c4e 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_info_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_robosense/robosense_info_driver.hpp @@ -1,15 +1,22 @@ +// Copyright 2024 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 "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -#include "nebula_common/point_types.hpp" #include "nebula_common/robosense/robosense_common.hpp" -#include "nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp" -#include "nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v3.hpp" -#include "nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v4.hpp" -#include "nebula_decoders/nebula_decoders_robosense/decoders/helios.hpp" -#include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_decoder.hpp" -#include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder.hpp" #include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder_base.hpp" #include diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp index 07b97bbf0..f550e527f 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp @@ -1,10 +1,23 @@ +// Copyright 2024 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_WS_VELODYNE_SCAN_DECODER_HPP #define NEBULA_WS_VELODYNE_SCAN_DECODER_HPP #include #include #include - #include #include @@ -161,8 +174,8 @@ class VelodyneScanDecoder has_scanned_ = false; processed_packets_++; - uint32_t packet_first_azm = packet[OFFSET_FIRST_AZIMUTH]; // lower word of azimuth block 0 - packet_first_azm |= packet[OFFSET_FIRST_AZIMUTH + 1] << 8; // higher word of azimuth block 0 + uint32_t packet_first_azm = packet[OFFSET_FIRST_AZIMUTH]; // lower word of azimuth block 0 + packet_first_azm |= packet[OFFSET_FIRST_AZIMUTH + 1] << 8; // higher word of azimuth block 0 uint32_t packet_last_azm = packet[OFFSET_LAST_AZIMUTH]; packet_last_azm |= packet[OFFSET_LAST_AZIMUTH + 1] << 8; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp index 9c9c5da49..645b7fdaf 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp" diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp index eaba7a759..3d434af0c 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp" diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp index 1c7b29436..0dc4ba563 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp" diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp index ca11c3a6c..746cec719 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_VELODYNE_DRIVER_H #define NEBULA_VELODYNE_DRIVER_H diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index b3afa886b..22269bba7 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp" diff --git a/nebula_decoders/src/nebula_decoders_robosense/robosense_driver.cpp b/nebula_decoders/src/nebula_decoders_robosense/robosense_driver.cpp index 659684880..96984e120 100644 --- a/nebula_decoders/src/nebula_decoders_robosense/robosense_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_robosense/robosense_driver.cpp @@ -1,8 +1,11 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_decoders/nebula_decoders_robosense/robosense_driver.hpp" #include "nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v3.hpp" #include "nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v4.hpp" #include "nebula_decoders/nebula_decoders_robosense/decoders/helios.hpp" +#include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_decoder.hpp" namespace nebula { @@ -50,20 +53,19 @@ Status RobosenseDriver::SetCalibrationConfiguration( calibration_configuration.calibration_file + ")"); } -std::tuple RobosenseDriver::ParseCloudPacket(const std::vector & packet) +std::tuple RobosenseDriver::ParseCloudPacket( + const std::vector & packet) { -std::tuple pointcloud; + std::tuple pointcloud; auto logger = rclcpp::get_logger("RobosenseDriver"); - if (driver_status_ != nebula::Status::OK) - { + if (driver_status_ != nebula::Status::OK) { RCLCPP_ERROR(logger, "Driver not OK."); return pointcloud; } scan_decoder_->unpack(packet); - if (scan_decoder_->hasScanned()) - { + if (scan_decoder_->hasScanned()) { pointcloud = scan_decoder_->getPointcloud(); } diff --git a/nebula_decoders/src/nebula_decoders_robosense/robosense_info_driver.cpp b/nebula_decoders/src/nebula_decoders_robosense/robosense_info_driver.cpp index 532f166c5..cfdc566eb 100644 --- a/nebula_decoders/src/nebula_decoders_robosense/robosense_info_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_robosense/robosense_info_driver.cpp @@ -1,5 +1,12 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_decoders/nebula_decoders_robosense/robosense_info_driver.hpp" +#include "nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v3.hpp" +#include "nebula_decoders/nebula_decoders_robosense/decoders/bpearl_v4.hpp" +#include "nebula_decoders/nebula_decoders_robosense/decoders/helios.hpp" +#include "nebula_decoders/nebula_decoders_robosense/decoders/robosense_info_decoder.hpp" + namespace nebula { namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp index 120b26b44..75497ca74 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp" #include diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp index e7b284de8..2ba96d17f 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp" #include diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp index a6ee6c875..f9f2f2d7e 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp" #include diff --git a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp index 91970d35b..c173e6a9d 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp" #include "nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp" diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp index da0807b64..247fd1ba0 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp @@ -20,7 +20,6 @@ #include #include #include -#include #include #include diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp index f41c0c795..d7afb4dcc 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp @@ -20,7 +20,6 @@ #include #include #include -#include #include #include diff --git a/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp index 21304c287..64e3d7435 100644 --- a/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp @@ -15,21 +15,9 @@ #ifndef NEBULA_VelodyneRosOfflineExtractBag_H #define NEBULA_VelodyneRosOfflineExtractBag_H -#include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -#include "nebula_common/velodyne/velodyne_calibration_decoder.hpp" #include "nebula_common/velodyne/velodyne_common.hpp" #include "nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp" -#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" -#include "rclcpp/serialization.hpp" -#include "rclcpp/serialized_message.hpp" -#include "rcpputils/filesystem_helper.hpp" -#include "rcutils/time.h" -#include "rosbag2_cpp/reader.hpp" -#include "rosbag2_cpp/readers/sequential_reader.hpp" -#include "rosbag2_cpp/writer.hpp" -#include "rosbag2_cpp/writers/sequential_writer.hpp" -#include "rosbag2_storage/storage_options.hpp" #include #include @@ -38,7 +26,6 @@ #include #include -#include #include namespace nebula diff --git a/nebula_examples/src/common/parameter_descriptors.cpp b/nebula_examples/src/common/parameter_descriptors.cpp index b62cb8a9e..7f4cfed8c 100644 --- a/nebula_examples/src/common/parameter_descriptors.cpp +++ b/nebula_examples/src/common/parameter_descriptors.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/common/parameter_descriptors.hpp" namespace nebula diff --git a/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp b/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp index 3bf1da6de..fca1b5d7c 100644 --- a/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp +++ b/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp @@ -14,6 +14,11 @@ #include "velodyne/velodyne_ros_offline_extract_bag_pcd.hpp" +#include +#include + +#include + namespace nebula { namespace ros diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp index f5692f5f5..9044bf5c6 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp @@ -1,13 +1,24 @@ +// Copyright 2024 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_HW_INTERFACE_BASE_H #define NEBULA_HW_INTERFACE_BASE_H -#include "boost_udp_driver/udp_driver.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" #include -#include -#include #include namespace nebula diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp index 13ad0ed53..b51ce3b3b 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 HESAI_CMD_RESPONSE_HPP #define HESAI_CMD_RESPONSE_HPP diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 10a1ec93f..668469b2e 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_HESAI_HW_INTERFACE_H #define NEBULA_HESAI_HW_INTERFACE_H // Have to define macros to silence warnings about deprecated headers being used by @@ -16,14 +30,10 @@ #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/hesai/hesai_status.hpp" #include "nebula_common/util/expected.hpp" -#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp" #include -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" - #include #include #include @@ -127,9 +137,6 @@ class HesaiHwInterface std::mutex mtx_inflight_tcp_request_; - int prev_phase_{}; - - bool is_solid_state = false; int target_model_no; /// @brief Get a one-off HTTP client to communicate with the hardware diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_robosense/robosense_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_robosense/robosense_hw_interface.hpp index bf39833df..7ae25bf21 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_robosense/robosense_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_robosense/robosense_hw_interface.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 // Have to define macros to silence warnings about deprecated headers being used by @@ -13,9 +27,12 @@ #include #include - #include +#include +#include +#include + namespace nebula { namespace drivers @@ -78,14 +95,12 @@ class RobosenseHwInterface /// @brief Registering callback for RobosenseScan /// @param scan_callback Callback function /// @return Resulting status - Status RegisterScanCallback( - std::function &)> scan_callback); + Status RegisterScanCallback(std::function &)> scan_callback); /// @brief Registering callback for RobosensePacket /// @param scan_callback Callback function /// @return Resulting status - Status RegisterInfoCallback( - std::function &)> info_callback); + Status RegisterInfoCallback(std::function &)> info_callback); /// @brief Setting rclcpp::Logger /// @param node Logger diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp index 56c7da9a3..3911b37d3 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_VELODYNE_HW_INTERFACE_H #define NEBULA_VELODYNE_HW_INTERFACE_H diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 29b260098..4a976f9e6 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" // #define WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE @@ -747,7 +749,7 @@ HesaiStatus HesaiHwInterface::GetLidarMonitorAsyncHttp( } hcd->asyncGet( - [this, str_callback](const std::string & str) { str_callback(str); }, + [str_callback](const std::string & str) { str_callback(str); }, "/pandar.cgi?action=get&object=lidar_monitor"); boost::system::error_code ec; ctx->run(ec); diff --git a/nebula_hw_interfaces/src/nebula_robosense_hw_interfaces/robosense_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_robosense_hw_interfaces/robosense_hw_interface.cpp index be004682a..3ce4858fc 100644 --- a/nebula_hw_interfaces/src/nebula_robosense_hw_interfaces/robosense_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_robosense_hw_interfaces/robosense_hw_interface.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_hw_interfaces/nebula_hw_interfaces_robosense/robosense_hw_interface.hpp" namespace nebula { @@ -63,7 +65,6 @@ Status RobosenseHwInterface::InfoInterfaceStart() info_udp_driver_->receiver()->asyncReceive( std::bind(&RobosenseHwInterface::ReceiveInfoPacketCallback, this, std::placeholders::_1)); - } catch (const std::exception & ex) { Status status = Status::UDP_CONNECTION_ERROR; std::cerr << status << sensor_configuration_->sensor_ip << "," @@ -89,14 +90,14 @@ Status RobosenseHwInterface::SetSensorConfiguration( } Status RobosenseHwInterface::RegisterScanCallback( - std::function&)> scan_callback) + std::function &)> scan_callback) { scan_reception_callback_ = std::move(scan_callback); return Status::OK; } Status RobosenseHwInterface::RegisterInfoCallback( - std::function&)> info_callback) + std::function &)> info_callback) { info_reception_callback_ = std::move(info_callback); return Status::OK; diff --git a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp index 4b7c7ee10..23b01d2b4 100644 --- a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp" namespace nebula diff --git a/nebula_messages/robosense_msgs/msg/RobosenseInfoPacket.msg b/nebula_messages/robosense_msgs/msg/RobosenseInfoPacket.msg index acf5751bd..944d41abf 100644 --- a/nebula_messages/robosense_msgs/msg/RobosenseInfoPacket.msg +++ b/nebula_messages/robosense_msgs/msg/RobosenseInfoPacket.msg @@ -1,2 +1,2 @@ string lidar_model -RobosensePacket packet \ No newline at end of file +RobosensePacket packet diff --git a/nebula_messages/robosense_msgs/msg/RobosensePacket.msg b/nebula_messages/robosense_msgs/msg/RobosensePacket.msg index 713682931..40b73bd17 100644 --- a/nebula_messages/robosense_msgs/msg/RobosensePacket.msg +++ b/nebula_messages/robosense_msgs/msg/RobosensePacket.msg @@ -1,2 +1,2 @@ builtin_interfaces/Time stamp -uint8[1248] data \ No newline at end of file +uint8[1248] data diff --git a/nebula_messages/robosense_msgs/msg/RobosenseScan.msg b/nebula_messages/robosense_msgs/msg/RobosenseScan.msg index 0c2b5518b..25bd36a37 100644 --- a/nebula_messages/robosense_msgs/msg/RobosenseScan.msg +++ b/nebula_messages/robosense_msgs/msg/RobosenseScan.msg @@ -1,2 +1,2 @@ std_msgs/Header header -RobosensePacket[] packets \ No newline at end of file +RobosensePacket[] packets diff --git a/nebula_messages/robosense_msgs/package.xml b/nebula_messages/robosense_msgs/package.xml index 29077edb2..e41802175 100644 --- a/nebula_messages/robosense_msgs/package.xml +++ b/nebula_messages/robosense_msgs/package.xml @@ -1,22 +1,22 @@ - robosense_msgs - 0.0.0 - Robosense message types for Nebula - Mehmet Emin BASOGLU - TODO: License declaration + robosense_msgs + 0.0.0 + Robosense message types for Nebula + Mehmet Emin BASOGLU + TODO: License declaration - ament_cmake_auto - rosidl_default_generators + ament_cmake_auto + rosidl_default_generators - builtin_interfaces - std_msgs + builtin_interfaces + std_msgs - rosidl_default_runtime - rosidl_interface_packages + rosidl_default_runtime + rosidl_interface_packages - - ament_cmake - + + ament_cmake + diff --git a/nebula_ros/config/lidar/hesai/Pandar128E4X.param.yaml b/nebula_ros/config/lidar/hesai/Pandar128E4X.param.yaml index bf93088c6..7f0375f42 100644 --- a/nebula_ros/config/lidar/hesai/Pandar128E4X.param.yaml +++ b/nebula_ros/config/lidar/hesai/Pandar128E4X.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 @@ -11,7 +11,7 @@ diag_span: 1000 min_range: 0.3 max_range: 300.0 - cloud_min_angle: 0 + cloud_min_angle: 0 cloud_max_angle: 360 scan_phase: 0.0 sensor_model: Pandar128E4X @@ -23,4 +23,4 @@ ptp_transport_type: L2 ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/hesai/Pandar40P.param.yaml b/nebula_ros/config/lidar/hesai/Pandar40P.param.yaml index 7dd0c7bf3..c24d61d36 100644 --- a/nebula_ros/config/lidar/hesai/Pandar40P.param.yaml +++ b/nebula_ros/config/lidar/hesai/Pandar40P.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 @@ -18,9 +18,9 @@ calibration_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).csv rotation_speed: 600 return_mode: Dual - ptp_profile: "1588v2" + ptp_profile: 1588v2 ptp_domain: 0 ptp_transport_type: UDP ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/hesai/Pandar64.param.yaml b/nebula_ros/config/lidar/hesai/Pandar64.param.yaml index e1ec8906e..1a1b975f6 100644 --- a/nebula_ros/config/lidar/hesai/Pandar64.param.yaml +++ b/nebula_ros/config/lidar/hesai/Pandar64.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 @@ -17,9 +17,9 @@ sensor_model: Pandar64 rotation_speed: 600 return_mode: Dual - ptp_profile: "1588v2" + ptp_profile: 1588v2 ptp_domain: 0 ptp_transport_type: UDP ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/hesai/PandarAT128.param.yaml b/nebula_ros/config/lidar/hesai/PandarAT128.param.yaml index 5f3ab1ba5..7db50fb52 100644 --- a/nebula_ros/config/lidar/hesai/PandarAT128.param.yaml +++ b/nebula_ros/config/lidar/hesai/PandarAT128.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 @@ -19,9 +19,9 @@ calibration_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).csv rotation_speed: 200 return_mode: Dual - ptp_profile: "1588v2" + ptp_profile: 1588v2 ptp_domain: 0 ptp_transport_type: UDP ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/hesai/PandarQT128.param.yaml b/nebula_ros/config/lidar/hesai/PandarQT128.param.yaml index 86593a4a3..c26977a2b 100644 --- a/nebula_ros/config/lidar/hesai/PandarQT128.param.yaml +++ b/nebula_ros/config/lidar/hesai/PandarQT128.param.yaml @@ -1,11 +1,11 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 - launch_hw: true + launch_hw: true setup_sensor: true frame_id: hesai diag_span: 1000 @@ -18,9 +18,9 @@ calibration_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).csv rotation_speed: 600 return_mode: LastStrongest - ptp_profile: "1588v2" + ptp_profile: 1588v2 ptp_domain: 0 ptp_transport_type: UDP ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/hesai/PandarQT64.param.yaml b/nebula_ros/config/lidar/hesai/PandarQT64.param.yaml index bd1bc2245..c707f7e12 100644 --- a/nebula_ros/config/lidar/hesai/PandarQT64.param.yaml +++ b/nebula_ros/config/lidar/hesai/PandarQT64.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 @@ -18,9 +18,9 @@ calibration_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).csv rotation_speed: 600 return_mode: Dual - ptp_profile: "1588v2" + ptp_profile: 1588v2 ptp_domain: 0 ptp_transport_type: UDP ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/hesai/PandarXT32.param.yaml b/nebula_ros/config/lidar/hesai/PandarXT32.param.yaml index 1aa27e856..db56ed435 100644 --- a/nebula_ros/config/lidar/hesai/PandarXT32.param.yaml +++ b/nebula_ros/config/lidar/hesai/PandarXT32.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 @@ -18,9 +18,9 @@ calibration_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).csv rotation_speed: 600 return_mode: Dual - ptp_profile: "1588v2" + ptp_profile: 1588v2 ptp_domain: 0 ptp_transport_type: UDP ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/hesai/PandarXT32M.param.yaml b/nebula_ros/config/lidar/hesai/PandarXT32M.param.yaml index c87b822ef..66cee1218 100644 --- a/nebula_ros/config/lidar/hesai/PandarXT32M.param.yaml +++ b/nebula_ros/config/lidar/hesai/PandarXT32M.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 10110 packet_mtu_size: 1500 @@ -18,9 +18,9 @@ calibration_file: $(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).csv rotation_speed: 600 return_mode: LastStrongest - ptp_profile: "1588v2" + ptp_profile: 1588v2 ptp_domain: 0 ptp_transport_type: UDP ptp_switch_type: TSN retry_hw: true - dual_return_distance_threshold: 0.1 \ No newline at end of file + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/robosense/Bpearl.param.yaml b/nebula_ros/config/lidar/robosense/Bpearl.param.yaml index c9abc5255..74a12080d 100644 --- a/nebula_ros/config/lidar/robosense/Bpearl.param.yaml +++ b/nebula_ros/config/lidar/robosense/Bpearl.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 2369 packet_mtu_size: 1500 diff --git a/nebula_ros/config/lidar/robosense/Helios.param.yaml b/nebula_ros/config/lidar/robosense/Helios.param.yaml index bc84175bd..5694362fc 100644 --- a/nebula_ros/config/lidar/robosense/Helios.param.yaml +++ b/nebula_ros/config/lidar/robosense/Helios.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 2369 packet_mtu_size: 1500 diff --git a/nebula_ros/config/lidar/velodyne/VLP16.param.yaml b/nebula_ros/config/lidar/velodyne/VLP16.param.yaml index 7604367ca..b46e980f0 100644 --- a/nebula_ros/config/lidar/velodyne/VLP16.param.yaml +++ b/nebula_ros/config/lidar/velodyne/VLP16.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 2369 packet_mtu_size: 1500 @@ -18,4 +18,4 @@ scan_phase: 0.0 sensor_model: VLP16 rotation_speed: 600 - return_mode: Dual \ No newline at end of file + return_mode: Dual diff --git a/nebula_ros/config/lidar/velodyne/VLP32.param.yaml b/nebula_ros/config/lidar/velodyne/VLP32.param.yaml index 153c492a2..96ce39a32 100644 --- a/nebula_ros/config/lidar/velodyne/VLP32.param.yaml +++ b/nebula_ros/config/lidar/velodyne/VLP32.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 2369 packet_mtu_size: 1500 diff --git a/nebula_ros/config/lidar/velodyne/VLS128.param.yaml b/nebula_ros/config/lidar/velodyne/VLS128.param.yaml index 2cddcd352..c5c0c6313 100644 --- a/nebula_ros/config/lidar/velodyne/VLS128.param.yaml +++ b/nebula_ros/config/lidar/velodyne/VLS128.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" + host_ip: 255.255.255.255 + sensor_ip: 192.168.1.201 data_port: 2368 gnss_port: 2369 packet_mtu_size: 1500 diff --git a/nebula_ros/config/radar/continental/ARS548.param.yaml b/nebula_ros/config/radar/continental/ARS548.param.yaml index 91021f442..7f9a76ed7 100644 --- a/nebula_ros/config/radar/continental/ARS548.param.yaml +++ b/nebula_ros/config/radar/continental/ARS548.param.yaml @@ -1,13 +1,13 @@ /**: ros__parameters: - host_ip: "10.13.1.166" - sensor_ip: "10.13.1.114" + host_ip: 10.13.1.166 + sensor_ip: 10.13.1.114 data_port: 42102 frame_id: continental base_frame: base_link object_frame: base_link launch_hw: true - multicast_ip: "224.0.2.2" + multicast_ip: 224.0.2.2 sensor_model: ARS548 configuration_host_port: 42401 configuration_sensor_port: 42101 diff --git a/nebula_ros/include/nebula_ros/common/mt_queue.hpp b/nebula_ros/include/nebula_ros/common/mt_queue.hpp index aca385ce3..c7fe30c0f 100644 --- a/nebula_ros/include/nebula_ros/common/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/common/mt_queue.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 diff --git a/nebula_ros/include/nebula_ros/common/nebula_driver_ros_wrapper_base.hpp b/nebula_ros/include/nebula_ros/common/nebula_driver_ros_wrapper_base.hpp deleted file mode 100644 index 8ca27b175..000000000 --- a/nebula_ros/include/nebula_ros/common/nebula_driver_ros_wrapper_base.hpp +++ /dev/null @@ -1,53 +0,0 @@ -#ifndef NEBULA_DRIVER_WRAPPER_BASE_H -#define NEBULA_DRIVER_WRAPPER_BASE_H - -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" - -#include -#include -#include - -#include - -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Base class for ros wrapper of each sensor driver -class NebulaDriverRosWrapperBase -{ -public: - NebulaDriverRosWrapperBase() = default; - - NebulaDriverRosWrapperBase(NebulaDriverRosWrapperBase && c) = delete; - NebulaDriverRosWrapperBase & operator=(NebulaDriverRosWrapperBase && c) = delete; - NebulaDriverRosWrapperBase(const NebulaDriverRosWrapperBase & c) = delete; - NebulaDriverRosWrapperBase & operator=(const NebulaDriverRosWrapperBase & c) = delete; - -private: - /// @brief Virtual function for initializing ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - virtual Status InitializeDriver( - [[maybe_unused]] std::shared_ptr sensor_configuration, - [[maybe_unused]] std::shared_ptr - calibration_configuration) - { - return Status::NOT_IMPLEMENTED; - } - - // status ReceiveScanMsgCallback(void * ScanMsg); // ROS message callback for individual packet - // type - - /// @brief Point cloud publisher - rclcpp::Publisher::SharedPtr cloud_pub_; -}; - -} // namespace ros -} // namespace nebula -#endif // NEBULA_DRIVER_WRAPPER_BASE_H diff --git a/nebula_ros/include/nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp b/nebula_ros/include/nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp deleted file mode 100644 index b42948426..000000000 --- a/nebula_ros/include/nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp +++ /dev/null @@ -1,54 +0,0 @@ -#ifndef NEBULA_HW_INTERFACE_WRAPPER_BASE_H -#define NEBULA_HW_INTERFACE_WRAPPER_BASE_H - -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" - -#include -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Base class for hardware interface ros wrapper of each LiDAR -class NebulaHwInterfaceWrapperBase -{ -public: - NebulaHwInterfaceWrapperBase() = default; - - NebulaHwInterfaceWrapperBase(NebulaHwInterfaceWrapperBase && c) = delete; - NebulaHwInterfaceWrapperBase & operator=(NebulaHwInterfaceWrapperBase && c) = delete; - NebulaHwInterfaceWrapperBase(const NebulaHwInterfaceWrapperBase & c) = delete; - NebulaHwInterfaceWrapperBase & operator=(const NebulaHwInterfaceWrapperBase & c) = delete; - - /// @brief Start point cloud streaming (Call SensorInterfaceStart of HwInterface) - /// @return Resulting status - virtual Status StreamStart() = 0; - - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - virtual Status StreamStop() = 0; - - /// @brief Shutdown (not used) - /// @return Resulting status - virtual Status Shutdown() = 0; - -protected: - /// @brief Virtual function for initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - virtual Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) = 0; - // void SendDataPacket(const std::vector &buffer); // Ideally this will be - // implemented as specific functions, GetFanStatus, GetEchoMode - - /// @brief Enable sensor setup during initialization and set_parameters_callback - bool setup_sensor; -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_HW_INTERFACE_WRAPPER_BASE_H diff --git a/nebula_ros/include/nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp b/nebula_ros/include/nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp deleted file mode 100644 index 29f8440cd..000000000 --- a/nebula_ros/include/nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp +++ /dev/null @@ -1,49 +0,0 @@ -#ifndef NEBULA_HW_MONITOR_WRAPPER_BASE_H -#define NEBULA_HW_MONITOR_WRAPPER_BASE_H - -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" - -#include -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Base class for hardware monitor ros wrapper of each LiDAR -class NebulaHwMonitorWrapperBase -{ -public: - NebulaHwMonitorWrapperBase() = default; - - NebulaHwMonitorWrapperBase(NebulaHwMonitorWrapperBase && c) = delete; - NebulaHwMonitorWrapperBase & operator=(NebulaHwMonitorWrapperBase && c) = delete; - NebulaHwMonitorWrapperBase(const NebulaHwMonitorWrapperBase & c) = delete; - NebulaHwMonitorWrapperBase & operator=(const NebulaHwMonitorWrapperBase & c) = delete; - - /// @brief Start monitoring (not used) - /// @return Resulting status - virtual Status MonitorStart() = 0; - - /// @brief Stop monitoring (not used) - /// @return Resulting status - virtual Status MonitorStop() = 0; - - /// @brief Shutdown (not used) - /// @return Resulting status - virtual Status Shutdown() = 0; - -protected: - /// @brief Virtual function for initializing hardware monitor ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - virtual Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) = 0; -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_HW_MONITOR_WRAPPER_BASE_H diff --git a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp index 6d4e38504..db37cdb10 100644 --- a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp +++ b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 diff --git a/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp index 522f9a32d..fc4dd2967 100644 --- a/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp +++ b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp index b2bdf856c..396f16d23 100644 --- a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 63ce94915..8a70aa0e3 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "boost_tcp_driver/tcp_driver.hpp" diff --git a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp index 0791af5e2..9706497c6 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_ros/common/parameter_descriptors.hpp" diff --git a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp index 0b270623f..d8885574f 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp @@ -1,6 +1,18 @@ -#pragma once +// Copyright 2024 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_ros/common/parameter_descriptors.hpp" +#pragma once #include #include @@ -12,7 +24,6 @@ #include #include -#include #include #include #include @@ -94,7 +105,6 @@ class HesaiHwMonitorWrapper std::vector temperature_names_; - bool setup_sensor; const std::string MSG_NOT_SUPPORTED = "Not supported"; const std::string MSG_ERROR = "Error"; const std::string MSG_SEP = ": "; diff --git a/nebula_ros/include/nebula_ros/robosense/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/robosense/decoder_wrapper.hpp index d051d6340..f0d858e59 100644 --- a/nebula_ros/include/nebula_ros/robosense/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/robosense/decoder_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_ros/common/watchdog_timer.hpp" @@ -13,6 +27,7 @@ #include #include +#include namespace nebula { diff --git a/nebula_ros/include/nebula_ros/robosense/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/robosense/hw_interface_wrapper.hpp index 31f52c710..29c6efef4 100644 --- a/nebula_ros/include/nebula_ros/robosense/hw_interface_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/robosense/hw_interface_wrapper.hpp @@ -1,11 +1,26 @@ +// Copyright 2024 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 { namespace ros @@ -13,10 +28,12 @@ namespace ros class RobosenseHwInterfaceWrapper { public: - explicit RobosenseHwInterfaceWrapper(rclcpp::Node* const parent_node, - std::shared_ptr& config); + explicit RobosenseHwInterfaceWrapper( + rclcpp::Node * const parent_node, + std::shared_ptr & config); - void OnConfigChange(const std::shared_ptr & new_config); + void OnConfigChange( + const std::shared_ptr & new_config); nebula::Status Status(); diff --git a/nebula_ros/include/nebula_ros/robosense/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/robosense/hw_monitor_wrapper.hpp index 6b56f33e5..a5fe251e6 100644 --- a/nebula_ros/include/nebula_ros/robosense/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/robosense/hw_monitor_wrapper.hpp @@ -1,21 +1,34 @@ -#pragma once +// Copyright 2024 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_ros/common/parameter_descriptors.hpp" +#pragma once #include +#include #include #include #include - -#include #include #include #include #include +#include +#include #include -#include +#include namespace nebula { @@ -26,10 +39,12 @@ namespace ros class RobosenseHwMonitorWrapper { public: - explicit RobosenseHwMonitorWrapper(rclcpp::Node* const parent_node, - std::shared_ptr& config); - - void OnConfigChange(const std::shared_ptr & new_config); + explicit RobosenseHwMonitorWrapper( + rclcpp::Node * const parent_node, + std::shared_ptr & config); + + void OnConfigChange( + const std::shared_ptr & new_config); /// @brief Callback for receiving DIFOP packet /// @param info_msg Received DIFOP packet diff --git a/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp index 2bf44bfd6..0c66e0f9d 100644 --- a/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp @@ -1,7 +1,20 @@ +// Copyright 2024 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 "nebula_ros/common/mt_queue.hpp" -#include "nebula_ros/common/parameter_descriptors.hpp" #include "nebula_ros/robosense/decoder_wrapper.hpp" #include "nebula_ros/robosense/hw_interface_wrapper.hpp" #include "nebula_ros/robosense/hw_monitor_wrapper.hpp" @@ -24,11 +37,11 @@ #include #include -#include -#include +#include #include #include #include +#include namespace nebula { diff --git a/nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp index 3cfc8b214..e78e51e0c 100644 --- a/nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_ros/common/parameter_descriptors.hpp" diff --git a/nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp index e20125710..e919b4367 100644 --- a/nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_ros/common/parameter_descriptors.hpp" diff --git a/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp index a87de5095..c86bfd917 100644 --- a/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_ros/common/parameter_descriptors.hpp" diff --git a/nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp index 5b8d17697..2ed7c4038 100644 --- a/nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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 "nebula_ros/common/mt_queue.hpp" diff --git a/nebula_ros/schema/ARS548.schema.json b/nebula_ros/schema/ARS548.schema.json index 28eeb9907..1245c1190 100644 --- a/nebula_ros/schema/ARS548.schema.json +++ b/nebula_ros/schema/ARS548.schema.json @@ -79,10 +79,14 @@ "$ref": "#/definitions/ARS548" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/Bpearl.schema.json b/nebula_ros/schema/Bpearl.schema.json index f813380fa..17326d0fd 100644 --- a/nebula_ros/schema/Bpearl.schema.json +++ b/nebula_ros/schema/Bpearl.schema.json @@ -80,10 +80,14 @@ "$ref": "#/definitions/Bpearl" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/Helios.schema.json b/nebula_ros/schema/Helios.schema.json index a9a21ac04..6e4881c1c 100644 --- a/nebula_ros/schema/Helios.schema.json +++ b/nebula_ros/schema/Helios.schema.json @@ -80,10 +80,14 @@ "$ref": "#/definitions/Helios" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/Pandar128E4X.schema.json b/nebula_ros/schema/Pandar128E4X.schema.json index 46aba8e65..913d58be0 100644 --- a/nebula_ros/schema/Pandar128E4X.schema.json +++ b/nebula_ros/schema/Pandar128E4X.schema.json @@ -130,9 +130,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/Pandar40P.schema.json b/nebula_ros/schema/Pandar40P.schema.json index d41b96797..0ec03169e 100644 --- a/nebula_ros/schema/Pandar40P.schema.json +++ b/nebula_ros/schema/Pandar40P.schema.json @@ -120,9 +120,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/Pandar64.schema.json b/nebula_ros/schema/Pandar64.schema.json index fceec64e4..cf95db7d5 100644 --- a/nebula_ros/schema/Pandar64.schema.json +++ b/nebula_ros/schema/Pandar64.schema.json @@ -116,9 +116,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/PandarAT128.schema.json b/nebula_ros/schema/PandarAT128.schema.json index f74cd9a6f..7b138055a 100644 --- a/nebula_ros/schema/PandarAT128.schema.json +++ b/nebula_ros/schema/PandarAT128.schema.json @@ -70,7 +70,7 @@ "$ref": "sub/hardware.json#/definitions/rotation_speed", "default": 200, "enum": [ - 200, + 200, 400 ] }, @@ -142,9 +142,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/PandarQT128.schema.json b/nebula_ros/schema/PandarQT128.schema.json index 1fcd4fc7c..f139b890c 100644 --- a/nebula_ros/schema/PandarQT128.schema.json +++ b/nebula_ros/schema/PandarQT128.schema.json @@ -124,9 +124,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/PandarQT64.schema.json b/nebula_ros/schema/PandarQT64.schema.json index 9a683132d..81ee37460 100644 --- a/nebula_ros/schema/PandarQT64.schema.json +++ b/nebula_ros/schema/PandarQT64.schema.json @@ -120,9 +120,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/PandarXT32.schema.json b/nebula_ros/schema/PandarXT32.schema.json index 0f0c022ed..2ef52aa39 100644 --- a/nebula_ros/schema/PandarXT32.schema.json +++ b/nebula_ros/schema/PandarXT32.schema.json @@ -124,9 +124,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/PandarXT32M.schema.json b/nebula_ros/schema/PandarXT32M.schema.json index bcc3a9d36..ac5051f5e 100644 --- a/nebula_ros/schema/PandarXT32M.schema.json +++ b/nebula_ros/schema/PandarXT32M.schema.json @@ -124,9 +124,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/VLP16.schema.json b/nebula_ros/schema/VLP16.schema.json index dca0a3aa0..db72f5778 100644 --- a/nebula_ros/schema/VLP16.schema.json +++ b/nebula_ros/schema/VLP16.schema.json @@ -96,10 +96,14 @@ "$ref": "#/definitions/VLP16" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/VLP32.schema.json b/nebula_ros/schema/VLP32.schema.json index 319fa4bb4..55cbc546d 100644 --- a/nebula_ros/schema/VLP32.schema.json +++ b/nebula_ros/schema/VLP32.schema.json @@ -97,9 +97,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/VLS128.schema.json b/nebula_ros/schema/VLS128.schema.json index 82545e946..86ddcb79f 100644 --- a/nebula_ros/schema/VLS128.schema.json +++ b/nebula_ros/schema/VLS128.schema.json @@ -97,9 +97,13 @@ }, "additionalProperties": false }, - "required": ["ros__parameters"] + "required": [ + "ros__parameters" + ] } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/example.schema.template.json b/nebula_ros/schema/example.schema.template.json index 727f358dc..19d39dfc9 100644 --- a/nebula_ros/schema/example.schema.template.json +++ b/nebula_ros/schema/example.schema.template.json @@ -53,10 +53,14 @@ "$ref": "#/definitions/" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } diff --git a/nebula_ros/schema/sub/hardware.json b/nebula_ros/schema/sub/hardware.json index bdc6a59ab..21073acc2 100644 --- a/nebula_ros/schema/sub/hardware.json +++ b/nebula_ros/schema/sub/hardware.json @@ -29,4 +29,4 @@ "description": "Whether TCP connections are retried on failure or the driver should instead exit." } } -} \ No newline at end of file +} diff --git a/nebula_ros/schema/sub/lidar_robosense.json b/nebula_ros/schema/sub/lidar_robosense.json index d2a946385..5fed19f04 100644 --- a/nebula_ros/schema/sub/lidar_robosense.json +++ b/nebula_ros/schema/sub/lidar_robosense.json @@ -20,4 +20,4 @@ ] } } -} \ No newline at end of file +} diff --git a/nebula_ros/schema/sub/lidar_velodyne.json b/nebula_ros/schema/sub/lidar_velodyne.json index 933504344..182952696 100644 --- a/nebula_ros/schema/sub/lidar_velodyne.json +++ b/nebula_ros/schema/sub/lidar_velodyne.json @@ -32,4 +32,4 @@ "multipleOf": 60 } } -} \ No newline at end of file +} diff --git a/nebula_ros/schema/sub/misc.json b/nebula_ros/schema/sub/misc.json index e74d461bb..3164b998e 100644 --- a/nebula_ros/schema/sub/misc.json +++ b/nebula_ros/schema/sub/misc.json @@ -87,4 +87,4 @@ "description": "Sensor scan phase." } } -} \ No newline at end of file +} diff --git a/nebula_ros/schema/sub/radar_continental.json b/nebula_ros/schema/sub/radar_continental.json index cf499f2ba..278877917 100644 --- a/nebula_ros/schema/sub/radar_continental.json +++ b/nebula_ros/schema/sub/radar_continental.json @@ -11,4 +11,4 @@ ] } } -} \ No newline at end of file +} diff --git a/nebula_ros/schema/sub/topic.json b/nebula_ros/schema/sub/topic.json index b20f859d3..5394da54f 100644 --- a/nebula_ros/schema/sub/topic.json +++ b/nebula_ros/schema/sub/topic.json @@ -47,4 +47,4 @@ "description": "Use sensor time for published sensor data." } } -} \ No newline at end of file +} diff --git a/nebula_ros/schema/sub/type_vendor.template.json b/nebula_ros/schema/sub/type_vendor.template.json index 53a7ca6be..e430a450e 100644 --- a/nebula_ros/schema/sub/type_vendor.template.json +++ b/nebula_ros/schema/sub/type_vendor.template.json @@ -26,4 +26,4 @@ "$comment": "Wrong! If no changes declare parameter in schema/.schema.json." } } -} \ No newline at end of file +} diff --git a/nebula_ros/src/common/parameter_descriptors.cpp b/nebula_ros/src/common/parameter_descriptors.cpp index b62cb8a9e..7f4cfed8c 100644 --- a/nebula_ros/src/common/parameter_descriptors.cpp +++ b/nebula_ros/src/common/parameter_descriptors.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/common/parameter_descriptors.hpp" namespace nebula diff --git a/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp b/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp index 52f8c1df5..a1db3cc2d 100644 --- a/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp +++ b/nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp @@ -14,6 +14,8 @@ #include "nebula_ros/continental/continental_ars548_ros_wrapper.hpp" +#pragma clang diagnostic ignored "-Wbitwise-instead-of-logical" + namespace nebula { namespace ros diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index bb18789fe..b13d9d782 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -1,5 +1,8 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/hesai/decoder_wrapper.hpp" +#pragma clang diagnostic ignored "-Wbitwise-instead-of-logical" namespace nebula { namespace ros diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 4c965aee5..f7b93cb81 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -1,5 +1,9 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/hesai/hesai_ros_wrapper.hpp" +#pragma clang diagnostic ignored "-Wbitwise-instead-of-logical" + namespace nebula { namespace ros @@ -38,7 +42,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) decoder_thread_ = std::thread([this]() { while (true) { - decoder_wrapper_->ProcessCloudPacket(std::move(packet_queue_.pop())); + decoder_wrapper_->ProcessCloudPacket(packet_queue_.pop()); } }); @@ -72,8 +76,7 @@ nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() config.return_mode = drivers::ReturnModeFromStringHesai(_return_mode, config.sensor_model); config.host_ip = declare_parameter("host_ip", param_read_only()); - config.sensor_ip = - declare_parameter("sensor_ip", param_read_only()); + config.sensor_ip = declare_parameter("sensor_ip", param_read_only()); config.data_port = declare_parameter("data_port", param_read_only()); config.gnss_port = declare_parameter("gnss_port", param_read_only()); config.frame_id = declare_parameter("frame_id", param_read_write()); @@ -99,8 +102,7 @@ nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() descriptor.additional_constraints = "300, 600, 1200"; descriptor.integer_range = int_range(300, 1200, 300); } - config.rotation_speed = - declare_parameter("rotation_speed", descriptor); + config.rotation_speed = declare_parameter("rotation_speed", descriptor); } { rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); diff --git a/nebula_ros/src/hesai/hw_interface_wrapper.cpp b/nebula_ros/src/hesai/hw_interface_wrapper.cpp index dd93f7d96..f9abbd164 100644 --- a/nebula_ros/src/hesai/hw_interface_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_interface_wrapper.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/hesai/hw_interface_wrapper.hpp" namespace nebula diff --git a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp index 721da5502..239c57d3f 100644 --- a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp @@ -1,5 +1,9 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/hesai/hw_monitor_wrapper.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" + namespace nebula { namespace ros diff --git a/nebula_ros/src/robosense/decoder_wrapper.cpp b/nebula_ros/src/robosense/decoder_wrapper.cpp index b9e47b2cc..c7cae7d3a 100644 --- a/nebula_ros/src/robosense/decoder_wrapper.cpp +++ b/nebula_ros/src/robosense/decoder_wrapper.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/robosense/decoder_wrapper.hpp" namespace nebula @@ -5,11 +7,11 @@ namespace nebula namespace ros { -using namespace std::chrono_literals; +using namespace std::chrono_literals; // NOLINT(build/namespaces) RobosenseDecoderWrapper::RobosenseDecoderWrapper( rclcpp::Node * const parent_node, - const std::shared_ptr& hw_interface, + const std::shared_ptr & hw_interface, const std::shared_ptr & config, const std::shared_ptr & calibration) : status_(nebula::Status::NOT_INITIALIZED), @@ -27,38 +29,43 @@ RobosenseDecoderWrapper::RobosenseDecoderWrapper( RCLCPP_INFO(logger_, ". Driver "); // Publish packets only if HW interface is connected - if (hw_interface_) - { + if (hw_interface_) { current_scan_msg_ = std::make_unique(); - packets_pub_ = - parent_node->create_publisher("robosense_packets", rclcpp::SensorDataQoS()); + packets_pub_ = parent_node->create_publisher( + "robosense_packets", rclcpp::SensorDataQoS()); } auto qos_profile = rmw_qos_profile_sensor_data; - auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + auto pointcloud_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - nebula_points_pub_ = parent_node->create_publisher("robosense_points", pointcloud_qos); - aw_points_base_pub_ = parent_node->create_publisher("aw_points", pointcloud_qos); - aw_points_ex_pub_ = parent_node->create_publisher("aw_points_ex", pointcloud_qos); + nebula_points_pub_ = parent_node->create_publisher( + "robosense_points", pointcloud_qos); + aw_points_base_pub_ = + parent_node->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = + parent_node->create_publisher("aw_points_ex", pointcloud_qos); RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); - cloud_watchdog_ = std::make_shared(*parent_node, 100'000us, [this, parent_node](bool ok) { - if (ok) - return; - RCLCPP_WARN_THROTTLE(logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline"); - }); + cloud_watchdog_ = + std::make_shared(*parent_node, 100'000us, [this, parent_node](bool ok) { + if (ok) return; + RCLCPP_WARN_THROTTLE( + logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline"); + }); RCLCPP_INFO(logger_, "Initialized decoder wrapper."); } -void RobosenseDecoderWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { +void RobosenseDecoderWrapper::ProcessCloudPacket( + std::unique_ptr packet_msg) +{ // Accumulate packets for recording only if someone is subscribed to the topic (for performance) - if (hw_interface_ && - (packets_pub_->get_subscription_count() > 0 || packets_pub_->get_intra_process_subscription_count() > 0)) - { - if (current_scan_msg_->packets.size() == 0) - { + if ( + hw_interface_ && (packets_pub_->get_subscription_count() > 0 || + packets_pub_->get_intra_process_subscription_count() > 0)) { + if (current_scan_msg_->packets.size() == 0) { current_scan_msg_->header.stamp = packet_msg->stamp; } @@ -70,56 +77,61 @@ void RobosenseDecoderWrapper::ProcessCloudPacket(std::unique_ptr pointcloud_ts{}; nebula::drivers::NebulaPointCloudPtr pointcloud = nullptr; - + { std::lock_guard lock(mtx_driver_ptr_); pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); pointcloud = std::get<0>(pointcloud_ts); } - if (pointcloud == nullptr) - { + if (pointcloud == nullptr) { return; - }; + } cloud_watchdog_->update(); // Publish scan message only if it has been written to - if (current_scan_msg_ && !current_scan_msg_->packets.empty()) - { + if (current_scan_msg_ && !current_scan_msg_->packets.empty()) { packets_pub_->publish(std::move(current_scan_msg_)); current_scan_msg_ = std::make_unique(); } - if (nebula_points_pub_->get_subscription_count() > 0 || - nebula_points_pub_->get_intra_process_subscription_count() > 0) - { + if ( + nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_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(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); } - if (aw_points_base_pub_->get_subscription_count() > 0 || - aw_points_base_pub_->get_intra_process_subscription_count() > 0) - { - const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + if ( + aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_cloud_xyzi = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); } - if (aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) - { - const auto autoware_ex_cloud = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + if ( + aw_points_ex_pub_->get_subscription_count() > 0 || + aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( + pointcloud, std::get<1>(pointcloud_ts)); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); } } -void RobosenseDecoderWrapper::OnConfigChange(const std::shared_ptr& new_config) { +void RobosenseDecoderWrapper::OnConfigChange( + const std::shared_ptr & new_config) +{ std::lock_guard lock(mtx_driver_ptr_); auto new_driver = std::make_shared(new_config, calibration_cfg_ptr_); driver_ptr_ = new_driver; @@ -128,7 +140,8 @@ void RobosenseDecoderWrapper::OnConfigChange(const std::shared_ptr namespace nebula @@ -83,13 +87,15 @@ void RobosenseHwMonitorWrapper::DiagnosticsCallback( current_sensor_info_ = diag_info; current_info_time_ = current_time; } - + if (!diagnostics_updater_) { InitializeRobosenseDiagnostics(); } } -void RobosenseHwMonitorWrapper::OnConfigChange(const std::shared_ptr & new_config) { +void RobosenseHwMonitorWrapper::OnConfigChange( + const std::shared_ptr & new_config) +{ std::lock_guard lock(mtx_config_); if (!new_config) { @@ -103,6 +109,5 @@ void RobosenseHwMonitorWrapper::OnConfigChange(const std::shared_ptrProcessCloudPacket(std::move(packet_queue_.pop())); + decoder_wrapper_->ProcessCloudPacket(packet_queue_.pop()); } }); @@ -72,8 +78,7 @@ nebula::Status RobosenseRosWrapper::DeclareAndGetSensorConfigParams() config.return_mode = drivers::ReturnModeFromStringRobosense(_return_mode); config.host_ip = declare_parameter("host_ip", param_read_only()); - config.sensor_ip = - declare_parameter("sensor_ip", param_read_only()); + config.sensor_ip = declare_parameter("sensor_ip", param_read_only()); config.data_port = declare_parameter("data_port", param_read_only()); config.gnss_port = declare_parameter("gnss_port", param_read_only()); config.frame_id = declare_parameter("frame_id", param_read_write()); @@ -219,7 +224,7 @@ Status RobosenseRosWrapper::StreamStart() rcl_interfaces::msg::SetParametersResult RobosenseRosWrapper::OnParameterChange( const std::vector & p) { - using namespace rcl_interfaces::msg; + using rcl_interfaces::msg::SetParametersResult; if (p.empty()) { return rcl_interfaces::build().successful(true).reason(""); diff --git a/nebula_ros/src/velodyne/decoder_wrapper.cpp b/nebula_ros/src/velodyne/decoder_wrapper.cpp index e2fbeb721..f55d7f28e 100644 --- a/nebula_ros/src/velodyne/decoder_wrapper.cpp +++ b/nebula_ros/src/velodyne/decoder_wrapper.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/velodyne/decoder_wrapper.hpp" namespace nebula diff --git a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp index 159f31380..dafbf0d7e 100644 --- a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/velodyne/hw_interface_wrapper.hpp" namespace nebula diff --git a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp index 945a6d650..d8aae2bc6 100644 --- a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/velodyne/hw_monitor_wrapper.hpp" namespace nebula diff --git a/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp index a8e8cf5d6..49c93b43a 100644 --- a/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp +++ b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp @@ -1,5 +1,9 @@ +// Copyright 2024 TIER IV, Inc. + #include "nebula_ros/velodyne/velodyne_ros_wrapper.hpp" +#pragma clang diagnostic ignored "-Wbitwise-instead-of-logical" + namespace nebula { namespace ros @@ -38,7 +42,7 @@ VelodyneRosWrapper::VelodyneRosWrapper(const rclcpp::NodeOptions & options) decoder_thread_ = std::thread([this]() { while (true) { - decoder_wrapper_->ProcessCloudPacket(std::move(packet_queue_.pop())); + decoder_wrapper_->ProcessCloudPacket(packet_queue_.pop()); } }); @@ -72,8 +76,7 @@ nebula::Status VelodyneRosWrapper::DeclareAndGetSensorConfigParams() config.return_mode = drivers::ReturnModeFromString(_return_mode); config.host_ip = declare_parameter("host_ip", param_read_only()); - config.sensor_ip = - declare_parameter("sensor_ip", param_read_only()); + config.sensor_ip = declare_parameter("sensor_ip", param_read_only()); config.data_port = declare_parameter("data_port", param_read_only()); config.gnss_port = declare_parameter("gnss_port", param_read_only()); config.frame_id = declare_parameter("frame_id", param_read_write()); diff --git a/nebula_tests/continental/continental_ros_decoder_test_ars548.hpp b/nebula_tests/continental/continental_ros_decoder_test_ars548.hpp index 64e53c04b..b509de9aa 100644 --- a/nebula_tests/continental/continental_ros_decoder_test_ars548.hpp +++ b/nebula_tests/continental/continental_ros_decoder_test_ars548.hpp @@ -18,7 +18,6 @@ #include #include #include -#include #include #include @@ -27,6 +26,7 @@ #include #include +#include #include #include diff --git a/nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml b/nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml index 536456380..54e2fec22 100644 --- a/nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml +++ b/nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml @@ -23,4 +23,4 @@ rosbag2_bagfile_information: nanoseconds_since_epoch: 1713492677464078412 duration: nanoseconds: 376987098 - message_count: 5 \ No newline at end of file + message_count: 5 diff --git a/nebula_tests/hesai/hesai_common.hpp b/nebula_tests/hesai/hesai_common.hpp index 84c7fbbdd..d01a0edf8 100644 --- a/nebula_tests/hesai/hesai_common.hpp +++ b/nebula_tests/hesai/hesai_common.hpp @@ -1,19 +1,28 @@ -#pragma once +// Copyright 2024 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_common/hesai/hesai_common.hpp" -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" -#include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp" -#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" +#pragma once #include +#include +#include +#include +#include +#include #include -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" - #include -#include #include @@ -22,7 +31,8 @@ namespace nebula namespace test { -void checkPCDs(nebula::drivers::NebulaPointCloudPtr pc, pcl::PointCloud::Ptr pc_ref) +inline void checkPCDs( + nebula::drivers::NebulaPointCloudPtr pc, pcl::PointCloud::Ptr pc_ref) { EXPECT_EQ(pc->points.size(), pc_ref->points.size()); auto bound = std::min(pc->points.size(), pc_ref->points.size()); @@ -41,7 +51,8 @@ void checkPCDs(nebula::drivers::NebulaPointCloudPtr pc, pcl::PointCloudpoints.size(), pp2->points.size()); for (uint32_t i = 0; i < pp1->points.size(); i++) { @@ -58,7 +69,7 @@ void checkPCDs(nebula::drivers::NebulaPointCloudPtr pp1, nebula::drivers::Nebula } } -void printPCD(nebula::drivers::NebulaPointCloudPtr pp) +inline void printPCD(nebula::drivers::NebulaPointCloudPtr pp) { for (auto p : pp->points) { std::cout << "(" << p.x << ", " << p.y << "," << p.z << "): " << p.intensity << ", " diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.cpp b/nebula_tests/hesai/hesai_ros_decoder_test.cpp index 289e8a711..7968f5ce9 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "hesai_ros_decoder_test.hpp" #include "rclcpp/serialization.hpp" diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.hpp b/nebula_tests/hesai/hesai_ros_decoder_test.hpp index a10a9e5f4..775fcf8c0 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.hpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.hpp @@ -1,6 +1,19 @@ +// Copyright 2024 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 "hesai_common.hpp" #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" @@ -9,9 +22,6 @@ #include #include -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" - #include #include diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.yaml b/nebula_tests/hesai/hesai_ros_decoder_test.yaml index ea4b66a98..23ff28ea1 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.yaml +++ b/nebula_tests/hesai/hesai_ros_decoder_test.yaml @@ -1,12 +1,12 @@ /**: ros__parameters: - sensor_model: "PandarAT128" # See readme for supported models - sensor_ip: "192.168.1.201" # Lidar Sensor IP - host_ip: "255.255.255.255" # Broadcast IP from Sensor - frame_id: "hesai" + sensor_model: PandarAT128 # See readme for supported models + sensor_ip: 192.168.1.201 # Lidar Sensor IP + host_ip: 255.255.255.255 # Broadcast IP from Sensor + frame_id: hesai data_port: 2368 # LiDAR Data Port gnss_port: 10110 # LiDAR GNSS Port - return_mode: "LastStrongest" # See readme for supported return modes + return_mode: LastStrongest # See readme for supported return modes scan_phase: 0.0 # Angle where scans begin (degrees, [0.,360.] packet_mtu_size: 1500 # Packet MTU size rotation_speed: 200 # Motor RPM, the sensor's internal spin rate. @@ -15,9 +15,9 @@ min_range: 0.3 # Minimum range. max_range: 300. # Maximum range. diag_span: 1000 # milliseconds - calibration_file: "./install/nebula_decoders/share/nebula_decoders/calibration/hesai/PandarAT128.csv" - correction_file: "./install/nebula_decoders/share/nebula_decoders/calibration/hesai/PandarAT128.dat" + calibration_file: ./install/nebula_decoders/share/nebula_decoders/calibration/hesai/PandarAT128.csv + correction_file: ./install/nebula_decoders/share/nebula_decoders/calibration/hesai/PandarAT128.dat - storage_id: "sqlite3" - format: "cdr" - target_topic: "/pandar_packets" + storage_id: sqlite3 + format: cdr + target_topic: /pandar_packets diff --git a/nebula_tests/hesai/hesai_ros_decoder_test_launch.py b/nebula_tests/hesai/hesai_ros_decoder_test_launch.py index f4286b6c2..96b01cd3a 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test_launch.py +++ b/nebula_tests/hesai/hesai_ros_decoder_test_launch.py @@ -10,16 +10,22 @@ @pytest.mark.rostest def generate_test_description(): test_node = launch_ros.actions.Node( - package='nebula_tests', - executable='hesai_ros_decoder_test_node_standalone', - parameters=['test/hesai_ros_decoder_test.yaml'], + package="nebula_tests", + executable="hesai_ros_decoder_test_node_standalone", + parameters=["test/hesai_ros_decoder_test.yaml"], ) - return launch.LaunchDescription([ - # other fixture actions - test_node, - launch_testing.util.KeepAliveProc(), - launch_testing.actions.ReadyToTest() - ]), locals() + return ( + launch.LaunchDescription( + [ + # other fixture actions + test_node, + launch_testing.util.KeepAliveProc(), + launch_testing.actions.ReadyToTest(), + ] + ), + locals(), + ) + @launch_testing.post_shutdown_test() class TestOutcome(unittest.TestCase): diff --git a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp index 7f80f6f48..c66b05267 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "hesai_ros_decoder_test_main.hpp" #include "hesai_common.hpp" @@ -9,7 +11,6 @@ #include #include -#include #include #include #include diff --git a/nebula_tests/hesai/hesai_ros_decoder_test_main.hpp b/nebula_tests/hesai/hesai_ros_decoder_test_main.hpp index dca0f05d7..e4c610954 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test_main.hpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test_main.hpp @@ -1,10 +1,27 @@ +// Copyright 2024 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 "hesai_ros_decoder_test.hpp" -#include #include +#include + +#include + namespace nebula { namespace test diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp16.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp16.cpp index 77496bcd2..f17abef87 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp16.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp16.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "velodyne_ros_decoder_test_vlp16.hpp" #include diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp index eda4969c6..e07f1212b 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "velodyne_ros_decoder_test_vlp32.hpp" #include diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vls128.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vls128.cpp index 94502b363..0fd0b77e2 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vls128.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vls128.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "velodyne_ros_decoder_test_vls128.hpp" #include diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp index 5f41b210d..b4bb04236 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "velodyne_ros_decoder_test_vlp16.hpp" #include "rclcpp/serialization.hpp" diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp index 7beb47807..47885ab2d 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_VelodyneRosDecoderTestVlp16_H #define NEBULA_VelodyneRosDecoderTestVlp16_H diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp index 494a7a451..bfa6a490e 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp @@ -1,19 +1,19 @@ +// Copyright 2024 TIER IV, Inc. + #include "velodyne_ros_decoder_test_vlp32.hpp" #include "rclcpp/serialization.hpp" #include "rclcpp/serialized_message.hpp" #include "rcpputils/filesystem_helper.hpp" -#include "rcutils/time.h" #include "rosbag2_cpp/reader.hpp" #include "rosbag2_cpp/readers/sequential_reader.hpp" -#include "rosbag2_cpp/writer.hpp" -#include "rosbag2_cpp/writers/sequential_writer.hpp" #include "rosbag2_storage/storage_options.hpp" #include #include #include +#include namespace nebula { diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp index 7beb47807..47885ab2d 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_VelodyneRosDecoderTestVlp16_H #define NEBULA_VelodyneRosDecoderTestVlp16_H diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp index 3794ff4fb..c6980daef 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp @@ -1,3 +1,5 @@ +// Copyright 2024 TIER IV, Inc. + #include "velodyne_ros_decoder_test_vls128.hpp" #include diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp index 7397ff029..8787e8b0d 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp @@ -1,3 +1,17 @@ +// Copyright 2024 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_VelodyneRosDecoderTestVls128_H #define NEBULA_VelodyneRosDecoderTestVls128_H diff --git a/scripts/hesai_config.py b/scripts/hesai_config.py index fc45b7a65..b7f586ee9 100644 --- a/scripts/hesai_config.py +++ b/scripts/hesai_config.py @@ -1,14 +1,16 @@ from __future__ import annotations +from argparse import ArgumentParser +from dataclasses import dataclass +from ipaddress import IPv4Address +from ipaddress import IPv4Network +from ipaddress import ip_interface import socket import struct import sys -from argparse import ArgumentParser -from dataclasses import dataclass -from ipaddress import IPv4Address, IPv4Network, ip_interface from typing import Any -from rich import print +from rich import print # noqa: A004 from rich.syntax import Syntax from rich.table import Table @@ -19,15 +21,15 @@ SET_CONTROL_PORT_COMMAND = 0x21 -def unpack(format: str, buffer: bytes) -> Any: - return struct.unpack(format, buffer)[0] +def unpack(struct_fields: str, buffer: bytes) -> Any: + return struct.unpack(struct_fields, buffer)[0] class PtcCommandBase: def parse(self) -> dict[str, str]: raise NotImplementedError() - def print(self, title: str) -> None: + def print(self, title: str) -> None: # noqa: A003 table = Table("Parameter", "Value", title=title, highlight=True, min_width=45) for key, value in self.parse().items(): table.add_row(key, str(value)) @@ -93,13 +95,9 @@ def parse(self) -> dict[str, str]: "stop_angle": unpack("!H", self.stop_angle), "clock_source": "PTP" if unpack("!B", self.clock_source) else "Unknown", "udp_seq": "ON" if unpack("!B", self.udp_seq) else "OFF", - "trigger_method": "Time-based" - if unpack("!B", self.trigger_method) - else "Angle-based", + "trigger_method": "Time-based" if unpack("!B", self.trigger_method) else "Angle-based", "return_mode": RETURN_MODE_MAP[unpack("!B", self.return_mode)], - "standby_mode": "Standby" - if unpack("!B", self.standby_mode) - else "In operation", + "standby_mode": "Standby" if unpack("!B", self.standby_mode) else "In operation", "motor_status": unpack("!B", self.motor_status), "vlan_flag": unpack("!B", self.vlan_flag), "vlan_id": unpack("!H", self.vlan_id), @@ -168,21 +166,17 @@ class PtcCommandGetPtpConfig(PtcCommandBase): def parse(self) -> dict[str, str]: return { "status": "Enabled" if unpack("!B", self.status) else "Disabled", - "profile": "802.1AS (AutoSAR)" - if unpack("!B", self.profile) == 3 - else "Unknown", + "profile": "802.1AS (AutoSAR)" if unpack("!B", self.profile) == 3 else "Unknown", "domain": unpack("!B", self.domain), "network": "L2" if unpack("!B", self.network) == 1 else "Unknown", "tsn_switch": "TSN" if unpack("!B", self.tsn_switch) else "Non-TSN", } -def compose_packet( - command: str, payload_length: int = 0, payload: bytes = b"" -) -> bytes: - format = ">B B B B I {}s".format(payload_length) +def compose_packet(command: str, payload_length: int = 0, payload: bytes = b"") -> bytes: + struct_fields = ">B B B B I {}s".format(payload_length) - return struct.pack(format, 0x47, 0x74, command, 0x00, payload_length, payload) + return struct.pack(struct_fields, 0x47, 0x74, command, 0x00, payload_length, payload) def get_config_info(sock: socket.socket): @@ -192,9 +186,7 @@ def get_config_info(sock: socket.socket): payload_length = sum(response[4:]) payload = sock.recv(payload_length) - fields = struct.unpack( - "4s 4s 4s 4s 2s 2s 2s s 2s 2s 2s s s s s s s s 2s s s s", payload[:41] - ) + fields = struct.unpack("4s 4s 4s 4s 2s 2s 2s s 2s 2s 2s s s s s s s s 2s s s s", payload[:41]) return PtcCommandGetConfigInfo(*fields) @@ -339,8 +331,7 @@ class NameSpace: if args.data_port is not None: if args.data_port < 0 or 65535 < args.data_port: raise ValueError( - f"Invalid data port {args.data_port}. " - "It must be in the range of 0 to 65535." + f"Invalid data port {args.data_port}. " "It must be in the range of 0 to 65535." ) sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) @@ -369,14 +360,10 @@ class NameSpace: current_mask = parsed_config_info["mask"] destination_ip = ( - current_destination_ip - if args.destination_ip is None - else args.destination_ip + current_destination_ip if args.destination_ip is None else args.destination_ip ) data_port = current_data_port if args.data_port is None else args.data_port - new_sensor_ip = ( - args.sensor_ip if args.new_sensor_ip is None else args.new_sensor_ip - ) + new_sensor_ip = args.sensor_ip if args.new_sensor_ip is None else args.new_sensor_ip mask = current_mask if args.mask is None else args.mask # Set Destination IP (0x20) @@ -397,9 +384,7 @@ class NameSpace: payload += struct.pack("!H", data_port) payload += struct.pack("!H", 2369) - sock.sendall( - compose_packet(SET_DESTINATION_IP_COMMAND, len(payload), payload) - ) + sock.sendall(compose_packet(SET_DESTINATION_IP_COMMAND, len(payload), payload)) print("Done") @@ -418,9 +403,7 @@ class NameSpace: payload += struct.pack("!B", 0) payload += struct.pack("!H", 0) - sock.sendall( - compose_packet(SET_CONTROL_PORT_COMMAND, len(payload), payload) - ) + sock.sendall(compose_packet(SET_CONTROL_PORT_COMMAND, len(payload), payload)) print("Done") @@ -428,9 +411,7 @@ class NameSpace: print( f"Make sure the new sensor IP is successfully set to {new_sensor_ip}/{mask} by the following command" ) - print( - Syntax(f"python3 {sys.argv[0]} --sensor-ip {new_sensor_ip}", "console") - ) + print(Syntax(f"python3 {sys.argv[0]} --sensor-ip {new_sensor_ip}", "console")) if ( args.destination_ip is not None @@ -445,9 +426,7 @@ class NameSpace: if new_sensor_ip != args.sensor_ip: table.add_row("sensor_ip", str(args.sensor_ip), str(new_sensor_ip)) if destination_ip != current_destination_ip: - table.add_row( - "destination_ip", str(current_destination_ip), str(destination_ip) - ) + table.add_row("destination_ip", str(current_destination_ip), str(destination_ip)) if data_port != current_data_port: table.add_row("data_port", str(current_data_port), str(data_port)) if mask != current_mask: diff --git a/scripts/profiling_runner.bash b/scripts/profiling_runner.bash index 029faf647..107c15ff6 100755 --- a/scripts/profiling_runner.bash +++ b/scripts/profiling_runner.bash @@ -2,10 +2,9 @@ # Configuration -print_usage () { +print_usage() { # Print optionally passed error message - if [ -n "$1" ] - then + if [ -n "$1" ]; then echo "$1" fi echo "Usage: $0 [-t|--timeout ] [-m|--sensor-model ] [-n|--n-runs ] [-f|--maxfreq ] [-c|--taskset-cores ] [-b|--rosbag-path ]" @@ -18,15 +17,14 @@ print_usage () { } # Default parameters -runtime=20 # seconds (rosbag runtime is timeout-3s for startup) -n_runs=3 # number of runs per test -maxfreq=2300000 # 2.3 GHz -n_cores=$(nproc --all) # number of cores of the CPU -taskset_cores=0-$(( $n_cores - 1 )) # cores to run Nebula on -nebula_dir=$( cd -- "$( dirname -- "${BASH_SOURCE[0]}" )/.." &> /dev/null && pwd ) - -if [ $# -lt 1 ] -then +runtime=20 # seconds (rosbag runtime is timeout-3s for startup) +n_runs=3 # number of runs per test +maxfreq=2300000 # 2.3 GHz +n_cores=$(nproc --all) # number of cores of the CPU +taskset_cores=0-$((n_cores - 1)) # cores to run Nebula on +nebula_dir=$(cd -- "$(dirname -- "${BASH_SOURCE[0]}")/.." &>/dev/null && pwd) + +if [ $# -lt 1 ]; then print_usage "No run name specified" exit 1 fi @@ -35,62 +33,59 @@ run_name=$1 shift #do the parsing -while [[ $# -gt 0 ]] -do +while [[ $# -gt 0 ]]; do key="$1" case $key in - -t|--runtime) - runtime="$2" - shift - shift - ;; - -m|--sensor-model) - sensor_model="$2" - shift - shift - ;; - -n|--n-runs) - n_runs="$2" - shift - shift - ;; - -f|--maxfreq) - maxfreq="$2" - shift - shift - ;; - -c|--taskset-cores) - taskset_cores="$2" - shift - shift - ;; - -d|--nebula-dir) - nebula_dir="$2" - shift - shift - ;; - -b|--rosbag-path) - rosbag_path="$2" - shift - shift - ;; - *) - print_usage "Unknown option $1" - exit 1 - ;; + -t | --runtime) + runtime="$2" + shift + shift + ;; + -m | --sensor-model) + sensor_model="$2" + shift + shift + ;; + -n | --n-runs) + n_runs="$2" + shift + shift + ;; + -f | --maxfreq) + maxfreq="$2" + shift + shift + ;; + -c | --taskset-cores) + taskset_cores="$2" + shift + shift + ;; + -d | --nebula-dir) + nebula_dir="$2" + shift + shift + ;; + -b | --rosbag-path) + rosbag_path="$2" + shift + shift + ;; + *) + print_usage "Unknown option $1" + exit 1 + ;; esac done # Enf of configuration -if [ -z "$rosbag_path" ] -then +if [ -z "$rosbag_path" ]; then print_usage "No --rosbag-path specified" exit 1 fi -if [ -z "$sensor_model" ] -then +if [ -z "$sensor_model" ]; then print_usage "No --sensor-model specified" exit 1 fi @@ -100,13 +95,12 @@ output_dir="$nebula_dir/profiling_output" mkdir -p "$output_dir" echo "Outputting to '$output_dir/$run_name-[1-$n_runs].log'" -cd "$nebula_dir" +cd "$nebula_dir" || exit -lockfreq () { - for (( i=0; i<$n_cores; i++ )) - do - echo userspace | sudo tee /sys/devices/system/cpu/cpufreq/policy$i/scaling_governor > /dev/null - echo $maxfreq | sudo tee /sys/devices/system/cpu/cpufreq/policy$i/scaling_setspeed > /dev/null +lockfreq() { + for ((i = 0; i < n_cores; i++)); do + echo userspace | sudo tee /sys/devices/system/cpu/cpufreq/policy$i/scaling_governor >/dev/null + echo "$maxfreq" | sudo tee /sys/devices/system/cpu/cpufreq/policy$i/scaling_setspeed >/dev/null echo -n "CPU $i's frequency is: " sudo cat /sys/devices/system/cpu/cpu$i/cpufreq/cpuinfo_cur_freq done @@ -114,10 +108,9 @@ lockfreq () { sudo sh -c "echo 0 > /sys/devices/system/cpu/cpufreq/boost" } -unlockfreq () { - for (( i=0; i<$n_cores; i++ )) - do - echo schedutil | sudo tee /sys/devices/system/cpu/cpufreq/policy$i/scaling_governor > /dev/null +unlockfreq() { + for ((i = 0; i < n_cores; i++)); do + echo schedutil | sudo tee /sys/devices/system/cpu/cpufreq/policy$i/scaling_governor >/dev/null echo -n "CPU $i's frequency is: " sudo cat /sys/devices/system/cpu/cpu$i/cpufreq/cpuinfo_cur_freq done @@ -129,6 +122,7 @@ echo "Setting up for compiling" unlockfreq colcon build --symlink-install --packages-up-to nebula_ros --cmake-args -DCMAKE_BUILD_TYPE=Release || exit 1 +# shellcheck disable=SC1091 source "$nebula_dir/install/setup.bash" ros2 daemon stop @@ -137,15 +131,14 @@ ros2 daemon start echo "Setting up for test run" lockfreq -for (( i=1; i<=$n_runs; i++ )) -do +for ((i = 1; i <= n_runs; i++)); do echo "Running iteration $i of $n_runs" # set the log level to debug for all ros 2 nodes - timeout -s INT $runtime taskset -c "$taskset_cores" ros2 launch nebula_ros nebula_launch.py "sensor_model:=$sensor_model" launch_hw:=false debug_logging:=true > "$output_dir/$run_name-$i.log" 2>&1 & - (sleep 3 && timeout -s KILL $(( $runtime - 3 )) nohup ros2 bag play -l "$rosbag_path") > /dev/null & + timeout -s INT "$runtime" taskset -c "$taskset_cores" ros2 launch nebula_ros nebula_launch.py "sensor_model:=$sensor_model" launch_hw:=false debug_logging:=true >"$output_dir/$run_name-$i.log" 2>&1 & + (sleep 3 && timeout -s KILL $((runtime - 3)) nohup ros2 bag play -l "$rosbag_path") >/dev/null & wait done echo "Unlocking frequency" -unlockfreq \ No newline at end of file +unlockfreq