diff --git a/CHANGELOG.rst b/CHANGELOG.rst index d5fdcdb3..22cc22ef 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,39 @@ Changelog ========= +[0.16.1] +========= + +* [BUGFIX] Add ``--coord-frame`` (``SENSOR|BODY|WORLD``) to ``ouster-cli source ... filter`` for XYZ filtering. ``WORLD`` now applies ``dewarp(points, scan.pose)`` before thresholding, ``BODY`` remains the default for backward compatibility, and ``SENSOR`` uses XYZ without extrinsics. +* [BUGFIX] Fix crash in ``LidarScan.__str__`` when scans contain non-pixel fields (IMU, GNSS, ZONE, or CHAR fields). The ``to_string()`` function now properly handles these field types, with special formatting for CHAR fields to display NMEA sentences. +* [BUGFIX] Avoid divide-by-zero in IMU visualization when IMU magnitudes are zero. +* [BUGFIX] Fix AOI picker showing normalized values for unknown fields in the viz. +* [BREAKING] Renamed ``-F`` flag to ``-f`` in ``ouster-cli source`` command (short for ``--filter`` flag), which drops scans with missing data. +* [BUGFIX] PLY maker minor change (e.g. support for no valid key field, ``--field NONE``). +* [BUGFIX] Use stderr instead of stdout for logging in ouster-cli. +* [BUGFIX] Fix ``filter``, ``clip``, and ``mask`` bugs: correct filter_xyz semantics (points inside bounds zeroed), restrict operations to PIXEL_FIELD only to avoid crashes with IMU/GNSS fields, and use RANGE2 coordinates for second-return fields. +* [BUGFIX] Handle unsupported ChanFieldTypes when reading OSF files: skip unsupported fields with a warning instead of crashing (forward compatibility with newer OSF files). +* Add ``--legacy`` flag for OSF export (PNG compression + drop CHAR/ZONE_STATE for SDK 0.12–0.15 compatibility), separate from ``--png`` (PNG compression only). +* [BUGFIX] Update TUM format in trajectory saving as per official specification. +* [BUGFIX] Fix viz GL buffer cleanup leaks: add missing ``glDeleteBuffers()`` for GLCuboid, GLRings, and GLImage to prevent GPU memory growth on repeated create/destroy. +* [BUGFIX] Fix ValueError in viz when resizing before scans received. +* [BUGFIX] Fix crash when saving a GIF when frame duration is negative (e.g. source has looped); fix viz deadlock when saving image recording. +* [BUGFIX] Fix improper handling of sensors with lidar data disabled. +* [BUGFIX] SLAM crashes when at least one sensor doesn't have imu data in a multi-sensor setup with the Synchronous IMU feature enabled. +* [BUGFIX] SLAM uses un-corrected timestamps when using the the inertial integration deskew method with multi-sensor unsynchronized setups. +* Pose Optimizer: constraint ID counter moved to constraint base class; constraint IDs are now logged when adding/processing constraints, and reassign constraint id when conflict instead of throwing. +* [BUGFIX] Remove the skipping on single scans in SLAM and localize pipelines for multi-sensor datasets. +* [BUGFIX] PNGs from the viz now embed the Display P3 profile so their colors match the viz window. +* Add ``--http-addr`` option to ``sensor_replay`` plugin (e.g. for use with Ouster Detect). +* Update README with community forum and support info. +* Normalize license files for GitHub detection. + +Important Notes +--------------- + +* This will be the last release that supports macOS 11.x, 12.x and 13.x. + + [0.16.0] ========= @@ -10,7 +43,7 @@ Changelog * Clear AOI selection in the viz when right click is pressed and there is a preexisting selection. * Extend AOI selection to show 3 axis fields properly when right click in viz images. * Add support for low bandwidth dual returns lidar profile (PROFILE_RNG15_RFL8_NIR8_DUAL). -* [BREAKING] renamed ``data_format::packets_per_frame()`` to ``lidar_packets_per_frame()`` +* [BREAKING] Renamed ``data_format::packets_per_frame()`` to ``lidar_packets_per_frame()`` * Add support for saving and reading new ZPNG based OSF files which are several times faster and have better compression ratios. * [BREAKING] Make ZPNG the default format for saved OSF files. This format cannot be opened by older SDK versions. * [BREAKING] Change ``ouster-cli source dump`` JSON output to return the OSF version as a semver-style string instead of an integer. @@ -85,7 +118,7 @@ Changelog * Changed all core sdk enums to enum classes and removed the prefixes from enum values. The C++ enums naming is now consistent with the Python enums naming. - e.g. ``OPERATING_NORMAL`` is now ``OperatingMode::UNSPECIFIED`` - The older enum identiers are still available for use but are deprecated. -* Utilize imu data when compensating for lidar data distortion during motion in SLAM and Localization. +* Utilize imu data when compensating for lidar data distortion during motion in SLAM and Localization. * Add Zone Monitor: - Add support for reading and writing Zone Monitor configurations for sensors running firmware 3.2 and above. - Add zone state data to LidarScans when Zone Monitor is enabled on the sensor. diff --git a/CMakeLists.txt b/CMakeLists.txt index 13772c97..4c6e3ac2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -66,7 +66,7 @@ if(CMAKE_PROJECT_NAME STREQUAL PROJECT_NAME) if(MSVC) add_compile_options(/W2 /bigobj /Zf) - add_compile_definitions(NOMINMAX _USE_MATH_DEFINES WIN32_LEAN_AND_MEAN) + add_compile_definitions(NOMINMAX _USE_MATH_DEFINES WIN32_LEAN_AND_MEAN _ENABLE_EXTENDED_ALIGNED_STORAGE) else() add_compile_options(-Wall -Wextra) endif() diff --git a/VERSION b/VERSION index 85b76682..68b16227 100644 --- a/VERSION +++ b/VERSION @@ -1,2 +1,2 @@ -__version__ = '0.16.0' -__cpp_version__ = '0.16.0' +__version__ = '0.16.1' +__cpp_version__ = '0.16.1' diff --git a/docs/cli/filter-sessions.rst b/docs/cli/filter-sessions.rst index c3a0780b..0d54d66b 100644 --- a/docs/cli/filter-sessions.rst +++ b/docs/cli/filter-sessions.rst @@ -30,6 +30,8 @@ Where: - ``--invalid-value``: The value to replace the pixels that match the predicate. Default is zero. - ``--filtered-fields``: A comma-separated list of fields to apply the filter to. If not specified, the filter will be applied to all fields of the scan. + - ``--coord-frame``: Coordinate frame for XYZ filtering only. Options are ``SENSOR`` (no extrinsics), + ``BODY`` (extrinsics, default), and ``WORLD`` (dewarp with poses). Example Usage ------------- @@ -55,7 +57,7 @@ command predicate, we can highlight points in the low cloud with higher reflecti :align: center :width: 800px - + 2) Filter based on cartesian coordinates: Another way to filter the point cloud is to use the cartesian coordinates of the points. For example, imagine we want to @@ -66,6 +68,13 @@ follows: ouster-cli source filter Z :-1m filter Z 1m: viz +If you need the XYZ filter in a different coordinate frame, use ``--coord-frame``. For example, dewarp +into WORLD coordinates before filtering: + +.. code:: bash + + ouster-cli source filter --coord-frame WORLD Z :-1m viz + After applying this filter the resulting point cloud will look like this: .. image:: /images/filter-example-z.png @@ -92,7 +101,7 @@ resulting point cloud will look like this: :align: center :width: 800px -This can be useful to mask out certain columns (``V``) or certain beams (``U``) of the LidarScan. +This can be useful to mask out certain columns (``V``) or certain beams (``U``) of the LidarScan. .. note:: diff --git a/docs/cli/pose-optimizer-sessions.rst b/docs/cli/pose-optimizer-sessions.rst index 8170ce4a..2a803781 100644 --- a/docs/cli/pose-optimizer-sessions.rst +++ b/docs/cli/pose-optimizer-sessions.rst @@ -43,8 +43,8 @@ Optional Config Parameters The constraint JSON file may also include the following optional parameters to fine-tune the optimization process: -- ``traj_rotation_weight`` (float): The weight for rotational constraints during trajectory optimization (default: ``10.0``). Higher values enforce stronger rotation consistency. -- ``traj_translation_weight`` (float): The weight for translational constraints during trajectory optimization (default: ``10.0``). Higher values enforce stronger position consistency. +- ``traj_rotation_weight`` (float): The weight for rotational constraints during trajectory optimization (default: ``10.0``). Higher values enforce stronger rotation consistency. Must be a float ``> 0``. +- ``traj_translation_weight`` (float): The weight for translational constraints during trajectory optimization (default: ``10.0``). Higher values enforce stronger position consistency. Must be a float ``> 0``. - ``max_num_iterations`` (int): The maximum number of iterations the solver will perform before terminating. - ``loss_function`` (str): The name of the robust loss function to use (e.g., ``HUBER_LOSS``, ``CAUCHY_LOSS``, ``SOFT_L_ONE_LOSS``, ``ARCTAN_LOSS``, ``TRIVIAL_LOSS``). - ``loss_scale`` (float): The scaling parameter for the chosen loss function. Higher values make the loss less sensitive to outliers. @@ -67,6 +67,7 @@ Several constraint types (explained later) support optional weight fields that e **rotation weight** - ``rotation_weight`` (single float) scales the quaternion axis-alignment residual for ``ABSOLUTE_POSE`` and ``POSE_TO_POSE`` constraints. Higher values enforce the orientation more strongly; set it to ``0`` to ignore the rotational component. +- Must be a single float value ``>= 0``. **Example (rotation_weight for ABSOLUTE_POSE):** @@ -78,7 +79,7 @@ This doubles the strength of the orientation penalty for that absolute pose. **translation_weight** -- Must be a list of three numbers. +- Must be a list of three float values ``>= 0``. - Applies to the positional components: **x**, **y**, and **z**. - Higher values signal stronger confidence in the position, and lower values give the optimizer more freedom to adjust. - Values are treated as relative weights for each axis. @@ -132,9 +133,10 @@ Defines an absolute pose measurement relative to the world coordinate frame. * Scales the quaternion axis-alignment residual applied to this pose. * Higher values increase sensitivity to rotational deviations; setting it to ``0`` disables the rotational penalty. + * Must be a float value ``>= 0``. - ``translation_weight``: - * A list of three values. + * A list of three float values ``>= 0``. * Corresponds to confidence in the **x**, **y**, and **z** position. See :ref:`weight-fields` for a detailed explanation. @@ -178,13 +180,13 @@ Fixes a single point from a scan to known coordinates in the trajectory map fram - ``type``: Must be exactly ``"ABSOLUTE_POINT"``. - ``timestamp``: Lidar frame timestamp (first valid column timestamp). - ``row``: Row index of the point (>= 0 && < scan.h). -- ``col``: Column index of the point (>= 0 && scan.w). +- ``col``: Column index of the point (>= 0 && < scan.w). - ``return_idx``: Which range return to use (1 or 2). - ``absolute_position``: Either an object with keys ``x``, ``y``, ``z`` or a list of three numbers ``[x, y, z]``. **Optional fields:** -- ``translation_weight``: List of three values describing confidence along ``x``, ``y``, and ``z``. +- ``translation_weight``: List of three float values ``>= 0`` describing confidence along ``x``, ``y``, and ``z``. .. note:: @@ -230,7 +232,7 @@ This constraint uses 2D image coordinates to select points from the lidar scans: **Optional field:** -- ``translation_weight``: A list of three numbers. +- ``translation_weight``: A list of three float values ``>= 0``. See :ref:`weight-fields` for a detailed explanation. @@ -297,8 +299,8 @@ The ``POSE_TO_POSE`` constraint defines a constraint between two poses in the tr * A dictionary (with ``rx``, ``ry``, ``rz``, ``x``, ``y``, ``z``), or * A 16-element list (4x4 matrix) * If omitted, transformation is auto-estimated using ICP matching. -- ``rotation_weight`` (float): Scales the quaternion axis-alignment residual for the relative pose. Setting it higher enforces the measured rotation more strongly; setting it to ``0`` disables the rotational penalty. -- ``translation_weight``: List of three values. +- ``rotation_weight`` (float): Scales the quaternion axis-alignment residual for the relative pose. Setting it higher enforces the measured rotation more strongly; setting it to ``0`` disables the rotational penalty. Must be a float value ``>= 0``. +- ``translation_weight``: List of three float values ``>= 0``. See :ref:`weight-fields` for a detailed explanation. @@ -457,11 +459,13 @@ addition to any constraints loaded from ``--config``). Remember the ``--config`` To record a dataset, connect your sensor to receive GPS data over a serial interface and set the udp_profile_imu to ACCEL32_GYRO32_NMEA. Detailed instructions for configuring the sensor to accept GPS input can be found in the `Sensor Time Sync`_ documentation: +Note: ``ACCEL32_GYRO32_NMEA`` is only available in firmware 3.2 or later. - ``--auto-constraints``: Automatically generate and add GPS absolute pose constraints. - ``--gps-constraints-every-m``: Approximate spacing in meters between constraints, computed from distance traveled using lidar scan poses. -- ``--gps-constraints-weights``: Translation weights ``WX,WY,WZ``. ``WX`` and ``WY`` +- ``--gps-constraints-weights``: Translation weights ``WX,WY,WZ`` (three + comma-separated numbers >= 0). - ``--no-initial-align``: In ``--viz`` mode, disables the initial alignment step using absolute constraints. diff --git a/ouster_client/include/ouster/impl/lidar_scan_impl.h b/ouster_client/include/ouster/impl/lidar_scan_impl.h index 2875f685..7fc7fbab 100644 --- a/ouster_client/include/ouster/impl/lidar_scan_impl.h +++ b/ouster_client/include/ouster/impl/lidar_scan_impl.h @@ -86,9 +86,11 @@ void visit_field_2d(FieldView& field, OP&& op, Args&&... args) { std::forward(args)...); break; case ChanFieldType::ZONE_STATE: - // IMPORTANT: ZoneState is not an Eigen scalar type, - // so many of the operations provide as the template parameter OP - // will cause compilation errors if we try to apply them. + case ChanFieldType::CHAR: + case ChanFieldType::VOID: + case ChanFieldType::UNREGISTERED: + // These types are not Eigen scalar types or are not supported, + // so we silently skip them rather than crash. break; default: throw std::invalid_argument("Invalid field for LidarScan"); @@ -140,9 +142,11 @@ void visit_field_2d(const FieldView& field, OP&& op, Args&&... args) { std::forward(args)...); break; case ChanFieldType::ZONE_STATE: - // IMPORTANT: ZoneState is not an Eigen scalar type, - // so many of the operations provide as the template parameter OP - // will cause compilation errors if we try to apply them. + case ChanFieldType::CHAR: + case ChanFieldType::VOID: + case ChanFieldType::UNREGISTERED: + // These types are not Eigen scalar types or are not supported, + // so we silently skip them rather than crash. break; default: throw std::invalid_argument("Invalid field for LidarScan"); diff --git a/ouster_client/include/ouster/impl/logging.h b/ouster_client/include/ouster/impl/logging.h index 2d1b528d..8c5c847e 100644 --- a/ouster_client/include/ouster/impl/logging.h +++ b/ouster_client/include/ouster/impl/logging.h @@ -37,6 +37,8 @@ class Logger { bool configure_stdout_sink(const std::string& log_level); + bool configure_stderr_sink(const std::string& log_level); + bool configure_file_sink(const std::string& log_level, const std::string& log_file_path, bool rotating, int max_size_in_bytes, int max_files); diff --git a/ouster_client/include/ouster/lidar_scan.h b/ouster_client/include/ouster/lidar_scan.h index 63bef0d4..6bbacbf2 100644 --- a/ouster_client/include/ouster/lidar_scan.h +++ b/ouster_client/include/ouster/lidar_scan.h @@ -552,7 +552,7 @@ class OUSTER_API_CLASS LidarScan { ConstArrayView1 zones() const; /** - * Return the first valid packet timestamp + * Return the first valid packet timestamp from any packet type. * * @return the first valid packet timestamp, 0 if none available */ @@ -560,13 +560,29 @@ class OUSTER_API_CLASS LidarScan { uint64_t get_first_valid_packet_timestamp() const; /** - * Return the last valid packet timestamp + * Return the last valid packet timestamp from any packet type. * * @return the last valid packet timestamp, 0 if none available */ OUSTER_API_FUNCTION uint64_t get_last_valid_packet_timestamp() const; + /** + * Return the first valid lidar packet timestamp + * + * @return the first valid lidar packet timestamp, 0 if none available + */ + OUSTER_API_FUNCTION + uint64_t get_first_valid_lidar_packet_timestamp() const; + + /** + * Return the last valid lidar packet timestamp + * + * @return the last valid lidar packet timestamp, 0 if none available + */ + OUSTER_API_FUNCTION + uint64_t get_last_valid_lidar_packet_timestamp() const; + /** * Return the first valid column timestamp * diff --git a/ouster_client/include/ouster/types.h b/ouster_client/include/ouster/types.h index 393ba51c..382be10d 100644 --- a/ouster_client/include/ouster/types.h +++ b/ouster_client/include/ouster/types.h @@ -312,6 +312,9 @@ enum class UDPProfileLidar { /** Single Return Zone Monitoring */ RNG19_RFL8_SIG16_NIR16_ZONE16, + /** Single Return Low Data Rate Window Status */ + RNG15_RFL8_WIN8, + /** disabled */ OFF = 100, diff --git a/ouster_client/src/cloud_io.cpp b/ouster_client/src/cloud_io.cpp index e04adace..e53a35df 100644 --- a/ouster_client/src/cloud_io.cpp +++ b/ouster_client/src/cloud_io.cpp @@ -82,7 +82,7 @@ PointCloudXYZf read_pointcloud(const std::string& filename) { input.seekg(0, std::ios::beg); // field sizes - std::map field_sizes{{"float", 4}}; + std::map field_sizes{{"float", 4}, {"uchar", 1}}; bool end_header_found = false; bool is_binary = true; int current_offset = 0; diff --git a/ouster_client/src/lidar_scan.cpp b/ouster_client/src/lidar_scan.cpp index 7658d80d..23799606 100644 --- a/ouster_client/src/lidar_scan.cpp +++ b/ouster_client/src/lidar_scan.cpp @@ -103,6 +103,13 @@ static const Table LB_FIELD_SLOTS{{ {ChanField::FLAGS, ChanFieldType::UINT8}, }}; +static const Table LB_WINDOW_FIELD_SLOTS{{ + {ChanField::RANGE, ChanFieldType::UINT32}, + {ChanField::REFLECTIVITY, ChanFieldType::UINT8}, + {ChanField::WINDOW, ChanFieldType::UINT8}, + {ChanField::FLAGS, ChanFieldType::UINT8}, +}}; + static const Table ZM_LB_FIELD_SLOTS{{ {ChanField::RANGE, ChanFieldType::UINT32}, {ChanField::REFLECTIVITY, ChanFieldType::UINT8}, @@ -158,6 +165,8 @@ Table default_scan_fields {SINGLE_FIELD_SLOTS.data(), SINGLE_FIELD_SLOTS.size()}}, {UDPProfileLidar::RNG15_RFL8_NIR8, {LB_FIELD_SLOTS.data(), LB_FIELD_SLOTS.size()}}, + {UDPProfileLidar::RNG15_RFL8_WIN8, + {LB_WINDOW_FIELD_SLOTS.data(), LB_WINDOW_FIELD_SLOTS.size()}}, {UDPProfileLidar::FIVE_WORD_PIXEL, {FIVE_WORD_SLOTS.data(), FIVE_WORD_SLOTS.size()}}, {UDPProfileLidar::FUSA_RNG15_RFL8_NIR8_DUAL, @@ -578,7 +587,47 @@ ConstArrayView1 LidarScan::zones() const { return it->second; } +// NOLINTNEXTLINE(google-build-using-namespace) +using namespace ouster::sdk::core::ChanField; uint64_t LidarScan::get_first_valid_packet_timestamp() const { + uint64_t time = get_first_valid_lidar_packet_timestamp(); + if (has_field(IMU_PACKET_TIMESTAMP)) { + ConstArrayView data = field(IMU_PACKET_TIMESTAMP); + for (size_t i = 0; i < data.size(); i++) { + if (data(i) != 0) { + time = (time == 0) ? data(i) : std::min(data(i), time); + break; + } + } + } + if (has_field(ZONE_PACKET_TIMESTAMP)) { + ConstArrayView data = field(ZONE_PACKET_TIMESTAMP); + if (data(0) != 0) { + time = (time == 0) ? data(0) : std::min(data(0), time); + } + } + return time; +} + +uint64_t LidarScan::get_last_valid_packet_timestamp() const { + uint64_t time = get_last_valid_lidar_packet_timestamp(); + if (has_field(IMU_PACKET_TIMESTAMP)) { + ConstArrayView data = field(IMU_PACKET_TIMESTAMP); + for (int i = static_cast(data.size()) - 1; i >= 0; i--) { + if (data(i) != 0) { + time = std::max(data(i), time); + break; + } + } + } + if (has_field(ZONE_PACKET_TIMESTAMP)) { + ConstArrayView data = field(ZONE_PACKET_TIMESTAMP); + time = std::max(data(0), time); + } + return time; +} + +uint64_t LidarScan::get_first_valid_lidar_packet_timestamp() const { int total_packets = packet_timestamp().size(); int columns_per_packet = w / total_packets; @@ -594,7 +643,7 @@ uint64_t LidarScan::get_first_valid_packet_timestamp() const { return 0; } -uint64_t LidarScan::get_last_valid_packet_timestamp() const { +uint64_t LidarScan::get_last_valid_lidar_packet_timestamp() const { int total_packets = packet_timestamp().size(); int columns_per_packet = w / total_packets; @@ -909,8 +958,63 @@ std::string to_string(const LidarScan& lidar_scan) { string_stream << ") "; if (field_val.bytes() > 0) { - FieldView flat_view = field_val.reshape(1, field_val.size()); - impl::visit_field_2d(flat_view, read_eigen, string_stream); + if (field_val.tag() == ChanFieldType::CHAR) { + // Show first sentence (e.g., first NMEA string). + const char* data = static_cast(field_val.get()); + size_t max_len = NMEA_SENTENCE_LENGTH; + const auto& shape = field_val.shape(); + if (!shape.empty() && shape.back() > 0) { + max_len = shape.back(); + } + const char* end = + static_cast(memchr(data, '\0', max_len)); + size_t len = (end != nullptr) ? static_cast(end - data) + : max_len; + std::string preview; + preview.reserve(len); + for (size_t i = 0; i < len; ++i) { + switch (data[i]) { + case '\r': + preview += "\\r"; + break; + case '\n': + preview += "\\n"; + break; + case '\t': + preview += "\\t"; + break; + case '\\': + preview += "\\\\"; + break; + case '\b': + preview += "\\b"; + break; + case '\f': + preview += "\\f"; + break; + case '\v': + preview += "\\v"; + break; + case '"': + preview += "\\\""; + break; + default: + preview += data[i]; + break; + } + } + bool truncated = (len == max_len && end == nullptr); + if (truncated) { + preview += "..."; + } + string_stream << "\"" << preview << "\""; + } else { + // For numeric types, show min/mean/max stats + // visit_field_2d will no-op for unsupported types (ZONE_STATE, + // etc.) + FieldView flat_view = field_val.reshape(1, field_val.size()); + impl::visit_field_2d(flat_view, read_eigen, string_stream); + } } string_stream << std::endl; }; diff --git a/ouster_client/src/logging.cpp b/ouster_client/src/logging.cpp index 2a6da38a..bf0fc72c 100644 --- a/ouster_client/src/logging.cpp +++ b/ouster_client/src/logging.cpp @@ -23,7 +23,7 @@ struct Logger::internal_logger { internal_logger(const std::string& logger_name, const std::string& pattern) : logger_(std::make_unique( - logger_name, std::make_shared())), + logger_name, std::make_shared())), pattern_(pattern) {} void configure_generic_sink(spdlog::sink_ptr sink, @@ -78,6 +78,19 @@ bool Logger::configure_stdout_sink(const std::string& log_level) { return true; } +bool Logger::configure_stderr_sink(const std::string& log_level) { + try { + internal_logger_->configure_generic_sink( + std::make_shared(), log_level); + } catch (const spdlog::spdlog_ex& ex) { + std::cerr << LOGGER_NAME << " init_logger failed: " << ex.what() + << std::endl; + return false; + } + + return true; +} + bool Logger::configure_file_sink(const std::string& log_level, const std::string& log_file_path, bool rotating, int max_size_in_bytes, diff --git a/ouster_client/src/metadata.cpp b/ouster_client/src/metadata.cpp index 4bb8e7a6..4f4c4c92 100644 --- a/ouster_client/src/metadata.cpp +++ b/ouster_client/src/metadata.cpp @@ -655,6 +655,14 @@ class SensorInfoImpl : public impl::JsonTools { sensor_info.format.zone_monitoring_enabled = true; } } + + // handle the case where lidar data is disabled + // make sure to default to assuming the stream is enabled if we + // are missing the config settings for some reason + if (sensor_info.config.udp_port_lidar.value_or(7504) == 0 || + sensor_info.config.udp_dest.value_or("default").empty()) { + sensor_info.format.udp_profile_lidar = UDPProfileLidar::OFF; + } } void parse_and_validate_calibration_status(SensorInfo& sensor_info) { diff --git a/ouster_client/src/parsing.cpp b/ouster_client/src/parsing.cpp index afb4f771..b87e32bb 100644 --- a/ouster_client/src/parsing.cpp +++ b/ouster_client/src/parsing.cpp @@ -212,6 +212,14 @@ static const Table LB_FIELD_INFO{{ {ChanField::RAW32_WORD1, field_info(0, 32)}, }}; +static const Table LB_WINDOW_FIELD_INFO{{ + {ChanField::RANGE, field_info(0, 15, 3)}, + {ChanField::FLAGS, field_info(15, 1)}, + {ChanField::REFLECTIVITY, field_info(16, 8)}, + {ChanField::WINDOW, field_info(24, 8)}, + {ChanField::RAW32_WORD1, field_info(0, 32)}, +}}; + static const Table DUAL_FIELD_INFO{{ {ChanField::RANGE, field_info(0, 19)}, {ChanField::FLAGS, field_info(19, 5)}, @@ -317,6 +325,8 @@ Table OUSTER_API_FUNCTION {ZM_LB_FIELD_INFO.data(), ZM_LB_FIELD_INFO.size(), 8}}, {UDPProfileLidar::RNG19_RFL8_SIG16_NIR16_ZONE16, {ZM_SINGLE_FIELD_INFO.data(), ZM_SINGLE_FIELD_INFO.size(), 12}}, + {UDPProfileLidar::RNG15_RFL8_WIN8, + {LB_WINDOW_FIELD_INFO.data(), LB_WINDOW_FIELD_INFO.size(), 4}}, }}; OUSTER_API_FUNCTION Table diff --git a/ouster_client/src/types.cpp b/ouster_client/src/types.cpp index 82bbb90c..f0ce7478 100644 --- a/ouster_client/src/types.cpp +++ b/ouster_client/src/types.cpp @@ -103,6 +103,7 @@ Table udp_profile_lidar_strings{ {UDPProfileLidar::RNG15_RFL8_NIR8_ZONE16, "RNG15_RFL8_NIR8_ZONE16"}, {UDPProfileLidar::RNG19_RFL8_SIG16_NIR16_ZONE16, "RNG19_RFL8_SIG16_NIR16_ZONE16"}, + {UDPProfileLidar::RNG15_RFL8_WIN8, "RNG15_RFL8_WIN8"}, {UDPProfileLidar::OFF, "OFF"}, }}; diff --git a/ouster_mapping/include/ouster/deskew_method.h b/ouster_mapping/include/ouster/deskew_method.h index 8b661a87..8eac396b 100644 --- a/ouster_mapping/include/ouster/deskew_method.h +++ b/ouster_mapping/include/ouster/deskew_method.h @@ -180,12 +180,14 @@ class OUSTER_API_CLASS InertialIntegrationImuDeskewMethod Eigen::Ref linear_accel_body_frame); - static bool pick_the_last_valid_imu_pose_from_scan_set( + static bool pick_last_valid_imu_pose( const ouster::sdk::core::LidarScanSet& scan_set, double& last_ts, ouster::sdk::core::Matrix4dR& last_pose); std::vector imu_to_body_transform_; ouster::sdk::core::LidarScanSet last_scan_set_; + nonstd::optional last_scan_set_last_ts_{}; + nonstd::optional last_scan_set_last_pose_{}; nonstd::optional gravity_vector_world_frame_xyz_; std::vector accel_bias_imu_frame_; std::vector gyro_bias_imu_frame_; diff --git a/ouster_mapping/include/ouster/pose_optimizer.h b/ouster_mapping/include/ouster/pose_optimizer.h index 04b12c2d..6c51af0f 100644 --- a/ouster_mapping/include/ouster/pose_optimizer.h +++ b/ouster_mapping/include/ouster/pose_optimizer.h @@ -96,11 +96,12 @@ class OUSTER_API_CLASS PoseOptimizer { * @brief Add a constraint to the optimization problem. * * This is the main method for adding constraints to the pose optimizer. - * It accepts any constraint derived from Constraint. The constraint will - * be assigned and return a unique ID for later removal if needed. + * It accepts any constraint derived from Constraint. The constraint object + * carries its own ID assigned at construction; adding will fail if the ID + * is already in use. * * @param[in] constraint A constraint object derived from Constraint. - * @return The unique ID assigned to the constraint. + * @return The unique ID of the constraint. * @throws std::runtime_error if the constraint cannot be added. */ OUSTER_API_FUNCTION diff --git a/ouster_mapping/include/ouster/pose_optimizer_constraint.h b/ouster_mapping/include/ouster/pose_optimizer_constraint.h index 426b4896..7f3d6356 100644 --- a/ouster_mapping/include/ouster/pose_optimizer_constraint.h +++ b/ouster_mapping/include/ouster/pose_optimizer_constraint.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include #include @@ -160,7 +161,9 @@ class OUSTER_API_CLASS Constraint { * @brief Default Constructor */ OUSTER_API_FUNCTION - Constraint() = default; + Constraint() + : constraint_id( + next_constraint_id_.fetch_add(1, std::memory_order_relaxed)) {} /** Destructor */ OUSTER_API_FUNCTION @@ -173,7 +176,9 @@ class OUSTER_API_CLASS Constraint { */ OUSTER_API_FUNCTION Constraint(const Eigen::Array3d& translation_weights) - : translation_weights(translation_weights) {} + : translation_weights(translation_weights), + constraint_id( + next_constraint_id_.fetch_add(1, std::memory_order_relaxed)) {} /** * @brief Copy constructor @@ -188,8 +193,8 @@ class OUSTER_API_CLASS Constraint { /** * @brief Get the unique constraint ID. * - * Returns 0 for non-user (internal) constraints. IDs > 0 are assigned to - * user-added constraints and are immutable once set internally. + * Returns 0 for non-user (internal) constraints. IDs > 0 are assigned when + * constraint objects are constructed and are immutable once set internally. * * @return uint32_t The constraint identifier. */ @@ -220,17 +225,12 @@ class OUSTER_API_CLASS Constraint { private: friend class PoseOptimizer; - /** - * @brief Set the constraint ID. - * - * @param[in] id The id to assign to this constraint instance. - */ - void set_constraint_id(uint32_t id) { constraint_id = id; } + static std::atomic next_constraint_id_; /** * Internal constraint identifier. * 0 indicates an internal/trajectory constraint; >0 indicates a user-added - * constraint assigned by the optimizer. + * constraint assigned at construction time. */ uint32_t constraint_id = 0; }; diff --git a/ouster_mapping/src/active_time_correction.cpp b/ouster_mapping/src/active_time_correction.cpp index ee213673..4273d2d0 100644 --- a/ouster_mapping/src/active_time_correction.cpp +++ b/ouster_mapping/src/active_time_correction.cpp @@ -249,7 +249,7 @@ std::vector ActiveTimeCorrection::calculate_fallback_ts_offset( for (size_t idx : scans.valid_indices()) { const auto& scan = *scans[idx]; int64_t first_pkt_ts = - static_cast(scan.get_first_valid_packet_timestamp()); + static_cast(scan.get_first_valid_lidar_packet_timestamp()); int64_t frame_start_ts = static_cast(scan.get_first_valid_column_timestamp()); offsets[idx] = first_pkt_ts - frame_start_ts; diff --git a/ouster_mapping/src/deskew_method.cpp b/ouster_mapping/src/deskew_method.cpp index 7f13b63a..b108ef0a 100644 --- a/ouster_mapping/src/deskew_method.cpp +++ b/ouster_mapping/src/deskew_method.cpp @@ -56,31 +56,37 @@ InertialIntegrationImuDeskewMethod::InertialIntegrationImuDeskewMethod( } } -// TODO[UN]: Improve the implementation to search for values that don't exceed -// a preset timestamp threshold -bool InertialIntegrationImuDeskewMethod:: - pick_the_last_valid_imu_pose_from_scan_set(const LidarScanSet& scan_set, - double& last_ts, - Matrix4dR& last_pose) { - if (scan_set.size() == 0) { - return false; - } - const auto& last_scan = *scan_set.valid_scans().begin(); - Eigen::Ref> imu_status = - last_scan.field(ChanField::IMU_STATUS); - std::vector imu_valid = impl::get_valid_columns(imu_status); - if (imu_valid.empty()) { - return false; +bool InertialIntegrationImuDeskewMethod::pick_last_valid_imu_pose( + const LidarScanSet& scan_set, double& last_ts, Matrix4dR& last_pose) { + bool imu_data_found = false; + for (const auto& scan : scan_set.valid_scans()) { + if (!scan.has_field(ChanField::IMU_STATUS)) { + continue; + } + + Eigen::Ref> imu_status = + scan.field(ChanField::IMU_STATUS); + std::vector imu_valid = + impl::get_valid_columns(imu_status); + if (imu_valid.empty()) { + continue; + } + + int last_valid_imu_idx = imu_valid.back(); + Eigen::Ref> scan_ts = + scan.field(ChanField::IMU_TIMESTAMP); + double candidate_ts = scan_ts[last_valid_imu_idx] * 1e-9; + if (!imu_data_found || candidate_ts > last_ts) { + last_ts = candidate_ts; + Eigen::Ref> meas_id = + scan.field(ChanField::IMU_MEASUREMENT_ID); + uint16_t last_pose_col = meas_id(last_valid_imu_idx); + last_pose = scan.get_column_pose(last_pose_col); + } + imu_data_found = true; } - int last_valid_imu_idx = imu_valid.back(); - Eigen::Ref> last_scan_ts = - last_scan.field(ChanField::IMU_TIMESTAMP); - last_ts = last_scan_ts[last_valid_imu_idx] * 1e-9; - Eigen::Ref> last_meas_id = - last_scan.field(ChanField::IMU_MEASUREMENT_ID); - uint16_t last_pose_col = last_meas_id(last_valid_imu_idx); - last_pose = last_scan.get_column_pose(last_pose_col); - return true; + + return imu_data_found; } void InertialIntegrationImuDeskewMethod::update(LidarScanSet& scan_set) { @@ -147,13 +153,8 @@ void InertialIntegrationImuDeskewMethod::update(LidarScanSet& scan_set) { } } - double last_ts = 0.0; - Matrix4dR last_pose = Matrix4dR::Identity(); - - if (combined_ts.empty() || !pick_the_last_valid_imu_pose_from_scan_set( - last_scan_set_, last_ts, last_pose)) { - for (size_t idx : scan_set.valid_indices()) { - auto& scan = *scan_set[idx]; + if (combined_ts.empty() || last_scan_set_last_ts_ == nonstd::nullopt) { + for (auto& scan : scan_set.valid_scans()) { impl::interp_pose(scan, ts_list_.front(), pose_list_.front(), ts_list_.back(), pose_list_.back()); } @@ -161,6 +162,9 @@ void InertialIntegrationImuDeskewMethod::update(LidarScanSet& scan_set) { return; } + double last_ts = *last_scan_set_last_ts_; + Matrix4dR last_pose = *last_scan_set_last_pose_; + // TODO[UN]: optimize this sorting given the timestamps are monotonically // increasing for each sensor std::vector indices(combined_ts.size()); @@ -190,6 +194,12 @@ void InertialIntegrationImuDeskewMethod::update(LidarScanSet& scan_set) { for (size_t sidx : scan_set.valid_indices()) { auto& scan = *scan_set[sidx]; + if (!scan.has_field(ChanField::IMU_STATUS)) { + impl::interp_pose(scan, ts_list_.front(), pose_list_.front(), + ts_list_.back(), pose_list_.back()); + continue; + } + // This block deals with the edge cases where lidar packets may have // been dropped but corresponding imu packet exist and can be use to // subsitute the missing lidar timestamps @@ -225,6 +235,15 @@ void InertialIntegrationImuDeskewMethod::update(LidarScanSet& scan_set) { void InertialIntegrationImuDeskewMethod::set_last_pose(int64_t ts, const Matrix4dR& pose) { + // retrieve the last imu pose from the last scan set before the time get + // reset by the active time correction in case of an unsynchronized + // multi-sensor setup + double last_ts = 0.0; + Matrix4dR last_pose = Matrix4dR::Identity(); + if (pick_last_valid_imu_pose(last_scan_set_, last_ts, last_pose)) { + last_scan_set_last_ts_ = last_ts; + last_scan_set_last_pose_ = last_pose; + } DeskewMethod::set_last_pose(ts, pose); estimate_gravity_vector(last_scan_set_); } @@ -386,6 +405,12 @@ InertialIntegrationImuDeskewMethod::calc_poses_with_motion_model( pose_list_.front().block<3, 1>(0, 3)) / (ts_list_.back() - ts_list_.front()); + // TODO[UN]: we need to skip imu measurements for timestamps earlier than + // last_timestamp and feed in poses from last scan set or alter the logic + // of pick_last_valid_imu_pose to get the last imu pose before current + // timestamp[0]. Alternatively, in cases of an imu measurements overlap one + // could simply average the results between the overlapping measurements. + // I will defer the choice to the next iteration. for (size_t i = 0; i < N; ++i) { double dt; Eigen::Matrix3d prev_world_orientation; @@ -469,8 +494,11 @@ std::unique_ptr DeskewMethodFactory::create( } else if (method == "auto") { if (!has_imu_data) { logger().info( - "IMU data not available, falling back to " - "ConstantVelocityDeskewMethod"); + "Synchronous IMU data not available (requires FW 3.2+ and " + "ACCEL32_GYRO32_NMEA imu profile)," + " falling back to ConstantVelocityDeskewMethod.\n" + " Suppress this warning by adding '--deskew-method " + "constant_velocity' to the 'slam' or 'localize' command."); return std::make_unique(infos); } else { logger().info("Using InertialIntegrationImuDeskewMethod"); diff --git a/ouster_mapping/src/pose_optimizer.cpp b/ouster_mapping/src/pose_optimizer.cpp index 55eae48b..3fe7d38b 100644 --- a/ouster_mapping/src/pose_optimizer.cpp +++ b/ouster_mapping/src/pose_optimizer.cpp @@ -53,6 +53,10 @@ using ouster::sdk::core::logger; namespace ouster { namespace sdk { namespace mapping { + +// It starts at 1 because 0 is reserved for traj constraints +std::atomic Constraint::next_constraint_id_{1}; + namespace { PoseH run_icp(std::shared_ptr node_first, @@ -138,9 +142,6 @@ class PoseOptimizer::Impl { std::unordered_map constraint_id_to_residual_map; - // Counter for assigning unique constraint IDs - uint32_t next_constraint_id = 1; - // Downsample voxel size for point clouds used in ICP const double downsample_voxel_size = 0.05; @@ -443,9 +444,9 @@ class PoseOptimizer::Impl { release_first_node_anchor(); logger().info( - "Successfully processed absolute pose constraint for timestamp " - "{}", - abs_constraint->timestamp); + "Successfully processed absolute pose constraint id {} for " + "timestamp {}", + abs_constraint->get_constraint_id(), abs_constraint->timestamp); } catch (const std::exception& e) { logger().error( "Error creating absolute pose constraint for timestamp {}: {}", @@ -545,8 +546,9 @@ class PoseOptimizer::Impl { add_constraint_with_id( constraint_impl, pose_constraint->get_constraint_id()); logger().info( - "Successfully added pose to pose constraint between {} " - "and {}", + "Successfully added pose to pose constraint id {} " + "between {} and {}", + pose_constraint->get_constraint_id(), pose_constraint->timestamp1, pose_constraint->timestamp2); } else { @@ -577,8 +579,9 @@ class PoseOptimizer::Impl { add_constraint_with_id( constraint_impl, pose_constraint->get_constraint_id()); logger().info( - "Successfully added stored pose constraint between {} " - "and {}", + "Successfully added stored pose constraint id {} " + "between {} and {}", + pose_constraint->get_constraint_id(), pose_constraint->timestamp1, pose_constraint->timestamp2); } else { @@ -684,9 +687,10 @@ class PoseOptimizer::Impl { pt_constraint->get_constraint_id()); logger().info( - "Successfully added point to point constraint between {} and " - "{}", - pt_constraint->timestamp1, pt_constraint->timestamp2); + "Successfully added point to point constraint id {} between " + "{} and {}", + pt_constraint->get_constraint_id(), pt_constraint->timestamp1, + pt_constraint->timestamp2); } catch (const std::exception& e) { logger().error( "Error creating point to point constraint between timestamps " @@ -750,8 +754,9 @@ class PoseOptimizer::Impl { release_first_node_anchor(); logger().info( - "Successfully processed absolute point constraint for " + "Successfully processed absolute point constraint id {} for " "timestamp {}", + abs_pt_constraint->get_constraint_id(), abs_pt_constraint->timestamp); } catch (const std::exception& e) { logger().error( @@ -1068,14 +1073,32 @@ class PoseOptimizer::Impl { throw std::invalid_argument("Cannot add null constraint"); } - // Assign unique ID to constraint for tracking + // Checks if an ID is already taken by an existing user constraint. + // We look at both the active residual map and stored config + // constraints (id 0 is reserved for internal/trajectory constraints). + auto constraint_id_in_use = [&](uint32_t id) { + if (id == 0) { + return false; + } + if (constraint_id_to_residual_map.find(id) != + constraint_id_to_residual_map.end()) { + return true; + } + for (const auto& constraint : config.constraints) { + if (!constraint || constraint.get() == base_constraint) { + continue; + } + if (constraint->get_constraint_id() == id) { + return true; + } + } + return false; + }; + uint32_t constraint_id = base_constraint->get_constraint_id(); - if (constraint_id == 0) { - base_constraint->set_constraint_id(next_constraint_id++); - constraint_id = base_constraint->get_constraint_id(); - } else { - next_constraint_id = - std::max(next_constraint_id, constraint_id + 1); + if (constraint_id_in_use(constraint_id)) { + throw std::runtime_error("Constraint ID already in use: " + + std::to_string(constraint_id)); } // Dispatch to appropriate handler based on constraint type switch (base_constraint->get_type()) { @@ -1452,8 +1475,13 @@ class PoseOptimizer::Impl { // Remove residual block from Ceres auto residual_it = constraint_id_to_residual_map.find(constraint_id); if (residual_it != constraint_id_to_residual_map.end()) { - problem.RemoveResidualBlock(residual_it->second); + const auto residual_id = residual_it->second; + problem.RemoveResidualBlock(residual_id); constraint_id_to_residual_map.erase(residual_it); + user_constraint_residual_blocks.erase( + std::remove(user_constraint_residual_blocks.begin(), + user_constraint_residual_blocks.end(), residual_id), + user_constraint_residual_blocks.end()); } else { logger().error("Constraint ID {} not found in residual map", constraint_id); @@ -1795,12 +1823,13 @@ uint32_t PoseOptimizer::add_constraint(std::unique_ptr constraint) { } try { - // Store the Constraint in Impl's config for saving Constraint* constraint_ptr = constraint.get(); - pimpl_->config.constraints.push_back(std::move(constraint)); + const uint32_t constraint_id = + pimpl_->add_base_constraint(constraint_ptr); - // Create and add the implementation directly - return pimpl_->add_base_constraint(constraint_ptr); + // Store the Constraint in Impl's config for saving + pimpl_->config.constraints.push_back(std::move(constraint)); + return constraint_id; } catch (const std::exception& e) { logger().error("Failed to add constraint: {}", e.what()); diff --git a/ouster_osf/src/basics.cpp b/ouster_osf/src/basics.cpp index d12bb1b7..7935ea08 100644 --- a/ouster_osf/src/basics.cpp +++ b/ouster_osf/src/basics.cpp @@ -149,11 +149,8 @@ bool check_prefixed_size_block_crc(const OsfBuffer& buf, uint32_t prefixed_size = get_prefixed_size(buf); if (buf_length < prefixed_size + FLATBUFFERS_PREFIX_LENGTH + CRC_BYTES_SIZE) { - throw std::runtime_error( - "CRC32 validation failed!" - " (Prefix Size " + - std::to_string(prefixed_size) + "[bytes] Buf Length " + - std::to_string(buf_length) + "[bytes])"); + // prefixed size doesnt match buffer size, the data is corrupt + return false; } const uint32_t crc_stored = get_prefixed_size( diff --git a/ouster_osf/src/fb_common.cpp b/ouster_osf/src/fb_common.cpp index 5550fb90..83ac8e83 100644 --- a/ouster_osf/src/fb_common.cpp +++ b/ouster_osf/src/fb_common.cpp @@ -5,6 +5,7 @@ #include "fb_common.h" #include +#include #include #include "ouster/osf/impl/png_tools.h" @@ -277,9 +278,21 @@ void fb_restore_fields( } } ChanFieldType tag = from_osf_enum(fb_field->tag()); + std::vector shape{fb_field->shape()->begin(), fb_field->shape()->end()}; - auto desc = FieldDescriptor::array(tag, shape); + + // Skip fields with unsupported types (e.g., from a newer SDK version) + FieldDescriptor desc; + try { + desc = FieldDescriptor::array(tag, shape); + } catch (const std::invalid_argument&) { + error_handler(Severity::OUSTER_WARNING, + "Skipping field '" + name + + "' with unsupported type (tag=" + + std::to_string(static_cast(tag)) + ")"); + continue; + } ouster::sdk::core::FieldClass field_class = from_osf_enum(fb_field->field_class()); diff --git a/ouster_osf/src/file.cpp b/ouster_osf/src/file.cpp index 3024d348..43283ef5 100644 --- a/ouster_osf/src/file.cpp +++ b/ouster_osf/src/file.cpp @@ -285,14 +285,6 @@ void OsfFile::initialize_header_and_metadata() { "Osf: Metadata verification has failed."); return; } - - if (!check_prefixed_size_block_crc(metadata_chunk_, - metadata_chunk_.size())) { - metadata_chunk_ = {}; - ouster::sdk::core::logger().warn( - "Osf: CRC check of OSF metadata failed."); - return; - } } OsfOffset OsfFile::get_header_chunk_offset() { return header_offset_; } diff --git a/ouster_osf/src/writer.cpp b/ouster_osf/src/writer.cpp index 8187a251..180f2d9a 100644 --- a/ouster_osf/src/writer.cpp +++ b/ouster_osf/src/writer.cpp @@ -142,7 +142,7 @@ void Writer::save_internal(uint32_t stream_index, const LidarScan& scan, msg.scan_stream_id = lidar_streams_[stream_index]->meta().id(); msg.lidar_sensor_id = lidar_meta_id_[stream_index]; if (info_ts_ == ts_t::min()) { - info_ts_ = timestamp; + info_ts_ = time; } sensor_info_stream_->save(msg, info_ts_); // todo dont actually need to flush for every single sensor just need to diff --git a/ouster_pcap/src/pcap.cpp b/ouster_pcap/src/pcap.cpp index 8c604d49..f9e7c63c 100644 --- a/ouster_pcap/src/pcap.cpp +++ b/ouster_pcap/src/pcap.cpp @@ -127,7 +127,7 @@ const PacketInfo& PcapReader::current_info() const { return info_; } // Does offset need to unsigned int? void PcapReader::seek(uint64_t offset) { offset = std::max(offset, sizeof(struct pcap_file_header)); - if (FSEEK(impl_->pcap_reader_internals, static_cast(offset), + if (FSEEK(impl_->pcap_reader_internals, static_cast(offset), SEEK_SET)) { throw std::runtime_error("pcap seek failed"); } diff --git a/ouster_pcap/src/pcap_scan_source.cpp b/ouster_pcap/src/pcap_scan_source.cpp index 7199d908..707f3257 100644 --- a/ouster_pcap/src/pcap_scan_source.cpp +++ b/ouster_pcap/src/pcap_scan_source.cpp @@ -219,12 +219,24 @@ PcapScanSource::PcapScanSource(const std::string& source, // get average scan size plus some overhead const int pcap_pkt_header = 100; - int scan_size = 0; + size_t scan_size = 0; for (const auto& sensor : sensor_info()) { PacketFormat packet_format(*sensor); auto pkt_size = packet_format.lidar_packet_size + pcap_pkt_header; scan_size += pkt_size * sensor->format.lidar_packets_per_frame(); + auto imu_pkt_size = packet_format.imu_packet_size + pcap_pkt_header; + scan_size += imu_pkt_size * sensor->format.imu_packets_per_frame; + if (sensor->format.zone_monitoring_enabled) { + scan_size += packet_format.zone_packet_size + pcap_pkt_header; + } + } + + if (scan_size == 0) { + throw std::runtime_error( + "Unexpected scan data size of 0. SensorInfo may be corrupt."); } + + // divide size of all scans to get average scan size scan_size /= sensor_info().size(); // number of scans is approximately file size divided by scan size diff --git a/ouster_sensor/src/client.cpp b/ouster_sensor/src/client.cpp index dfd04875..13cfe96f 100644 --- a/ouster_sensor/src/client.cpp +++ b/ouster_sensor/src/client.cpp @@ -418,7 +418,7 @@ std::string get_metadata(Client& cli, int timeout_sec) { bool init_logger(const std::string& log_level, const std::string& log_file_path, bool rotating, int max_size_in_bytes, int max_files) { if (log_file_path.empty()) { - return Logger::instance().configure_stdout_sink(log_level); + return Logger::instance().configure_stderr_sink(log_level); } else { return Logger::instance().configure_file_sink( log_level, log_file_path, rotating, max_size_in_bytes, max_files); diff --git a/ouster_viz/include/ouster/point_viz.h b/ouster_viz/include/ouster/point_viz.h index ce8d53b4..62531fd4 100644 --- a/ouster_viz/include/ouster/point_viz.h +++ b/ouster_viz/include/ouster/point_viz.h @@ -26,6 +26,16 @@ namespace ouster { namespace sdk { namespace viz { +/** + * Exception thrown when a PointViz operation requires it to be running + * but it is not. + */ +struct PointVizNotRunningError : public std::runtime_error { + /// Constructor + PointVizNotRunningError() + : std::runtime_error("PointViz is not running.") {} +}; + /** * 4x4 matrix of doubles to represent transformations */ diff --git a/ouster_viz/src/display_p3_icc.h b/ouster_viz/src/display_p3_icc.h new file mode 100644 index 00000000..49ba3596 --- /dev/null +++ b/ouster_viz/src/display_p3_icc.h @@ -0,0 +1,65 @@ +#pragma once +#include +#include + +namespace ouster { +namespace sdk { +namespace viz { +namespace impl { +namespace screenshot_utils { + +// Embedded from: "Display P3.icc" +// This .icc file that contains the default color profile used on MacOs and +// can be found in /System/Library/ColorSync/Profiles/ +const std::vector display_p3_icc = { + 0x00, 0x00, 0x02, 0x18, 0x61, 0x70, 0x70, 0x6c, 0x04, 0x00, 0x00, 0x00, + 0x6d, 0x6e, 0x74, 0x72, 0x52, 0x47, 0x42, 0x20, 0x58, 0x59, 0x5a, 0x20, + 0x07, 0xe6, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x61, 0x63, 0x73, 0x70, 0x41, 0x50, 0x50, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x41, 0x50, 0x50, 0x4c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf6, 0xd6, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0xd3, 0x2d, 0x61, 0x70, 0x70, 0x6c, + 0xec, 0xfd, 0xa3, 0x8e, 0x38, 0x85, 0x47, 0xc3, 0x6d, 0xb4, 0xbd, 0x4f, + 0x7a, 0xda, 0x18, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, + 0x64, 0x65, 0x73, 0x63, 0x00, 0x00, 0x00, 0xfc, 0x00, 0x00, 0x00, 0x30, + 0x63, 0x70, 0x72, 0x74, 0x00, 0x00, 0x01, 0x2c, 0x00, 0x00, 0x00, 0x50, + 0x77, 0x74, 0x70, 0x74, 0x00, 0x00, 0x01, 0x7c, 0x00, 0x00, 0x00, 0x14, + 0x72, 0x58, 0x59, 0x5a, 0x00, 0x00, 0x01, 0x90, 0x00, 0x00, 0x00, 0x14, + 0x67, 0x58, 0x59, 0x5a, 0x00, 0x00, 0x01, 0xa4, 0x00, 0x00, 0x00, 0x14, + 0x62, 0x58, 0x59, 0x5a, 0x00, 0x00, 0x01, 0xb8, 0x00, 0x00, 0x00, 0x14, + 0x72, 0x54, 0x52, 0x43, 0x00, 0x00, 0x01, 0xcc, 0x00, 0x00, 0x00, 0x20, + 0x63, 0x68, 0x61, 0x64, 0x00, 0x00, 0x01, 0xec, 0x00, 0x00, 0x00, 0x2c, + 0x62, 0x54, 0x52, 0x43, 0x00, 0x00, 0x01, 0xcc, 0x00, 0x00, 0x00, 0x20, + 0x67, 0x54, 0x52, 0x43, 0x00, 0x00, 0x01, 0xcc, 0x00, 0x00, 0x00, 0x20, + 0x6d, 0x6c, 0x75, 0x63, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x0c, 0x65, 0x6e, 0x55, 0x53, 0x00, 0x00, 0x00, 0x14, + 0x00, 0x00, 0x00, 0x1c, 0x00, 0x44, 0x00, 0x69, 0x00, 0x73, 0x00, 0x70, + 0x00, 0x6c, 0x00, 0x61, 0x00, 0x79, 0x00, 0x20, 0x00, 0x50, 0x00, 0x33, + 0x6d, 0x6c, 0x75, 0x63, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x0c, 0x65, 0x6e, 0x55, 0x53, 0x00, 0x00, 0x00, 0x34, + 0x00, 0x00, 0x00, 0x1c, 0x00, 0x43, 0x00, 0x6f, 0x00, 0x70, 0x00, 0x79, + 0x00, 0x72, 0x00, 0x69, 0x00, 0x67, 0x00, 0x68, 0x00, 0x74, 0x00, 0x20, + 0x00, 0x41, 0x00, 0x70, 0x00, 0x70, 0x00, 0x6c, 0x00, 0x65, 0x00, 0x20, + 0x00, 0x49, 0x00, 0x6e, 0x00, 0x63, 0x00, 0x2e, 0x00, 0x2c, 0x00, 0x20, + 0x00, 0x32, 0x00, 0x30, 0x00, 0x32, 0x00, 0x32, 0x58, 0x59, 0x5a, 0x20, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf6, 0xd5, 0x00, 0x01, 0x00, 0x00, + 0x00, 0x00, 0xd3, 0x2c, 0x58, 0x59, 0x5a, 0x20, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x83, 0xdf, 0x00, 0x00, 0x3d, 0xbf, 0xff, 0xff, 0xff, 0xbb, + 0x58, 0x59, 0x5a, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4a, 0xbf, + 0x00, 0x00, 0xb1, 0x37, 0x00, 0x00, 0x0a, 0xb9, 0x58, 0x59, 0x5a, 0x20, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x28, 0x38, 0x00, 0x00, 0x11, 0x0b, + 0x00, 0x00, 0xc8, 0xb9, 0x70, 0x61, 0x72, 0x61, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x03, 0x00, 0x00, 0x00, 0x02, 0x66, 0x66, 0x00, 0x00, 0xf2, 0xa7, + 0x00, 0x00, 0x0d, 0x59, 0x00, 0x00, 0x13, 0xd0, 0x00, 0x00, 0x0a, 0x5b, + 0x73, 0x66, 0x33, 0x32, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0c, 0x42, + 0x00, 0x00, 0x05, 0xde, 0xff, 0xff, 0xf3, 0x26, 0x00, 0x00, 0x07, 0x93, + 0x00, 0x00, 0xfd, 0x90, 0xff, 0xff, 0xfb, 0xa2, 0xff, 0xff, 0xfd, 0xa3, + 0x00, 0x00, 0x03, 0xdc, 0x00, 0x00, 0xc0, 0x6e}; + +} // namespace screenshot_utils +} // namespace impl +} // namespace viz +} // namespace sdk +} // namespace ouster diff --git a/ouster_viz/src/image.cpp b/ouster_viz/src/image.cpp index 6d0e83de..ad253d33 100644 --- a/ouster_viz/src/image.cpp +++ b/ouster_viz/src/image.cpp @@ -60,6 +60,7 @@ GLImage::GLImage(const Image& /*image*/) : GLImage{} {} GLImage::~GLImage() { glDeleteBuffers(2, vertexbuffers_.data()); + glDeleteBuffers(1, &image_index_id_); glDeleteTextures(1, &image_texture_id_); glDeleteTextures(1, &mask_texture_id_); glDeleteTextures(1, &palette_texture_id_); diff --git a/ouster_viz/src/misc.cpp b/ouster_viz/src/misc.cpp index 03091419..f1a2c6f6 100644 --- a/ouster_viz/src/misc.cpp +++ b/ouster_viz/src/misc.cpp @@ -150,6 +150,7 @@ void GLRings::uninitialize() { GLRings::initialized = false; glDeleteProgram(ring_program_id); glDeleteVertexArrays(1, &GLRings::ring_vao); + glDeleteBuffers(1, &GLRings::xyz_buffer); } /* @@ -192,7 +193,11 @@ GLCuboid::GLCuboid() // for Indexed, arg ignored GLCuboid::GLCuboid(const Cuboid& /*unused*/) : GLCuboid{} {} -GLCuboid::~GLCuboid() { glDeleteBuffers(1, &xyz_buffer_); } +GLCuboid::~GLCuboid() { + glDeleteBuffers(1, &xyz_buffer_); + glDeleteBuffers(1, &indices_buffer_); + glDeleteBuffers(1, &edge_indices_buffer_); +} /* * Draws the cuboids from the point of view of the camera. diff --git a/ouster_viz/src/point_viz.cpp b/ouster_viz/src/point_viz.cpp index eaf45e55..e1c146d4 100644 --- a/ouster_viz/src/point_viz.cpp +++ b/ouster_viz/src/point_viz.cpp @@ -395,7 +395,10 @@ void PointViz::cursor_visible(bool state) { bool PointViz::running() { return pimpl_->glfw->running(); } -void PointViz::running(bool state) { pimpl_->glfw->running(state); } +void PointViz::running(bool state) { + std::unique_lock lock(pimpl_->screenshot_request_mutex); + pimpl_->glfw->running(state); +} void PointViz::visible(bool state) { pimpl_->glfw->visible(state); } @@ -794,11 +797,14 @@ std::vector PointViz::get_screenshot(uint32_t width, uint32_t height) { pimpl_->screenshot_fb = nullptr; } else { // get_screenshot is being called from a different thread than the main - // thread. Request the screenshot asynchrounously. + // thread. Request the screenshot asynchronously. // Submit screenshot request { std::unique_lock lock(pimpl_->screenshot_request_mutex); + if (!running()) { + throw PointVizNotRunningError(); + } if (!pimpl_->screenshot_request) { pimpl_->screenshot_request = std::make_unique(width, height); @@ -807,11 +813,8 @@ std::vector PointViz::get_screenshot(uint32_t width, uint32_t height) { "A screenshot request is already in progress. Only one " "screenshot request can be processed at a time."); } - } - // Block until the screenshot is complete - { - std::unique_lock lock(pimpl_->screenshot_request_mutex); + // Block until the screenshot is complete pimpl_->screenshot_condition_variable.wait(lock, [this]() { if (!pimpl_->screenshot_request) { return false; diff --git a/ouster_viz/src/screenshot_utils.cpp b/ouster_viz/src/screenshot_utils.cpp index fbd16ebf..dc6980e8 100644 --- a/ouster_viz/src/screenshot_utils.cpp +++ b/ouster_viz/src/screenshot_utils.cpp @@ -19,6 +19,8 @@ #include #include +#include "display_p3_icc.h" + namespace ouster { namespace sdk { namespace viz { @@ -111,6 +113,14 @@ std::string write_png(const std::string& path, PNG_INTERLACE_NONE, PNG_COMPRESSION_TYPE_DEFAULT, PNG_FILTER_TYPE_DEFAULT); +#ifdef __APPLE__ + // On Apple, "Display P3" is the default color profile setting. + // This function embeds a color profile into the resulting PNG making the + // screenshot colors to better match what the user is seeing on the screen. + png_set_iCCP(png, info, "Display P3", 0, display_p3_icc.data(), + (png_uint_32)display_p3_icc.size()); +#endif + png_write_info(png, info); png_set_filter(png, 0, PNG_FILTER_NONE); diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 85ffb921..a06ce4be 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -18,7 +18,7 @@ set(CMAKE_CXX_EXTENSIONS OFF) if(MSVC) add_compile_options(/W2 /wd4996) - add_compile_definitions(NOMINMAX _USE_MATH_DEFINES WIN32_LEAN_AND_MEAN) + add_compile_definitions(NOMINMAX _USE_MATH_DEFINES WIN32_LEAN_AND_MEAN _ENABLE_EXTENDED_ALIGNED_STORAGE) else() add_compile_options(-Wall -Wextra -Wno-error=deprecated-declarations) if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU") diff --git a/python/src/cpp/_mapping.cpp b/python/src/cpp/_mapping.cpp index 6a3f395a..ab2152df 100644 --- a/python/src/cpp/_mapping.cpp +++ b/python/src/cpp/_mapping.cpp @@ -128,6 +128,7 @@ void init_mapping(py::module& module, py::module& /*unused*/) { .def_readwrite("translation_weights", &Constraint::translation_weights) .def("get_constraint_id", &Constraint::get_constraint_id, R"pbdoc( Get the unique constraint ID. Returns 0 for non-user constraints. + IDs are assigned when constraint objects are constructed. Returns: int: The constraint ID, or 0 if not a user-added constraint. @@ -355,13 +356,14 @@ void init_mapping(py::module& module, py::module& /*unused*/) { This is the new unified API for adding constraints. Use the constraint class constructors to create constraints, then pass them to this method. - The constraint will be assigned a unique ID for later removal if needed. + The constraint must already have a unique ID for later removal. + Adding a constraint with a duplicate ID will fail. Args: constraint: A constraint object created by one of the constraint constructors. Returns: - int: The unique constraint ID assigned to the added constraint. + int: The unique constraint ID of the added constraint. Raises: RuntimeError: If the constraint cannot be added. @@ -934,4 +936,4 @@ void init_mapping(py::module& module, py::module& /*unused*/) { R"pbdoc( Restore the timestamps in the provided LidarScanSet to their original values before active time correction was applied. )pbdoc"); -} \ No newline at end of file +} diff --git a/python/src/cpp/_viz.cpp b/python/src/cpp/_viz.cpp index 35604c29..3c658216 100644 --- a/python/src/cpp/_viz.cpp +++ b/python/src/cpp/_viz.cpp @@ -46,6 +46,7 @@ using namespace ouster::sdk; using ouster::sdk::viz::EventModifierKeys; using ouster::sdk::viz::MouseButton; using ouster::sdk::viz::MouseButtonEvent; +using ouster::sdk::viz::PointVizNotRunningError; template static void check_array(const py::array_t& array, size_t size = 0, @@ -137,6 +138,12 @@ void init_viz(py::module& module, py::module& /*unused*/) { .value("MOD_NUM_LOCK", EventModifierKeys::MOD_NUM_LOCK) .export_values(); + // clang-tidy produces spurious error here + // NOLINTBEGIN + py::register_exception( + module, "PointVizNotRunningError", PyExc_RuntimeError); + // NOLINTEND + py::class_(module, "PointViz") .def(py::init(), py::arg("name"), py::arg("fix_aspect") = false, diff --git a/python/src/cpp/client/data.cpp b/python/src/cpp/client/data.cpp index 6a01d324..1d173632 100644 --- a/python/src/cpp/client/data.cpp +++ b/python/src/cpp/client/data.cpp @@ -686,7 +686,17 @@ void init_client_data(py::module& module, py::module& /*unused*/) { &SensorInfo::beam_to_lidar_transform, "Homogenous transformation matrix reprsenting Beam to " "Lidar Transform") - .def_readwrite("extrinsic", &SensorInfo::extrinsic, "Extrinsic Matrix.") + .def_property( + "extrinsic", + [](SensorInfo& self) + -> Eigen::Ref { + return self.extrinsic; + }, + [](SensorInfo& self, + const decltype(SensorInfo::extrinsic)& extrinsic) { + self.extrinsic = extrinsic; + }, + "Extrinsic Matrix.") .def_readwrite("init_id", &SensorInfo::init_id, "Initialization id.") .def_readwrite("build_date", &SensorInfo::build_date, "Build date") .def_readwrite("image_rev", &SensorInfo::image_rev, "Image rev") diff --git a/python/src/cpp/client/lidar_scan.cpp b/python/src/cpp/client/lidar_scan.cpp index 1ab10b9a..cb73e606 100644 --- a/python/src/cpp/client/lidar_scan.cpp +++ b/python/src/cpp/client/lidar_scan.cpp @@ -461,6 +461,12 @@ void init_client_lidar_scan(py::module& module, py::module& /*unused*/) { .def("get_last_valid_packet_timestamp", &LidarScan::get_last_valid_packet_timestamp, "Return last valid packet timestamp in the scan.") + .def("get_first_valid_lidar_packet_timestamp", + &LidarScan::get_first_valid_lidar_packet_timestamp, + "Return first valid lidar packet timestamp in the scan.") + .def("get_last_valid_lidar_packet_timestamp", + &LidarScan::get_last_valid_lidar_packet_timestamp, + "Return last valid lidar packet timestamp in the scan.") .def("get_first_valid_column_timestamp", &LidarScan::get_first_valid_column_timestamp, "Return first valid column timestamp in the scan.") @@ -585,6 +591,13 @@ void init_client_lidar_scan(py::module& module, py::module& /*unused*/) { py::keep_alive<0, 1>()) .def("__eq__", [](const LidarScanSet& left, const LidarScanSet& right) { return left == right; }) + .def( + "__setitem__", + [](LidarScanSet& self, int index, + const std::shared_ptr& value) { + self[index] = value; + }, + py::arg("index"), py::arg("value").none()) .def("__getitem__", [](const LidarScanSet& self, int index) { return self[index]; }); } diff --git a/python/src/ouster/cli/plugins/source.py b/python/src/ouster/cli/plugins/source.py index adf1a4d9..c42ff73b 100644 --- a/python/src/ouster/cli/plugins/source.py +++ b/python/src/ouster/cli/plugins/source.py @@ -592,10 +592,15 @@ def clip_iter(): "If not provided, the filter will be applied to all fields.") @click.option('--invalid-value', default=0, type=float, show_default=True, help="The value to used for pixels that match the filter") +@click.option('--coord-frame', default="BODY", show_default=True, + type=click.Choice(["SENSOR", "BODY", "WORLD"], case_sensitive=False), + help="Coordinate frame for XYZ filtering (SENSOR=no extrinsics, " + "BODY=extrinsics, WORLD=dewarped)") @click.pass_context @source_multicommand(type=SourceCommandType.PROCESSOR) def source_filter(ctx: SourceCommandContext, axis_field: str, indices: Tuple[Optional[int], Optional[int]], - filtered_fields: Optional[str], invalid_value: float, **kwargs) -> None: + filtered_fields: Optional[str], invalid_value: float, + coord_frame: str, **kwargs) -> None: """ Apply a filter to LidarScan data based on the specified axis/field and indices. @@ -605,7 +610,8 @@ def source_filter(ctx: SourceCommandContext, axis_field: str, indices: Tuple[Opt works by updating values that match the condition to the invalid-value (default: 0). Usage: - filter [--filtered-fields ] [--invalid-value ] + filter [--filtered-fields ] [--invalid-value ] + [--coord-frame ] Examples: @@ -629,12 +635,14 @@ def source_filter(ctx: SourceCommandContext, axis_field: str, indices: Tuple[Opt min_v = raw_min_v if raw_min_v is not None else float('-inf') max_v = raw_max_v if raw_max_v is not None else float('inf') - def filter_xyz_iter(scan_iter, axis_field, invalid_value, filtered_fields): + def filter_xyz_iter(scan_iter, axis_field, invalid_value, filtered_fields, coord_frame): axis_map = {'x': 0, 'y': 1, 'z': 2} - axis_idx = axis_map.get(axis_field, None) + axis_idx = axis_map[axis_field] # construct xyzlut per sensor from ouster.sdk.core import XYZLut - xyzluts = [XYZLut(s, use_extrinsics=True) for s in ctx.scan_source.sensor_info] + use_extrinsics = coord_frame != "sensor" + dewarp_points = coord_frame == "world" + xyzluts = [XYZLut(s, use_extrinsics=use_extrinsics) for s in ctx.scan_source.sensor_info] for scans in scan_iter(): out = copy.deepcopy(scans) for idx, scan in enumerate(out): @@ -642,7 +650,8 @@ def filter_xyz_iter(scan_iter, axis_field, invalid_value, filtered_fields): # we divide by 1000 since xyzlut values are measured in meters so.filter_xyz(scan, xyzluts[idx], axis_idx, min_v / 1000, max_v / 1000, invalid_value, - filtered_fields=filtered_fields) + filtered_fields=filtered_fields, + dewarp_points=dewarp_points) yield out def filter_field_uv(scan_iter, axis_field, invalid_value, filtered_fields): @@ -664,13 +673,19 @@ def filter_field_iter(scan_iter, axis_field, invalid_value, filtered_fields): yield out axis_field = axis_field.strip() + axis_field_lower = axis_field.lower() + coord_frame = coord_frame.strip().lower() field_list = None if filtered_fields is None else filtered_fields.strip().split(',') - if axis_field.lower() in 'xyz': - ctx.scan_iter = partial(filter_xyz_iter, ctx.scan_iter, axis_field.lower(), - invalid_value, field_list) # type: ignore - elif axis_field.lower() in 'uv': - ctx.scan_iter = partial(filter_field_uv, ctx.scan_iter, axis_field.lower(), + if axis_field_lower not in {"x", "y", "z"} and coord_frame != "body": + raise click.BadParameter("is only supported when filtering by X, Y, or Z.", + param_hint="--coord-frame") + + if axis_field_lower in {"x", "y", "z"}: + ctx.scan_iter = partial(filter_xyz_iter, ctx.scan_iter, axis_field_lower, + invalid_value, field_list, coord_frame) # type: ignore + elif axis_field_lower in {"u", "v"}: + ctx.scan_iter = partial(filter_field_uv, ctx.scan_iter, axis_field_lower, invalid_value, field_list) # type: ignore else: # assume it's a field name ctx.scan_iter = partial(filter_field_iter, ctx.scan_iter, axis_field, @@ -753,6 +768,11 @@ def __iter__(self): if (count > 100).all(): break + if sensor_idx is not None: + if idx != sensor_idx: + continue + idx = 0 + if isinstance(packet, ImuPacket): valid = packet.status() for m_idx, acc in enumerate(packet.accel()): @@ -1426,7 +1446,7 @@ def invoke(self, click_ctx: click.core.Context): @click.option('-s', '--soft-id-check', is_flag=True, default=None, help="Continue parsing lidar packets even if init_id/sn doesn't match with metadata") # noqa @click.option('-t', '--timeout', default=None, type=float, help="Seconds to wait for data [default: 1.0]") -@click.option('-F', '--filter', is_flag=True, help="Drop scans missing data") +@click.option('-f', '--filter', is_flag=True, help="Drop scans with missing data") @click.option('-e', '--extrinsics', type=str, required=False, help="Use this arg to adjust Lidar sensor extrinsics of the source." "\nSupported formats:" @@ -1740,7 +1760,8 @@ def catch_iter(): nonlocal filter if filter: for i in range(0, len(scan)): - if not scan[i].complete(): + profile = scan[i].sensor_info.format.udp_profile_lidar + if not scan[i].complete() and profile != core.UDPProfileLidar.OFF: scan[i] = None # skip rather than return empty array if somehow all were incomplete all_none = True diff --git a/python/src/ouster/cli/plugins/source_localization.py b/python/src/ouster/cli/plugins/source_localization.py index eb857991..c986cb9b 100644 --- a/python/src/ouster/cli/plugins/source_localization.py +++ b/python/src/ouster/cli/plugins/source_localization.py @@ -52,10 +52,6 @@ def make_kiss_localization() -> LocalizationEngine: def localization_iter(scan_source): localization_engine = make_kiss_localization() for scans in scan_source(): - scan = scans[0] - if scan is None: - continue - yield localization_engine.update(scans) # type ignored because generators are tricky to mypy diff --git a/python/src/ouster/cli/plugins/source_mapping.py b/python/src/ouster/cli/plugins/source_mapping.py index e4fd0805..256363f9 100644 --- a/python/src/ouster/cli/plugins/source_mapping.py +++ b/python/src/ouster/cli/plugins/source_mapping.py @@ -66,6 +66,15 @@ def parse_gps_constraints_weights( def save_pointcloud(filename: str, cloud: np.ndarray, ascii: bool = False, field="unknown"): + field_upper = field.upper() + if field_upper == "NONE": + keys_count = 0 + elif field_upper == "RGB": + keys_count = 3 + else: + keys_count = 1 + # Normalize scalar key to 0-1 for PLY output. + key_scale = 1.0 / 255.0 if keys_count == 1 else 1.0 def ply_header(): header = [] @@ -76,17 +85,17 @@ def ply_header(): header.append("property float y") header.append("property float z") # determine keys and normals - keys_count = 3 if field.upper() == 'RGB' else 1 normals_count = cloud.shape[1] - 3 - keys_count if normals_count not in (0, 3): raise ValueError("Unsupported cloud shape for PLY: expected normals to be 0 or 3 columns") - if keys_count == 1: - header.append(f"property float {field}") - else: - header.append("property uchar red") - header.append("property uchar green") - header.append("property uchar blue") + if keys_count > 0: + if keys_count == 1: + header.append(f"property float {field}") + else: + header.append("property uchar red") + header.append("property uchar green") + header.append("property uchar blue") if normals_count == 3: header.append("property float nx") @@ -99,7 +108,6 @@ def ply_header(): def pcd_header(data_mode: str): header = [] # determine fields dynamically - keys_count = 3 if field.upper() == 'RGB' else 1 normals_count = cloud.shape[1] - 3 - keys_count if normals_count not in (0, 3): raise ValueError("Unsupported cloud shape for PCD: expected normals to be 0 or 3 columns") @@ -109,16 +117,17 @@ def pcd_header(data_mode: str): types = ["F", "F", "F"] counts = [1, 1, 1] - if keys_count == 1: - fields.append(field) - sizes.append(4) - types.append("F") - counts.append(1) - else: - fields.append("rgb") - sizes.append(4) - types.append("F") - counts.append(1) + if keys_count > 0: + if keys_count == 1: + fields.append(field) + sizes.append(4) + types.append("F") + counts.append(1) + else: + fields.append("rgb") + sizes.append(4) + types.append("F") + counts.append(1) if normals_count == 3: fields.extend(["nx", "ny", "nz"]) @@ -144,55 +153,76 @@ def color_f2i(value): with open(filename, 'w', encoding='utf-8') as f: f.write(ply_header()) # infer keys and normals - keys_count = 3 if field.upper() == 'RGB' else 1 normals_count = cloud.shape[1] - 3 - keys_count + normals_offset = 3 + keys_count for i in range(cloud.shape[0]): x, y, z = cloud[i, 0], cloud[i, 1], cloud[i, 2] - if keys_count == 1: - key = cloud[i, 3] - if normals_count == 0: - f.write(f"{x} {y} {z} {key}\n") + if keys_count > 0: + if keys_count == 1: + key = cloud[i, 3] * key_scale + if normals_count == 0: + f.write(f"{x} {y} {z} {key}\n") + else: + nx, ny, nz = cloud[i, 4], cloud[i, 5], cloud[i, 6] + f.write(f"{x} {y} {z} {key} {nx} {ny} {nz}\n") else: - nx, ny, nz = cloud[i, 4], cloud[i, 5], cloud[i, 6] - f.write(f"{x} {y} {z} {key} {nx} {ny} {nz}\n") + r = color_f2i(cloud[i, 3]) + g = color_f2i(cloud[i, 4]) + b = color_f2i(cloud[i, 5]) + if normals_count == 0: + f.write(f"{x} {y} {z} {r} {g} {b}\n") + else: + nx, ny, nz = cloud[i, 6], cloud[i, 7], cloud[i, 8] + f.write(f"{x} {y} {z} {r} {g} {b} {nx} {ny} {nz}\n") else: - r = color_f2i(cloud[i, 3]) - g = color_f2i(cloud[i, 4]) - b = color_f2i(cloud[i, 5]) if normals_count == 0: - f.write(f"{x} {y} {z} {r} {g} {b}\n") + f.write(f"{x} {y} {z}\n") else: - nx, ny, nz = cloud[i, 6], cloud[i, 7], cloud[i, 8] - f.write(f"{x} {y} {z} {r} {g} {b} {nx} {ny} {nz}\n") + nx, ny, nz = (cloud[i, normals_offset], + cloud[i, normals_offset + 1], + cloud[i, normals_offset + 2]) + f.write(f"{x} {y} {z} {nx} {ny} {nz}\n") else: with open(filename, 'wb') as f: # type: ignore[assignment] f.write(ply_header().encode("ascii")) # type: ignore[arg-type] # write full float32 buffer (includes normals if present) # if RGB keys present, convert to byte colors in binary case below - keys_count = 3 if field.upper() == 'RGB' else 1 normals_count = cloud.shape[1] - 3 - keys_count - if keys_count == 1: - cloud_bin = cloud.copy().astype(np.float32) - f.write(cloud_bin.tobytes()) # type: ignore[arg-type] + normals_offset = 3 + keys_count + if keys_count > 0: + if keys_count == 1: + cloud_bin = cloud.copy().astype(np.float32) + if key_scale != 1.0: + cloud_bin[:, 3] *= key_scale + f.write(cloud_bin.tobytes()) # type: ignore[arg-type] + else: + # encode RGB as bytes per vertex + for i in range(cloud.shape[0]): + x, y, z = cloud[i, 0], cloud[i, 1], cloud[i, 2] + r = np.uint8(color_f2i(cloud[i, 3])) + g = np.uint8(color_f2i(cloud[i, 4])) + b = np.uint8(color_f2i(cloud[i, 5])) + if normals_count == 3: + nx, ny, nz = float(cloud[i, 6]), float(cloud[i, 7]), float(cloud[i, 8]) + f.write(struct.pack('<3f3B3f', x, y, z, r, g, b, nx, ny, nz)) # type: ignore[arg-type] + else: + f.write(struct.pack('<3f3B', x, y, z, r, g, b)) # type: ignore[arg-type] else: - # encode RGB as bytes per vertex - for i in range(cloud.shape[0]): - x, y, z = cloud[i, 0], cloud[i, 1], cloud[i, 2] - r = np.uint8(color_f2i(cloud[i, 3])) - g = np.uint8(color_f2i(cloud[i, 4])) - b = np.uint8(color_f2i(cloud[i, 5])) - if normals_count == 3: - nx, ny, nz = float(cloud[i, 6]), float(cloud[i, 7]), float(cloud[i, 8]) - f.write(struct.pack('<3f3B3f', x, y, z, r, g, b, nx, ny, nz)) # type: ignore[arg-type] - else: - f.write(struct.pack('<3f3B', x, y, z, r, g, b)) # type: ignore[arg-type] + if normals_count == 0: + cloud_bin = cloud[:, :3].astype(np.float32) + else: + cloud_bin = np.empty((cloud.shape[0], 6), dtype=np.float32) + cloud_bin[:, 0:3] = cloud[:, 0:3].astype(np.float32) + cloud_bin[:, 3:6] = cloud[:, normals_offset:normals_offset + 3].astype( + np.float32) + f.write(cloud_bin.tobytes()) # type: ignore[arg-type] elif filename.endswith(".pcd"): if ascii: with open(filename, 'w', encoding='utf-8') as f: f.write(pcd_header("ascii")) - keys_count = 3 if field.upper() == 'RGB' else 1 normals_count = cloud.shape[1] - 3 - keys_count + normals_offset = 3 + keys_count def pack_rgb_to_float(r, g, b): ri = color_f2i(r) @@ -202,17 +232,26 @@ def pack_rgb_to_float(r, g, b): return struct.unpack(' 0: + if keys_count == 1: + if normals_count == 0: + f.write(f"{x} {y} {z} {cloud[i,3]}\n") + else: + f.write(f"{x} {y} {z} {cloud[i,3]} {cloud[i,4]} {cloud[i,5]} {cloud[i,6]}\n") else: - f.write(f"{x} {y} {z} {cloud[i,3]} {cloud[i,4]} {cloud[i,5]} {cloud[i,6]}\n") + color = pack_rgb_to_float(cloud[i, 3], cloud[i, 4], cloud[i, 5]) + if normals_count == 0: + f.write(f"{x} {y} {z} {np.float32(color)}\n") + else: + f.write(f"{x} {y} {z} {np.float32(color)} {cloud[i,6]} {cloud[i,7]} {cloud[i,8]}\n") else: - color = pack_rgb_to_float(cloud[i, 3], cloud[i, 4], cloud[i, 5]) if normals_count == 0: - f.write(f"{x} {y} {z} {np.float32(color)}\n") + f.write(f"{x} {y} {z}\n") else: - f.write(f"{x} {y} {z} {np.float32(color)} {cloud[i,6]} {cloud[i,7]} {cloud[i,8]}\n") + nx, ny, nz = (cloud[i, normals_offset], + cloud[i, normals_offset + 1], + cloud[i, normals_offset + 2]) + f.write(f"{x} {y} {z} {nx} {ny} {nz}\n") else: with open(filename, 'wb') as f: # type: ignore[assignment] buf = StringIO() @@ -220,28 +259,38 @@ def pack_rgb_to_float(r, g, b): f.write(buf.getvalue().encode("ascii")) # type: ignore[arg-type] # For binary, simply write the full float32 buffer. If RGB present, pack as before - keys_count = 3 if field.upper() == 'RGB' else 1 normals_count = cloud.shape[1] - 3 - keys_count - if keys_count == 3: - # pack rgb into one float channel, preserve normals if present - r = np.clip((255 * cloud[:, 3]).astype(np.uint32), 0, 255) - g = np.clip((255 * cloud[:, 4]).astype(np.uint32), 0, 255) - b = np.clip((255 * cloud[:, 5]).astype(np.uint32), 0, 255) - rgb_u32 = (r << 16) | (g << 8) | b - rgb_f32 = rgb_u32.view(np.float32) + normals_offset = 3 + keys_count + if keys_count > 0: + if keys_count == 3: + # pack rgb into one float channel, preserve normals if present + r = np.clip((255 * cloud[:, 3]).astype(np.uint32), 0, 255) + g = np.clip((255 * cloud[:, 4]).astype(np.uint32), 0, 255) + b = np.clip((255 * cloud[:, 5]).astype(np.uint32), 0, 255) + rgb_u32 = (r << 16) | (g << 8) | b + rgb_f32 = rgb_u32.view(np.float32) + if normals_count == 0: + out = np.empty((cloud.shape[0], 4), dtype=np.float32) + out[:, 0:3] = cloud[:, 0:3].astype(np.float32) + out[:, 3] = rgb_f32 + f.write(out.tobytes()) # type: ignore[arg-type] + else: + out = np.empty((cloud.shape[0], 7), dtype=np.float32) + out[:, 0:3] = cloud[:, 0:3].astype(np.float32) + out[:, 3] = rgb_f32 + out[:, 4:7] = cloud[:, 6:9].astype(np.float32) + f.write(out.tobytes()) # type: ignore[arg-type] + else: + f.write(cloud.astype(np.float32).tobytes()) # type: ignore[arg-type] + else: if normals_count == 0: - out = np.empty((cloud.shape[0], 4), dtype=np.float32) - out[:, 0:3] = cloud[:, 0:3].astype(np.float32) - out[:, 3] = rgb_f32 - f.write(out.tobytes()) # type: ignore[arg-type] + out = cloud[:, :3].astype(np.float32) else: - out = np.empty((cloud.shape[0], 7), dtype=np.float32) + out = np.empty((cloud.shape[0], 6), dtype=np.float32) out[:, 0:3] = cloud[:, 0:3].astype(np.float32) - out[:, 3] = rgb_f32 - out[:, 4:7] = cloud[:, 6:9].astype(np.float32) - f.write(out.tobytes()) # type: ignore[arg-type] - else: - f.write(cloud.astype(np.float32).tobytes()) # type: ignore[arg-type] + out[:, 3:6] = cloud[:, normals_offset:normals_offset + 3].astype( + np.float32) + f.write(out.tobytes()) # type: ignore[arg-type] @click.command @@ -300,10 +349,6 @@ def make_kiss_slam() -> SlamEngine: def slam_iter(scan_source): slam_engine = make_kiss_slam() for scans in scan_source(): - scan = scans[0] - if scan is None: - continue - yield slam_engine.update(scans) # only dump the map once @@ -332,10 +377,13 @@ def slam_iter(scan_source): type=click.Choice(['SIGNAL', 'NEAR_IR', 'REFLECTIVITY', - 'RGB'], + 'RGB', + 'NONE'], case_sensitive=False), default="REFLECTIVITY", - help="Chanfield for output file key value.", show_default=True) + help=("Chanfield for output file key value. Use NONE to omit " + "key fields in output point cloud."), + show_default=True) @click.option('--decimate', required=False, type=bool, default=True, help="Downsample the point cloud to output.", show_default=True) @click.option('--verbose', is_flag=True, default=False, @@ -376,7 +424,13 @@ def point_cloud_convert(ctx: SourceCommandContext, filename: str, prefix: str, already_saved = False empty_pose = True - keys_count = 3 if field.upper() == "RGB" else 1 + field_upper = field.upper() + if field_upper == "NONE": + keys_count = 0 + elif field_upper == "RGB": + keys_count = 3 + else: + keys_count = 1 normals_included = False def key_columns() -> int: @@ -403,7 +457,7 @@ def enable_normals(): axis=1) else: points_keys_total = np.zeros((0, total_columns()), dtype=float) - if keys_to_process.size: + if keys_to_process.shape[0]: keys_to_process = np.append( keys_to_process, np.zeros((keys_to_process.shape[0], 3), dtype=float), @@ -446,7 +500,13 @@ def process_points(points, keys): keys = keys[z_range_filter] if decimate: - points, keys = voxel_downsample(voxel_size, points, keys) + if keys_count == 0 and not normals_included: + points, _ = voxel_downsample( + voxel_size, points, + np.zeros((points.shape[0], 0), dtype=float)) + keys = np.zeros((points.shape[0], 0), dtype=float) + else: + points, keys = voxel_downsample(voxel_size, points, keys) pts_size_after = points.shape[0] points_down_removed += pts_size_before - pts_size_after @@ -469,10 +529,11 @@ def save_file(file_wo_ext: str, outfile_ext: str): LAS_file.z = points_keys_total[:, 2] # LAS file only has intensity but we can use it for other field # value - LAS_file.intensity = points_keys_total[:, 3] + if keys_count != 0: + LAS_file.intensity = points_keys_total[:, 3] + logger.info(f"LAS format only supports the Intensity field. " + f"Saving {field} as the Intensity field.") LAS_file.write(file_wo_ext + outfile_ext) - logger.info(f"LAS format only supports the Intensity field. " - f"Saving {field} as the Intensity field.") points_keys_total = np.zeros((0, total_columns()), dtype=float) @@ -516,7 +577,10 @@ def pc_status_print(): empty_pose = False points = xyzlut_list[idx](scan) - keys = scan.field(field) + if keys_count == 0: + keys = None + else: + keys = scan.field(field) normals_field = None if scan.has_field(ChanField.NORMALS): try: @@ -539,7 +603,10 @@ def pc_status_print(): out_range_row_index = scan.field(ChanField.RANGE) == 0 dewarped_points = dewarp(points, column_poses) filtered_points = dewarped_points[valid_row_index] - filtered_keys = keys[valid_row_index] + if keys_count == 0: + filtered_keys = np.zeros((filtered_points.shape[0], 0), dtype=float) + else: + filtered_keys = keys[valid_row_index] if normals_included: if normals_field is not None: try: @@ -595,7 +662,7 @@ def pc_status_print(): # handle the last part of point cloud or the first part of point cloud if # the size is less than down_sample_steps if not already_saved: - if keys_to_process.size > 0: + if points_to_process.shape[0] > 0: process_points(points_to_process, keys_to_process) if points_sum > 0: @@ -623,7 +690,7 @@ def trajectory_dump(scan_source): with open(filename, "wt") as f: if tum: # TUM format - f.write("#timestamp,x,y,z,qx,qy,qz,qw\n") + f.write("# timestamp tx ty tz qx qy qz qw\n") else: # CSV format f.write("timestamp,x,y,z,qx,qy,qz,qw\n") @@ -638,11 +705,11 @@ def trajectory_dump(scan_source): r = rotation_matrix_to_quaternion(scan_pose[:3, :3]) if tum: - f.write(f"{scan_ts} {p[0]} {p[1]} {p[2]} " - f"{r[1]} {r[2]} {r[3]} {r[0]}\n") + # scan_ts is in nanoseconds; convert to seconds for TUM/evo. + scan_ts_s = float(scan_ts) * 1e-9 + f.write(f"{scan_ts_s:.9f} {p[0]} {p[1]} {p[2]} {r[1]} {r[2]} {r[3]} {r[0]}\n") else: - f.write(f"{scan_ts},{p[0]},{p[1]},{p[2]}," - f"{r[1]},{r[2]},{r[3]},{r[0]}\n") + f.write(f"{scan_ts},{p[0]},{p[1]},{p[2]},{r[1]},{r[2]},{r[3]},{r[0]}\n") yield scans # address generator type later diff --git a/python/src/ouster/cli/plugins/source_replay.py b/python/src/ouster/cli/plugins/source_replay.py index 352dbf49..e509cd13 100644 --- a/python/src/ouster/cli/plugins/source_replay.py +++ b/python/src/ouster/cli/plugins/source_replay.py @@ -10,6 +10,7 @@ import click from datetime import datetime, timezone from ouster.sdk.core import SensorInfo, OperatingMode, UDPProfileLidar, TimestampMode +from ouster.sdk.zone_monitor import ZoneSetOutputFilter from ouster.sdk._bindings.client import PacketType from ouster.sdk.util.parsing import scan_to_packets from ouster.sdk.core.io_types import OusterIoType, io_type @@ -242,13 +243,26 @@ def __init__(self, sensor, http_addr, http_port): self._http_port = http_port def _sensor_info_as_json(sensor_info): - return json.loads(sensor_info.to_json_string()) + sensor_info_json = json.loads(sensor_info.to_json_string()) + if "zone_set" in sensor_info_json: + del sensor_info_json["zone_set"] + if "ouster-sdk" in sensor_info_json: + del sensor_info_json["ouster-sdk"] + return sensor_info_json @app.route('/api/v1/sensor/metadata', methods=['GET']) def get_all_metadata(): result = _sensor_info_as_json(self._sensor.sensor_info) return jsonify(result) + @app.route('/api/v1/zone_monitor/active/zip', methods=['GET']) + def handle_zones(): + zone_set = self._sensor.sensor_info.zone_set + if zone_set is None: + return "{}", 404 + blob = zone_set.to_zip_blob(ZoneSetOutputFilter.STL_AND_ZRB) + return blob, 200 + @app.route('/api/v1/sensor/metadata/', methods=['GET']) def get_sensor_metadata(metadata_type): sensor_info_json = _sensor_info_as_json(self._sensor.sensor_info) @@ -437,6 +451,14 @@ def configuration(): 'type': 'text', 'button': 'Set Local' }, + { + 'name': 'udp_dest_zm', + 'label': 'UDP Destination Address ZM', + 'active': config.udp_dest_zm, + 'staged': config.udp_dest_zm, + 'type': 'text', + 'button': 'Set Local' + }, { 'name': 'udp_port_lidar', 'label': 'UDP Port Lidar', @@ -452,6 +474,14 @@ def configuration(): 'staged': config.udp_port_imu, 'type': 'text', 'button': 'Reset to default' + }, + { + 'name': 'udp_port_zm', + 'label': 'UDP Port ZM', + 'active': config.udp_port_zm, + 'staged': config.udp_port_zm, + 'type': 'text', + 'button': 'Reset to default' } ], 'mode': [ @@ -499,7 +529,7 @@ def configuration(): 'active': config.udp_profile_lidar.name, 'staged': config.udp_profile_lidar.name, 'type': 'dropdown', - 'options': [profile.name for profile in UDPProfileLidar.values] + 'options': [profile.name for profile in UDPProfileLidar.values()] } ], 'timing': [ @@ -509,7 +539,7 @@ def configuration(): 'active': config.timestamp_mode.name, 'staged': config.timestamp_mode.name, 'type': 'dropdown', - 'options': [time_mode.name for time_mode in TimestampMode.values] + 'options': [time_mode.name for time_mode in TimestampMode.values()] }, { 'immutable': True, @@ -619,6 +649,12 @@ def apply_config(): imu_port = request.form.get('udp_port_imu') if imu_port: self._sensor.sensor_info.config.udp_port_imu = int(imu_port) + udp_dest_zm = request.form.get('udp_dest_zm') + if udp_dest_zm: + self._sensor.sensor_info.config.udp_dest_zm = udp_dest_zm + zm_port = request.form.get('udp_port_zm') + if zm_port: + self._sensor.sensor_info.config.udp_port_zm = int(zm_port) operating_mode = request.form.get('operating_mode') if operating_mode: self._sensor.sensor_info.config.operating_mode = OperatingMode.from_string(operating_mode) @@ -681,7 +717,7 @@ class ScanSourceUdpReplay(): def __init__(self, source_url, http_addr, http_port, loop, rate, soft_id_check, lidar_port=-1, imu_port=-1, udp_dest="127.0.0.1", operating_mode="NORMAL", sensor_sn="", - hide_diagnostics=False): + hide_diagnostics=False, zm_port=-1): source_type = io_type(source_url) pkt_src_handler = io_type_handlers[source_type] @@ -701,9 +737,12 @@ def packet_source_factory(): self._sensor_info.config.udp_port_lidar = lidar_port if imu_port != -1: self._sensor_info.config.udp_port_imu = imu_port + if zm_port != -1: + self._sensor_info.config.udp_port_zm = zm_port # should we override the current udp_dest? by default ? self._sensor_info.config.udp_dest = udp_dest - self._sensor_info.sn = sensor_sn if sensor_sn != "" else self._sensor_info.sn + self._sensor_info.config.udp_dest_zm = udp_dest + self._sensor_info.sn = int(sensor_sn) if sensor_sn != "" else self._sensor_info.sn self._sensor_info.config.operating_mode = OperatingMode.from_string(operating_mode) self._show_diagnostics = not hide_diagnostics @@ -761,8 +800,10 @@ def start(self): # grab current config in case it was changed via HTTP operating_mode = self._sensor_info.config.operating_mode udp_dest = self._sensor_info.config.udp_dest + udp_dest_zm = self._sensor_info.config.udp_dest_zm udp_port_lidar = self._sensor_info.config.udp_port_lidar udp_port_imu = self._sensor_info.config.udp_port_imu + udp_port_zm = self._sensor_info.config.udp_port_zm if operating_mode == OperatingMode.OPERATING_NORMAL: if packet.type == PacketType.Lidar: @@ -771,8 +812,11 @@ def start(self): elif packet.type == PacketType.Imu: sock_imu.sendto( packet.buf, (udp_dest, udp_port_imu)) + elif packet.type == PacketType.Zone: + sock_imu.sendto( + packet.buf, (udp_dest_zm, udp_port_zm)) else: - print(f"Unknown packet type {packet.type()}") + print(f"Unknown packet type {packet.type}") # diagnostics if self._show_diagnostics: @@ -784,6 +828,7 @@ def start(self): f"UDP Destination: {udp_dest}", f"UDP Port (Lidar): {udp_port_lidar}", f"UDP Port (IMU): {udp_port_imu}", + f"UDP Port (ZM): {udp_port_zm}", f"Host Time: {ts_format(packet.host_timestamp)}", f"{pkts_count} packets/seconds"]) pkts_count = 0 diff --git a/python/src/ouster/cli/plugins/source_save.py b/python/src/ouster/cli/plugins/source_save.py index 3d74a249..1cd3d5c9 100644 --- a/python/src/ouster/cli/plugins/source_save.py +++ b/python/src/ouster/cli/plugins/source_save.py @@ -48,6 +48,8 @@ def source_save_raw(ctx: SourceCommandContext, prefix: str, dir: str, filename: uri = ctx.source_uri if uri is None: raise RuntimeError("Unexpected condition") + source_list = [url.strip() for url in uri.split(',') if url.strip()] + extension = "" splitfn = os.path.splitext(filename) if splitfn[0][0] == '.' and splitfn[1] == "": @@ -64,7 +66,7 @@ def source_save_raw(ctx: SourceCommandContext, prefix: str, dir: str, filename: # Finally open the appropriate packet source packets: PacketSource - packets = open_packet_source(uri, **ctx.source_options) # type: ignore + packets = open_packet_source(source_list, **ctx.source_options) # type: ignore if extension == "pcap": save_pcap_impl(packets, filename, prefix, dir, raw=True, overwrite=overwrite, @@ -110,15 +112,17 @@ def source_save_pcap(ctx: SourceCommandContext, prefix: str, dir: str, filename: @click.option("--ts", default='packet', help="Timestamp to use for indexing.", type=click.Choice(['packet', 'lidar'])) @click.option("--compression-level", default=1, help="Specifies the level of compression for OSF files. Higher values " "are slower but more space-efficient; lower values are faster but less space-efficient.", type=click.IntRange(0, 9)) -@click.option("--png", is_flag=True, default=False, help="If true, save in legacy PNG compressed OSF format. " - "Useful for backwards compatibility.") +@click.option("--png", is_flag=True, default=False, help="Save using PNG compression instead of the default ZPNG. " + "See --legacy for older SDK compatibility.") +@click.option("--legacy", is_flag=True, default=False, help="Save in a format compatible with older SDKs (0.12-0.15). " + "Uses PNG compression and drops unsupported field types (e.g. CHAR, ZONE_STATE).") @click.option("--split", default=None, type=int, help="Split recordings when they approximately surpass this size in megabytes.") @click.pass_context @source_multicommand(type=SourceCommandType.CONSUMER) def source_save_osf(ctx: SourceCommandContext, prefix: str, dir: str, filename: str, overwrite: bool, ts: str, continue_anyways: bool, compression_level: int, - png: bool, split: Optional[int], **kwargs) -> None: + png: bool, legacy: bool, split: Optional[int], **kwargs) -> None: """Save source as an OSF""" scans = ctx.scan_iter info = ctx.scan_source.sensor_info # type: ignore @@ -135,7 +139,8 @@ def source_save_osf(ctx: SourceCommandContext, prefix: str, dir: str, filename: exit(1) # Initialize osf writer - if png: + # --legacy implies PNG compression + if png or legacy: encoder = osf.Encoder(osf.PngLidarScanEncoder(compression_level)) else: encoder = osf.Encoder(osf.ZPngLidarScanEncoder(compression_level)) @@ -146,33 +151,32 @@ def source_save_osf(ctx: SourceCommandContext, prefix: str, dir: str, filename: dropped_scans = 0 last_ts = [0] * len(info) file_number = 1 - dropped_string_fields: Set[str] = set() + dropped_fields: Set[str] = set() # returns false if we should stop recording need_split = False + # Standard numeric dtype kinds supported by older SDK versions (0.12-0.15) + LEGACY_DTYPE_KINDS = ("u", "i", "f") # unsigned int, signed int, float + def write_osf(scan: LidarScan, index: int): nonlocal wrote_scans, last_ts, dropped_scans, osf_writer, filename, file_number, need_split - scan_to_save = scan - if png: - # `save --png` exists primarily for backwards compatibility. Older SDK/CLI - # versions may not support string-typed ChanFields (e.g. POSITION_STRING), - # so strip any fields with numpy dtype kind 'S'/'U' from the scan. - for ft in scan_to_save.field_types: - try: - if np.dtype(ft.element_type).kind not in ("S", "U"): - continue - except (TypeError, ValueError): + if legacy: + # `save --legacy` is for backwards compatibility with SDK 0.12-0.15. + # Older versions only support standard numeric ChanFieldTypes (UINT*, INT*, FLOAT*). + # Drop fields with newer types like CHAR (kind 'S') or ZONE_STATE (kind 'V'). + for ft in scan.field_types: + if np.dtype(ft.element_type).kind in LEGACY_DTYPE_KINDS: continue name = ft.name - if scan_to_save.has_field(name): - scan_to_save.del_field(name) - dropped_string_fields.add(name) + if scan.has_field(name): + scan.del_field(name) + dropped_fields.add(name) # Set OSF timestamp to the timestamp of the first valid column - scan_ts = scan_to_save.get_first_valid_packet_timestamp() if ts == "packet" \ - else scan_to_save.get_first_valid_column_timestamp() + scan_ts = scan.get_first_valid_packet_timestamp() if ts == "packet" \ + else scan.get_first_valid_column_timestamp() if scan_ts: if scan_ts < last_ts[index]: if continue_anyways: @@ -198,7 +202,7 @@ def write_osf(scan: LidarScan, index: int): file_number += 1 osf_writer = osf.AsyncWriter(filename, info, [], 0, encoder) - osf_writer.save(index, scan_to_save, scan_ts) + osf_writer.save(index, scan, scan_ts) last_ts[index] = scan_ts if split is not None: @@ -230,8 +234,7 @@ def save_iter(): for index, scan in enumerate(s): if scan is None: continue - # Drop invalid lidarscans - if not stop and np.any(scan.status): + if not stop: if not write_osf(scan, index): stop = True yield s @@ -242,10 +245,10 @@ def save_iter(): finally: saved = True osf_writer.close() - if png and dropped_string_fields: + if legacy and dropped_fields: click.echo( - "NOTE: Dropping string ChanFields for backwards compatibility " - f"(--png): fields={sorted(dropped_string_fields)}" + "NOTE: Dropping fields with non-numeric types for backwards compatibility " + f"(--legacy): fields={sorted(dropped_fields)}" ) ctx.scan_iter = save_iter # type: ignore @@ -620,7 +623,7 @@ def do_split(): elif isinstance(packet, ImuPacket): save_packet(idx, packet, metadata[idx].config.udp_port_imu) elif isinstance(packet, ZonePacket): - save_packet(idx, packet, metadata[idx].config.zm.port) + save_packet(idx, packet, metadata[idx].config.udp_port_zm) if duration is not None: if end_time is None: @@ -661,7 +664,7 @@ def save_iter(): elif isinstance(packet, ImuPacket): save_packet(idx, packet, metadata[idx].config.udp_port_imu) elif isinstance(packet, ZonePacket): - save_packet(idx, packet, metadata[idx].config.zm.port) + save_packet(idx, packet, metadata[idx].config.udp_port_zm) # only split after saving a whole scan to prevent a scan # ending up between two files diff --git a/python/src/ouster/cli/plugins/templates/disclaimer.html b/python/src/ouster/cli/plugins/templates/disclaimer.html index 2985b663..d0bdc7cf 100644 --- a/python/src/ouster/cli/plugins/templates/disclaimer.html +++ b/python/src/ouster/cli/plugins/templates/disclaimer.html @@ -90,8 +90,10 @@

Ouster Sensor Emulation Limitation

The emulator allows the change of the following list of configuration options (All other settings are read-only):

* UDP Destination Address (udp_dest)
-
* UDP Lidar Port (lidar_port)
-
* UDP IMU Port (imu_port)
+
* UDP ZM Destination Address (udp_dest_zm)
+
* UDP Lidar Port (udp_port_lidar)
+
* UDP IMU Port (udp_port_imu)
+
* UDP ZM Port (udp_port_zm)
* Operating Mode (operating_mode)

diff --git a/python/src/ouster/sdk/_bindings/client.pyi b/python/src/ouster/sdk/_bindings/client.pyi index f7d097dd..55ffd38e 100644 --- a/python/src/ouster/sdk/_bindings/client.pyi +++ b/python/src/ouster/sdk/_bindings/client.pyi @@ -3705,6 +3705,9 @@ Overloaded function. """ ... + def __setitem__(self, index: int, value: Optional[LidarScan]) -> None: + ... + def __len__(self) -> int: """__len__(self: ouster.sdk._bindings.client.LidarScanSet) -> int """ diff --git a/python/src/ouster/sdk/_bindings/mapping.pyi b/python/src/ouster/sdk/_bindings/mapping.pyi index b75e60ec..0004f95e 100644 --- a/python/src/ouster/sdk/_bindings/mapping.pyi +++ b/python/src/ouster/sdk/_bindings/mapping.pyi @@ -54,6 +54,7 @@ class Constraint: Get the unique constraint ID. Returns 0 for non-user constraints. + IDs are assigned when constraint objects are constructed. Returns: int: The constraint ID, or 0 if not a user-added constraint. @@ -428,13 +429,14 @@ Overloaded function. This is the new unified API for adding constraints. Use the constraint class constructors to create constraints, then pass them to this method. - The constraint will be assigned a unique ID for later removal if needed. + The constraint must already have a unique ID for later removal. + Adding a constraint with a duplicate ID will fail. Args: constraint: A constraint object created by one of the constraint constructors. Returns: - int: The unique constraint ID assigned to the added constraint. + int: The unique constraint ID of the added constraint. Raises: RuntimeError: If the constraint cannot be added. @@ -916,4 +918,4 @@ class DeskewMethodFactory: DeskewMethod: A new instance of the specified deskew method. """ - ... \ No newline at end of file + ... diff --git a/python/src/ouster/sdk/_bindings/viz.pyi b/python/src/ouster/sdk/_bindings/viz.pyi index a1fbb4c3..9ce5fd45 100644 --- a/python/src/ouster/sdk/_bindings/viz.pyi +++ b/python/src/ouster/sdk/_bindings/viz.pyi @@ -797,6 +797,13 @@ class Label: """ ... + +class PointVizNotRunningError(Exception): + """Exception raised when attempting to run PointViz methods while not running.""" + def __init__(self) -> None: + ... + + class PointViz: def __init__(self, name: str, fix_aspect: bool=..., window_width: int=..., window_height: int=..., maximized: bool=..., fullscreen: bool=..., borderless: bool=...) -> None: diff --git a/python/src/ouster/sdk/core/scan_ops.py b/python/src/ouster/sdk/core/scan_ops.py index 51938347..3c08af52 100644 --- a/python/src/ouster/sdk/core/scan_ops.py +++ b/python/src/ouster/sdk/core/scan_ops.py @@ -1,56 +1,89 @@ from typing import List, Union, Callable, Optional import copy import numpy as np -from ouster.sdk.core import LidarScan, SensorInfo, FieldClass +from ouster.sdk.core import LidarScan, SensorInfo, FieldClass, dewarp from ouster.sdk.core.data import destagger -def clip(scan: LidarScan, fields: List[str], lower: int, upper: int, invalid: int = 0) -> None: +def _resolve_pixel_fields(scan: LidarScan, + filtered_fields: Optional[List[str]]) -> List[str]: + """Resolve which scan fields to operate on, restricted to PIXEL_FIELD types. + + Rules: + - If filtered_fields is None: return all pixel fields present in the scan. + - If filtered_fields is provided: validate that any present requested fields are + pixel fields; non-pixel fields raise ValueError. + (Missing fields are ignored to avoid failing mid-stream when fields vary.) + """ + pixel_fields = {ft.name for ft in scan.field_types + if ft.field_class == FieldClass.PIXEL_FIELD} + + requested = filtered_fields if filtered_fields is not None else list(scan.fields) + present = [f for f in requested if scan.has_field(f)] + + non_pixel = [f for f in present if f not in pixel_fields] + if filtered_fields is not None and non_pixel: + raise ValueError( + f"Only PIXEL_FIELD scan fields are supported here; requested non-pixel fields: {non_pixel}" + ) + + return [f for f in present if f in pixel_fields] + + +def clip(scan: LidarScan, fields: List[str], lower: float, upper: float, + invalid: int = 0) -> None: """ - limits the values of the specified set of fields to within the range = [lower, upper], any value - that exceeds this range is replaced by the supplied invalid value (default is zero) + Limits the values of the specified set of pixel fields to within the range + [lower, upper]. Any value outside this range is replaced by the supplied + invalid value (default is zero). """ - if not fields: - fields = list(scan.fields) - for f in fields: - if scan.has_field(f): - m = scan.field(f) - m[(m < lower) | (m > upper)] = invalid + # PIXEL_FIELD targets only (default: all pixel fields; explicit: requested pixel fields). + fields_to_clip = _resolve_pixel_fields(scan, fields if fields else None) + for f in fields_to_clip: + m = scan.field(f) + m[(m < lower) | (m > upper)] = invalid -def filter_field(scan: LidarScan, field: str, lower: int, upper: int, invalid: int = 0, +def filter_field(scan: LidarScan, field: str, lower: float, upper: float, invalid: int = 0, filtered_fields: Optional[List[str]] = None) -> None: """ - Filters out scan fields based on the specified axis and range. - Values that falls in the range [lower, upper] are replaced by - the supplied invalid value (default is zero). + Filters scan pixel fields based on the values of another pixel field. + Pixels whose filter field values fall in the range [lower, upper] are + replaced by the supplied invalid value (default is zero). Parameters: - scan: LidarScan - - field: str; the field to be used as the filter + - field: str; the pixel field to be used as the filter mask source - lower: float; lower bound - upper: float; upper bound - invalid: int; the invalid value to use default is 0 - filtered_fields: Optional[List[str]]; an optional list of fields to filter """ + # PIXEL_FIELD targets only (default: all pixel fields; explicit: requested pixel fields). + fields_to_filter = _resolve_pixel_fields(scan, filtered_fields) + m = scan.field(field) + if m.shape[0] != scan.h or m.shape[1] != scan.w: + raise ValueError( + f"filter_field requires a pixel field with shape (h, w) to build a mask; " + f"got field '{field}' with shape {m.shape} while scan size is ({scan.h}, {scan.w})" + ) + filtered_pts = (m >= lower) & (m <= upper) - filtered_fields = filtered_fields or list(scan.fields) - for target_f in filtered_fields: - if scan.has_field(target_f): - scan.field(target_f)[filtered_pts] = invalid + for target_f in fields_to_filter: + scan.field(target_f)[filtered_pts] = invalid def filter_uv(scan: LidarScan, coord_2d: str, lower: Union[int, float], upper: Union[int, float], invalid: int = 0, filtered_fields: Optional[List[str]] = None) -> None: """ - Filters the scan based on the specified image axis. - Values that falls in the range [lower, upper] are replaced by - the supplied invalid value (default is zero). + Filters the scan based on the specified image axis ('u' or 'v'). + Pixel values that fall within the specified index range [lower, upper) + are replaced by the supplied invalid value (default is zero). Parameters: - scan: LidarScan - - field: str; the field to be used as the filter + - coord_2d: str; image axis to filter ('u' rows, 'v' columns) - lower: Union[int, float]; lower bound if float it is assumed a percentage - upper: Union[int, float]; upper bound if float it is assumed a percentage - invalid: int; the invalid value to use default is 0 @@ -66,7 +99,7 @@ def _interpret_as_int(val: float) -> int: return 0 if val == float("inf"): return coord_size - if val > 0 and val < 1: + if 0 <= val <= 1: return int(coord_size * val) return int(val) @@ -81,68 +114,96 @@ def _interpret_as_int(val: float) -> int: if lower > upper: raise ValueError(f"lower == {lower} must be less than upper == {upper}") - filtered_fields = filtered_fields or list(scan.fields) + # PIXEL_FIELD targets only (default: all pixel fields; explicit: requested pixel fields). + fields_to_filter = _resolve_pixel_fields(scan, filtered_fields) + u_slice, v_slice = (slice(lower, upper), slice(None)) if coord_2d == 'u' \ else (slice(None), slice(lower, upper)) - for target_f in filtered_fields: - if scan.has_field(target_f): - if coord_2d == 'v': - # destaggering mainly affects the v axis - result = destagger(scan.sensor_info, scan.field(target_f)) - result[u_slice, v_slice] = invalid - scan.field(target_f)[:] = destagger(scan.sensor_info, result, inverse=True) - else: - scan.field(target_f)[u_slice, v_slice] = invalid + for target_f in fields_to_filter: + if coord_2d == 'v': + # destaggering mainly affects the v axis + result = destagger(scan.sensor_info, scan.field(target_f)) + result[u_slice, v_slice] = invalid + scan.field(target_f)[:] = destagger(scan.sensor_info, result, inverse=True) + else: + scan.field(target_f)[u_slice, v_slice] = invalid def filter_xyz(scan: LidarScan, xyzlut: Callable[[Union[LidarScan, np.ndarray]], np.ndarray], axis_idx: int, lower: float = float("-inf"), upper: float = float("inf"), - invalid: int = 0, filtered_fields: Optional[List[str]] = None) -> None: + invalid: int = 0, filtered_fields: Optional[List[str]] = None, + dewarp_points: bool = False) -> None: """ - Filters the scan based on the specified axis and range. Values below the lower bound or above the upper - bound are replaced by the supplied invalid value (default is zero) + Filters the scan based on spatial coordinates (X, Y, or Z). Points with coordinates inside + the specified range [lower, upper] are replaced with the invalid value (default is zero). + + Only PIXEL_FIELD types (spatial/image-like data such as RANGE, SIGNAL, REFLECTIVITY) are + filtered. Non-spatial fields (IMU, GNSS position, etc.) are preserved. Parameters: - scan: LidarScan - xyzlut: Callable[[Union[LidarScan, np.ndarray]], np.ndarray] - - axis_idx: int; can be 0, 1, or 2 + - axis_idx: int; spatial axis to filter (0=X, 1=Y, 2=Z) - lower: float; lower bound - upper: float; upper bound - - invalid: int; the invalid value to use default is 0 - - filtered_fields: Optional[List[str]]; an optional list of fields to filter + - invalid: int; the invalid value to use (default is 0) + - filtered_fields: Optional[List[str]]; specific fields to filter (if None, filters all PIXEL_FIELD types) + - dewarp_points: bool; if True, dewarp XYZ points using scan.pose """ if axis_idx < 0 or axis_idx > 2: raise ValueError(f"axis_idx == {axis_idx} must be in the range [0, 2]") - for range_f in ['RANGE', 'RANGE2']: - if not scan.has_field(range_f): - continue - pts = xyzlut(scan.field(range_f)) - below_min = pts[:, :, axis_idx] >= lower - above_max = pts[:, :, axis_idx] <= upper - filtered_pts = below_min & above_max - filtered_fields = filtered_fields or list(scan.fields) - fields = set(filtered_fields) - (set(['RANGE', 'RANGE2']) - set([range_f])) - for target_f in fields: - if scan.has_field(target_f): - scan.field(target_f)[filtered_pts] = invalid + # PIXEL_FIELD targets only (default: all pixel fields; explicit: requested pixel fields). + fields_to_filter = _resolve_pixel_fields(scan, filtered_fields) + + def _xyz_points(field_name: str) -> np.ndarray: + points = xyzlut(scan.field(field_name)) + if dewarp_points: + return dewarp(points, scan.pose) + return points + + # Compute spatial masks from range fields + range_mask = None + range2_mask = None + + if scan.has_field('RANGE'): + pts = _xyz_points('RANGE') + range_mask = (pts[:, :, axis_idx] >= lower) & (pts[:, :, axis_idx] <= upper) + + if scan.has_field('RANGE2'): + pts = _xyz_points('RANGE2') + range2_mask = (pts[:, :, axis_idx] >= lower) & (pts[:, :, axis_idx] <= upper) + + if range_mask is None and range2_mask is None: + return + + # Second-return fields (RANGE2, SIGNAL2, etc.) use RANGE2 coordinates + # All other fields use RANGE coordinates + second_return_fields = {'RANGE2', 'SIGNAL2', 'REFLECTIVITY2', 'FLAGS2'} + + for field in fields_to_filter: + if field in second_return_fields: + mask = range2_mask if range2_mask is not None else range_mask + else: + mask = range_mask if range_mask is not None else range2_mask + scan.field(field)[mask] = invalid def mask(scan: LidarScan, fields: List[str], mask: np.ndarray) -> None: """ - applies a mask/filter to all fields of the LidarScan - mask should be of the same as size scan.PIXEL_FIELD + Applies a boolean mask to scan pixel fields. + + mask should have shape (scan.h, scan.w). Pixels where mask == 0 are set to 0. """ if mask.shape[0] != scan.h or mask.shape[1] != scan.w: raise ValueError(f"Used mask size {mask.shape} doesn't match scan size" " ({scan.h}, {scan.w}") - if not fields: - fields = list(scan.fields) + # PIXEL_FIELD targets only (default: all pixel fields; explicit: requested pixel fields). + fields_to_mask = _resolve_pixel_fields(scan, fields if fields else None) masked_indices = np.where(mask == 0) - for f in fields: - if scan.has_field(f): - scan.field(f)[masked_indices] = 0 + for f in fields_to_mask: + scan.field(f)[masked_indices] = 0 def _reduce_factor_to_slice(factor: int, height: int) -> slice: @@ -190,7 +251,7 @@ def reduce_by_factor(scan: LidarScan, factor: int, raise ValueError(f"factor == {factor} must be a divisor of {scan.h}") scan_h = scan.h // factor - result = LidarScan(scan_h, scan.w, scan.field_types) + result = LidarScan(scan_h, scan.w, scan.field_types, scan.sensor_info.format.columns_per_packet) # copy std properties result.frame_id = scan.frame_id result.frame_status = scan.frame_status diff --git a/python/src/ouster/sdk/examples/viz_image_events.py b/python/src/ouster/sdk/examples/viz_image_events.py index 174800d8..0e0048cd 100644 --- a/python/src/ouster/sdk/examples/viz_image_events.py +++ b/python/src/ouster/sdk/examples/viz_image_events.py @@ -28,7 +28,6 @@ def update_window_size_label(position: Tuple[float, float], text: str): - global window_size_label window_size_label.set_text(text) window_size_label.set_position(*position) diff --git a/python/src/ouster/sdk/viz/__init__.py b/python/src/ouster/sdk/viz/__init__.py index 9def7c14..d6935d8d 100644 --- a/python/src/ouster/sdk/viz/__init__.py +++ b/python/src/ouster/sdk/viz/__init__.py @@ -9,6 +9,7 @@ from ouster.sdk._bindings.viz import MouseButton from ouster.sdk._bindings.viz import MouseButtonEvent from ouster.sdk._bindings.viz import EventModifierKeys +from ouster.sdk._bindings.viz import PointVizNotRunningError from ouster.sdk._bindings.viz import PointViz from ouster.sdk._bindings.viz import Cloud from ouster.sdk._bindings.viz import Image diff --git a/python/src/ouster/sdk/viz/core.py b/python/src/ouster/sdk/viz/core.py index c9222dab..d39da0f5 100644 --- a/python/src/ouster/sdk/viz/core.py +++ b/python/src/ouster/sdk/viz/core.py @@ -23,7 +23,7 @@ from ouster.sdk import core from ouster.sdk.core import LidarScan, ChanField, LidarScanSet, ScanSource, SensorInfo -from ouster.sdk._bindings.viz import (PointViz, Cloud, Image, Cuboid, Label, WindowCtx, Camera, +from ouster.sdk._bindings.viz import (PointVizNotRunningError, PointViz, Cloud, Image, Cuboid, Label, WindowCtx, Camera, TargetDisplay, add_default_controls, MouseButton, MouseButtonEvent, EventModifierKeys) from .util import push_point_viz_handler, BoundMethod from ouster.sdk.viz.model import VizExtraMode, LidarScanVizModel @@ -238,25 +238,45 @@ def add_field(field_name, img, color, sensor_idx): if first_valid is None: return # No valid scans with this field in the buffer measurements_per_scan = first_valid.field(field_name).shape[0] - all_scan_values = np.zeros((measurements_per_scan * len(scans),)) + # Use NaN for missing scans so gaps appear instead of false zeros + all_scan_values = np.full((measurements_per_scan * len(scans),), np.nan) self._imu_acc_scale[sensor_idx][field_name] = 1.0 for idx, scan in enumerate(scans): scan = scans[idx][sensor_idx] if scan is None: - continue # Leave zeros for missing scans + continue # NaN values left for missing scans create visual gaps field_values = scan.field(field_name)[::-1] field_value_magnitudes = np.linalg.norm(field_values, axis=1) - new_scale_amt = 1.0 / np.max(field_value_magnitudes) - if self._imu_acc_scale[sensor_idx][field_name] > new_scale_amt: - self._imu_acc_scale[sensor_idx][field_name] = new_scale_amt + # Mark invalid IMU measurements as missing. + if scan.has_field('IMU_STATUS'): + imu_status = scan.field('IMU_STATUS')[::-1] + field_value_magnitudes = field_value_magnitudes.astype(float) + field_value_magnitudes[(imu_status & 0x1) == 0] = np.nan + valid = field_value_magnitudes[~np.isnan(field_value_magnitudes)] + max_magnitude = np.max(valid) if len(valid) > 0 else 0 + if max_magnitude > 0: + new_scale_amt = 1.0 / max_magnitude + if self._imu_acc_scale[sensor_idx][field_name] > new_scale_amt: + self._imu_acc_scale[sensor_idx][field_name] = new_scale_amt all_scan_values[idx * measurements_per_scan:(idx + 1) * measurements_per_scan] = field_value_magnitudes chunk_w = img_w * len(scans) // self._imu_viz_num_scans x_axis_values = np.linspace(0, len(all_scan_values) - 1, chunk_w) - resampled_field = np.interp(x_axis_values, np.arange(len(all_scan_values)), all_scan_values) - scaled_resampled_field = (img_h - 1 - resampled_field * (img_h - 1) + # Interpolate over valid data only (np.interp can't handle NaN) + valid_mask = ~np.isnan(all_scan_values) + valid_indices = np.where(valid_mask)[0] + if len(valid_indices) == 0: + return + resampled_field = np.interp(x_axis_values, valid_indices, all_scan_values[valid_mask]) + # Restore NaN for pixels that map into gap regions + nearest_orig = np.clip(np.round(x_axis_values).astype(int), 0, len(all_scan_values) - 1) + resampled_field[~valid_mask[nearest_orig]] = np.nan + # Only plot pixels that have valid data + valid = ~np.isnan(resampled_field) + scaled = (img_h - 1 - resampled_field[valid] * (img_h - 1) * self._imu_acc_scale[sensor_idx][field_name]).astype(int) - indices = np.column_stack((scaled_resampled_field, np.arange(chunk_w))).T + pixel_x = np.arange(chunk_w)[valid] + indices = np.column_stack((scaled, pixel_x)).T img[indices[0], img_w - indices[1] - 1] = color for sensor_idx, sensor in enumerate(self._model._sensors): @@ -834,7 +854,11 @@ def _update_multi_viz_osd(self): if osd_str_extra: osd_str_extra += "\n" - first_frame_ts = min([s.get_first_valid_packet_timestamp() for s in self._scans if s]) * 1e-9 + valid_scans = [s for s in self._scans if s] + if not valid_scans: + return # Skip update if no scans available yet + + first_frame_ts = min([s.get_first_valid_packet_timestamp() for s in valid_scans]) * 1e-9 if self._first_frame_ts is None: self._first_frame_ts = first_frame_ts frame_ts = first_frame_ts - self._first_frame_ts # show relative time @@ -1390,19 +1414,22 @@ def toggle_img_recording(self) -> None: def screenshot(self, file_path: Optional[str] = None) -> None: file_name: str - if self._screenshot_resolution is None: - # Handle the 'None' case (default) - file_name = self._viz.save_screenshot(file_path or "") - elif isinstance(self._screenshot_resolution, float): - # Handle the scale factor case - scale_factor = self._screenshot_resolution - file_name = self._viz.save_screenshot(file_path or "", scale_factor) - else: - # Handle the tuple case (width, height) - width, height = self._screenshot_resolution - file_name = self._viz.save_screenshot(file_path or "", width, height) - if file_name: - print(f"Saved screenshot to: {file_name}") + try: + if self._screenshot_resolution is None: + # Handle the 'None' case (default) + file_name = self._viz.save_screenshot(file_path or "") + elif isinstance(self._screenshot_resolution, float): + # Handle the scale factor case + scale_factor = self._screenshot_resolution + file_name = self._viz.save_screenshot(file_path or "", scale_factor) + else: + # Handle the tuple case (width, height) + width, height = self._screenshot_resolution + file_name = self._viz.save_screenshot(file_path or "", width, height) + if file_name: + print(f"Saved screenshot to: {file_name}") + except PointVizNotRunningError: + pass _screenshot_resolutions: List[float] = [0.5, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0] @@ -1554,14 +1581,17 @@ def _process(self, seekable: _Seekable) -> None: if self._video_format == "png": self.screenshot("") else: - if self._screenshot_resolution is None: - pix = self._viz.get_screenshot() - elif isinstance(self._screenshot_resolution, float): - pix = self._viz.get_screenshot(self._screenshot_resolution) - else: - width, height = self._screenshot_resolution - pix = self._viz.get_screenshot(width, height) - self._images.append((PILImage.fromarray(pix), scan_ts)) + try: + if self._screenshot_resolution is None: + pix = self._viz.get_screenshot() + elif isinstance(self._screenshot_resolution, float): + pix = self._viz.get_screenshot(self._screenshot_resolution) + else: + width, height = self._screenshot_resolution + pix = self._viz.get_screenshot(width, height) + self._images.append((PILImage.fromarray(pix), scan_ts)) + except PointVizNotRunningError: + pass except StopIteration: if not self._paused and not self._on_eof == "stop": break @@ -1588,11 +1618,10 @@ def scans_per_sec(self) -> float: else: return 0.0 - def _save_gif(self) -> None: + def _save_gif(self, filename=f"viz_gif_{datetime.now().strftime('%Y-%m-%d_%H-%M-%S')}.gif") -> None: if len(self._images) == 0: return - filename = f"viz_gif_{datetime.now().strftime('%Y-%m-%d_%H-%M-%S')}.gif" print("Saving gif to " + filename) start = self._images[0][0] rate = SimpleViz._playback_rates[self._rate_ind] @@ -1606,6 +1635,8 @@ def _save_gif(self) -> None: for i in range(1, len(self._images)): images.append(self._images[i][0]) dt = self._images[i][1] - self._images[i - 1][1] + if dt <= 0: + dt = self._lidar_frame_period() durations.append(dt * 1000 / rate) durations.append(durations[-1]) # assume last frame has same duration as the one before diff --git a/python/src/ouster/sdk/viz/model.py b/python/src/ouster/sdk/viz/model.py index 80fa31ad..ce6ab561 100644 --- a/python/src/ouster/sdk/viz/model.py +++ b/python/src/ouster/sdk/viz/model.py @@ -645,7 +645,9 @@ def update_zone_occupancy_cloud_and_image_masks(self, scan: Optional[core.LidarS bit = 0x1 << z_idx mask[(occupancy & bit) > 0] = triggered_live_zone_color(self._zone_palette, zone_id) else: - mask[occupancy > 0] = (1, 0, 1, 1) + for z_idx in range(16): # TODO[tws] max live zones constant + bit = 0x1 << z_idx + mask[(occupancy & bit) > 0] = triggered_live_zone_color(self._zone_palette, z_idx) destaggered_mask = core.destagger(self._meta, mask) self._cloud_masks[0] = mask for image in self._images: @@ -803,6 +805,8 @@ def select_image_mode(self, i: int, name: str) -> bool: def cycle_image_mode(self, i: int, direction: int): """Updates the currently selected image mode from the list of all available cloud modes.""" all_image_mode_names = self.sorted_image_mode_names() + if len(all_image_mode_names) == 0: + return self._image_mode_ind[i] = (self._image_mode_ind[i] + direction) % len(all_image_mode_names) self._image_mode_names[i] = all_image_mode_names[self._image_mode_ind[i]] # TODO[tws] optimize update image palettes diff --git a/python/src/ouster/sdk/viz/view_mode.py b/python/src/ouster/sdk/viz/view_mode.py index b7f4952f..175baa78 100644 --- a/python/src/ouster/sdk/viz/view_mode.py +++ b/python/src/ouster/sdk/viz/view_mode.py @@ -174,8 +174,7 @@ def _prepare_data(self, f = self._fields[return_num] field = ls.field(f) - key_data = field if field.dtype == np.float32 else field.astype( - np.float32) + key_data = field.astype(np.float32, copy=True) if self._buc: self._buc(key_data) @@ -244,13 +243,13 @@ def _prepare_data(self, if np.ndim(field) != 3 and field.shape != 3: raise TypeError(f"Unsupport field shape: {field.shape}") if field.dtype == np.uint8: - key_data = (field / (2**8 - 1)).astype(np.float32) + key_data = (field / (2**8 - 1)).astype(np.float32, copy=True) elif field.dtype == np.uint16: - key_data = (field / (2**16 - 1)).astype(np.float32) + key_data = (field / (2**16 - 1)).astype(np.float32, copy=True) elif field.dtype == np.float32: key_data = field elif field.dtype == np.float64: - key_data = field.astype(np.float32) + key_data = field.astype(np.float32, copy=True) else: raise TypeError(f"Unsupport field type {field.dtype}") @@ -373,7 +372,7 @@ def _prepare_data(self, return None f = self._fields[return_num] - refl_data = ls.field(f).astype(np.float32) + refl_data = ls.field(f).astype(np.float32, copy=True) if self._normalized_refl: refl_data /= 255.0 else: diff --git a/python/src/ouster/sdk/viz/xxxxx b/python/src/ouster/sdk/viz/xxxxx deleted file mode 100644 index 863358f0..00000000 --- a/python/src/ouster/sdk/viz/xxxxx +++ /dev/null @@ -1,99 +0,0 @@ -The current date and time is: 2025-12-17 13:57:28 -ouster_sdk version: 0.16.0.dev594+mr.1462.dba7094 -kiss-icp version: 1.2.3 -Start #1 process: handheld_slam.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-1-128 682419000011 a1550f210a78a6f7db3bf0ca4836be0618137405 1024x10] -Avg diff: 0.90% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 94.25 MB while old PLY size: 104 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.0652844499558798 while old loop score: 0.0674. Status: SUCCESS -Job #1 handheld_slam.osf SLAM execution time: 31 seconds -Job #1 handheld_slam.osf end-to-end time: 134 seconds -Start #2 process: os0_4096x5_3.2_2741_roof_and_engineering_loop_handheld.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-0-128 122321000098 bcf3fc9ba01dbff062ffee160c6e31188ff71f3a 4096x5] -Avg diff: 37.60% while the threshold: 7.60%. Status: FAIL -New PLY size: 102.53 MB while old PLY size: 117 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.4065485617717211 while old loop score: 1.0694031. Status: SUCCESS -Job #2 os0_4096x5_3.2_2741_roof_and_engineering_loop_handheld.osf SLAM execution time: 64 seconds -Job #2 os0_4096x5_3.2_2741_roof_and_engineering_loop_handheld.osf end-to-end time: 248 seconds -Start #3 process: os0_4096x5_3.2_350_loop_handheld.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-0-128 122321000098 bcf3fc9ba01dbff062ffee160c6e31188ff71f3a 4096x5] -Avg diff: 6.80% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 205.94 MB while old PLY size: 237 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.012782290554988082 while old loop score: 0.0153361. Status: SUCCESS -Job #3 os0_4096x5_3.2_350_loop_handheld.osf SLAM execution time: 83 seconds -Job #3 os0_4096x5_3.2_350_loop_handheld.osf end-to-end time: 357 seconds -Start #4 process: os0_4096x5_3.2_downtown_walking_loop_handheld.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-0-128 122321000098 bcf3fc9ba01dbff062ffee160c6e31188ff71f3a 4096x5] -Avg diff: 32.30% while the threshold: 7.60%. Status: FAIL -New PLY size: 1396.40 MB while old PLY size: 1589 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.95649187557617 while old loop score: 1.4315839. Status: SUCCESS -Job #4 os0_4096x5_3.2_downtown_walking_loop_handheld.osf SLAM execution time: 205 seconds -Job #4 os0_4096x5_3.2_downtown_walking_loop_handheld.osf end-to-end time: 946 seconds -Start #5 process: os0_office.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-0-128 122323001641 v3.1.0 1024x10] -Avg diff: 0.50% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 174.30 MB while old PLY size: 176 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.014575614688635944 while old loop score: 0.0215. Status: SUCCESS -Job #5 os0_office.osf SLAM execution time: 37 seconds -Job #5 os0_office.osf end-to-end time: 161 seconds -Start #6 process: os0_office_low_bw.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-0-128 122323001641 v3.1.0 1024x10] -Avg diff: 0.30% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 164.85 MB while old PLY size: 166 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.006051682083630196 while old loop score: 0.0061. Status: SUCCESS -Job #6 os0_office_low_bw.osf SLAM execution time: 35 seconds -Job #6 os0_office_low_bw.osf end-to-end time: 141 seconds -Start #7 process: os1_office.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-1-128 122345000030 v3.1.0 1024x10] -Avg diff: 0.80% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 135.33 MB while old PLY size: 136 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.1457030031839098 while old loop score: 0.149. Status: SUCCESS -Job #7 os1_office.osf SLAM execution time: 38 seconds -Job #7 os1_office.osf end-to-end time: 185 seconds -Start #8 process: os1_office_1024_20.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-1-128 122345000030 v3.1.0 1024x20] -Avg diff: 0.40% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 176.55 MB while old PLY size: 179 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.005183361349830752 while old loop score: 0.0049. Status: FAIL -Job #8 os1_office_1024_20.osf SLAM execution time: 55 seconds -Job #8 os1_office_1024_20.osf end-to-end time: 310 seconds -Start #9 process: os1_office_2048.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-1-128 122345000030 v3.1.0 2048x10] -Avg diff: 0.60% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 147.41 MB while old PLY size: 149 MB. Status: SUCCESS -Loop Type Data -New loop score: 0.003856473564583278 while old loop score: 0.0034. Status: FAIL -Job #9 os1_office_2048.osf SLAM execution time: 50 seconds -Job #9 os1_office_2048.osf end-to-end time: 307 seconds -Start #10 process: outdoor_circle.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-1-128 992034000673 v2.1.0-rc.3 1024x10] -Avg diff: 9.50% while the threshold: 7.60%. Status: FAIL -New PLY size: 966.81 MB while old PLY size: 968 MB. Status: SUCCESS -Loop Type Data -New loop score: 2.3854990660538125 while old loop score: 2.559. Status: SUCCESS -Job #10 outdoor_circle.osf SLAM execution time: 48 seconds -Job #10 outdoor_circle.osf end-to-end time: 237 seconds -Start #11 process: sample.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-1-128 122247000750 v3.0.1 4096x5] -Avg diff: 5.70% while the threshold: 7.60%. Status: SUCCESS -New PLY size: 1071.89 MB while old PLY size: 1073 MB. Status: SUCCESS -Loop Type Data -Job #11 sample.osf SLAM execution time: 71 seconds -Job #11 sample.osf end-to-end time: 370 seconds -Start #12 process: swagon_slam.osf -SensorInfo: [ouster.sdk.client.SensorInfo OS-0-128 122217001397 v2.4.0 1024x10, ouster.sdk.client.SensorInfo OS-1-128 122207003269 v2.4.0 1024x10, ouster.sdk.client.SensorInfo OS-0-128 122217003234 v2.4.0 1024x10, ouster.sdk.client.SensorInfo OS-1-128 122208001355 v2.4.0 1024x10, ouster.sdk.client.SensorInfo OS-2-128 992239000002 v2.4.0 1024x10, ouster.sdk.client.SensorInfo OS-2-128 992238000267 v2.4.0 1024x10, ouster.sdk.client.SensorInfo OS-0-128 122235000184 v2.4.0 1024x10, ouster.sdk.client.SensorInfo OS-0-128 122235000278 v2.3.1 1024x10] -Avg diff: 23.00% while the threshold: 7.60%. Status: FAIL -New PLY size: 4104.70 MB while old PLY size: 4106 MB. Status: SUCCESS -Loop Type Data -Job #12 swagon_slam.osf SLAM execution time: 342 seconds -Job #12 swagon_slam.osf end-to-end time: 3800 seconds -Completed in 7196 seconds -Total SLAM execution time: 1059 seconds diff --git a/python/tests/test_cli.py b/python/tests/test_cli.py index dcb35511..f0c03416 100644 --- a/python/tests/test_cli.py +++ b/python/tests/test_cli.py @@ -1,7 +1,9 @@ # type: ignore import os +import inspect from glob import glob from pathlib import Path +import click import pytest import sys import json @@ -456,6 +458,32 @@ def test_source_pcap_save_raw(test_pcap_file, runner, tmp_path): assert any(filename == 'test.pcap' for filename in files) +def test_source_pcap_save_zm_imu(runner, tmp_path): + """It should save a pcap file with the desired name.""" + test_pcap_file = str(Path(PCAPS_DATA_DIR) / 'imu_zm_no_lidar.pcap') + with set_directory(tmp_path): + assert not os.listdir(tmp_path) # no files in output dir + result = runner.invoke(core.cli, CliArgs(['source', test_pcap_file, 'save', 'test.pcap']).args) + assert result.exit_code == 0 + # there's a pcap in the output directory + files = os.listdir(tmp_path) + assert len(files) == 2 + assert any(filename == 'test.pcap' for filename in files) + + +def test_source_pcap_save_raw_zm_imu(runner, tmp_path): + """It should save a pcap file with the desired name.""" + test_pcap_file = str(Path(PCAPS_DATA_DIR) / 'imu_zm_no_lidar.pcap') + with set_directory(tmp_path): + assert not os.listdir(tmp_path) # no files in output dir + result = runner.invoke(core.cli, CliArgs(['source', test_pcap_file, 'save_raw', 'test.pcap']).args) + assert result.exit_code == 0 + # there's a pcap in the output directory + files = os.listdir(tmp_path) + assert len(files) == 2 + assert any(filename == 'test.pcap' for filename in files) + + def test_source_osf_info_help(test_osf_file, runner): """ouster-cli source .osf info --help should display OSF viz help""" @@ -564,6 +592,114 @@ def test_source_stats(test_pcap_file, runner, monkeypatch): assert "Incomplete Scans" in result +def test_source_filter_no_lidar(runner, monkeypatch): + """ouster-cli source --filter on data with no lidar packets should pass through scans""" + test_pcap_file = str(Path(PCAPS_DATA_DIR) / 'imu_zm_no_lidar.pcap') + result = get_stats(monkeypatch, runner, test_pcap_file, args = []) + assert "Count: 1" in result + result = get_stats(monkeypatch, runner, test_pcap_file, args = ["--filter"]) + assert "Count: 1" in result + + +def test_source_filter(runner, monkeypatch): + """ouster-cli source --filter removes incomplete scans""" + test_pcap_file = str(Path(PCAPS_DATA_DIR) / 'crc_test.pcap') + result = get_stats(monkeypatch, runner, test_pcap_file, args = []) + assert "Count: 2" in result + result = get_stats(monkeypatch, runner, test_pcap_file, args = ["--filter"]) + assert "Count: 1" in result + + +def test_source_filter_coord_frame_requires_xyz(): + """--coord-frame should only be accepted for X/Y/Z filtering.""" + ctx = source.SourceCommandContext() + source_filter_fn = inspect.unwrap(source.source_filter.callback) + with pytest.raises(click.BadParameter, match="X, Y, or Z"): + source_filter_fn( + ctx=ctx, + axis_field="U", + indices=(None, 10), + filtered_fields=None, + invalid_value=0, + coord_frame="WORLD", + ) + + +@pytest.mark.parametrize("coord_frame, expected_use_extrinsics, expected_dewarp_points", [ + ("SENSOR", False, False), + ("BODY", True, False), + ("WORLD", True, True), +]) +def test_source_filter_xyz_coord_frame_modes( + monkeypatch, + coord_frame, + expected_use_extrinsics, + expected_dewarp_points, +): + """XYZ coord frames should map to expected LUT/dewarp behavior.""" + import ouster.sdk.core as sdk_core + import ouster.sdk.core.scan_ops as so + source_filter_fn = inspect.unwrap(source.source_filter.callback) + + xyzlut_use_extrinsics = [] + dewarp_points_args = [] + scan_tokens = [] + + class FakeScanSource: + sensor_info = [object()] + + ctx = source.SourceCommandContext() + ctx.scan_source = FakeScanSource() + ctx.scan_iter = lambda: iter([[{"scan": 1}]]) # type: ignore + + def fake_xyzlut(sensor_info, use_extrinsics=True): + xyzlut_use_extrinsics.append(use_extrinsics) + + def fake_xyz(range_image): + h, w = range_image.shape + return np.zeros((h, w, 3), dtype=np.float64) + + return fake_xyz + + def fake_filter_xyz(scan, xyzlut, axis_idx, lower, upper, invalid, + filtered_fields=None, dewarp_points=False): + scan_tokens.append(scan) + dewarp_points_args.append(dewarp_points) + return None + + monkeypatch.setattr(sdk_core, "XYZLut", fake_xyzlut) + monkeypatch.setattr(so, "filter_xyz", fake_filter_xyz) + + source_filter_fn( + ctx=ctx, + axis_field="X", + indices=(-1000, 1000), + filtered_fields=None, + invalid_value=0, + coord_frame=coord_frame, + ) + list(ctx.scan_iter()) # type: ignore[operator] + + assert scan_tokens + assert xyzlut_use_extrinsics + assert set(xyzlut_use_extrinsics) == {expected_use_extrinsics} + assert dewarp_points_args + assert set(dewarp_points_args) == {expected_dewarp_points} + + +def test_source_plumb(test_pcap_file, runner, tmp_path): + """ouster-cli source ... plumb should run successfully.""" + with set_directory(tmp_path): + assert not os.listdir(tmp_path) # no files in output dir + result = runner.invoke(core.cli, CliArgs(['source', "--sensor-idx", "0", + test_pcap_file, 'plumb', 'save', 'test.osf']).args) + assert result.exit_code == 0 + # there's at most one OSF file in output dir + files = os.listdir(tmp_path) + assert len(files) == 1 + assert all(filename == 'test.osf' for filename in files) + + def test_source_osf(runner, has_mapping) -> None: """It should list the correct commands in the help depending on source type.""" diff --git a/python/tests/test_lidar_scan_set.py b/python/tests/test_lidar_scan_set.py index 0aa719dd..9c6b0013 100644 --- a/python/tests/test_lidar_scan_set.py +++ b/python/tests/test_lidar_scan_set.py @@ -37,3 +37,11 @@ def test_lidar_scan_set_with_missing_scans() -> None: assert (collation[0].w, collation[0].h) == (10, 10) # type: ignore assert collation[1] is None assert len(collation) == 3 + + +def test_lidar_scan_set_assignment() -> None: + scans_in = [LidarScan(10, 10), None] + collation = LidarScanSet(scans_in) + collation[0] = None + assert len(collation) == 2 + assert collation[0] is None diff --git a/python/tests/test_metadata.py b/python/tests/test_metadata.py index 28513544..a5629adb 100644 --- a/python/tests/test_metadata.py +++ b/python/tests/test_metadata.py @@ -326,3 +326,14 @@ def test_zone_monitoring_enabled(): sensor_info_json = json.loads(sensor_info.to_json_string()) sensor_info_new = core.SensorInfo(json.dumps(sensor_info_json)) assert sensor_info_new.format.zone_monitoring_enabled is True + + +def test_extrinsic_mutability(meta: core.SensorInfo) -> None: + """Check that extrinsic is mutable and can be set to a new value.""" + new_extrinsic = numpy.eye(4) + new_extrinsic[0, 3] = 1.0 + meta.extrinsic = new_extrinsic + assert (meta.extrinsic == new_extrinsic).all() + + meta.extrinsic[0, 3] = 2.0 + assert meta.extrinsic[0, 3] == 2.0 diff --git a/python/tests/test_open_source.py b/python/tests/test_open_source.py index f34fa357..963de467 100644 --- a/python/tests/test_open_source.py +++ b/python/tests/test_open_source.py @@ -5,7 +5,7 @@ import pytest import tempfile from ouster.sdk.util import resolve_metadata_multi -from ouster.sdk.core import SensorInfo +from ouster.sdk.core import SensorInfo, FieldClass from ouster.sdk import open_source, open_packet_source, SourceURLException from tests.conftest import PCAPS_DATA_DIR, BAGS_DATA_DIR, OSFS_DATA_DIR @@ -154,6 +154,24 @@ def test_open_packet_source_bag() -> None: assert got_packet +def test_source_no_lidar() -> None: + """Validate that we can load a source with no lidar data and see no lidar fields""" + file_path = os.path.join(PCAPS_DATA_DIR, 'imu_zm_no_lidar.pcap') + + src = open_source(file_path) + scan = next(iter(src))[0] + assert scan is not None + ft_names = [ft.name for ft in scan.field_types] + assert "IMU_PACKET_TIMESTAMP" in ft_names + assert "ZONE_PACKET_TIMESTAMP" in ft_names + # assert none are pixel fields + for ft in scan.field_types: + assert ft.field_class != FieldClass.PIXEL_FIELD + + # also assert that we see 0 lidar packets per frame + assert scan.sensor_info.format.lidar_packets_per_frame() == 0 + + def test_open_source_collating_osf() -> None: file_path = os.path.join(OSFS_DATA_DIR, "OS-1-128_v2.3.0_1024x10_lb_n3.osf") diff --git a/python/tests/test_scan_ops.py b/python/tests/test_scan_ops.py index 36e1125c..e45cf186 100644 --- a/python/tests/test_scan_ops.py +++ b/python/tests/test_scan_ops.py @@ -6,7 +6,7 @@ but limits the interaction with the source to the scope. """ -from typing import cast +from typing import cast, Union import os import pytest import sys @@ -16,6 +16,7 @@ from ouster.sdk.core import ChanField, LidarScan from ouster.sdk.core import (ScanSource, ReducedScanSource, ClippedScanSource, MaskedScanSource) +import ouster.sdk.core.scan_ops as scan_ops import numpy as np from tests.conftest import OSFS_DATA_DIR @@ -228,3 +229,97 @@ def test_chain(scan_source_path) -> None: got_scan = True break assert got_scan + + +def test_lidarscan_field_types_writable(scan_source_path) -> None: + """Create LidarScan, add all supported field types, verify they are writable.""" + src = open_source(scan_source_path) + info = src.sensor_info[0] + + ls = LidarScan(info.format.columns_per_frame, + info.format.pixels_per_column, + info.format.udp_profile_lidar) + + # Attempt to add fields of all possible numpy scalar types + dtypes = [ + np.uint8, np.uint16, np.uint32, np.uint64, + np.int8, np.int16, np.int32, np.int64, + np.float32, np.float64 + ] + + for dtype in dtypes: + try: + ls.add_field(f"test_field_{dtype.__name__}", dtype) + except (TypeError, ValueError): + # Not all types might be supported by the bindings + pass + + ls.add_field("X", + np.array([b'0', b'1', b'2', b'3', b'4', b'5', b'6', b'7'], + dtype='|S8').view(np.recarray), + core.FieldClass.SCAN_FIELD) + + for field_name in ls.fields: + arr = ls.field(field_name) + # Check that it is a numpy array (or convertible/workable) and writable + assert isinstance(arr, np.ndarray) + assert arr.flags.writeable, f"Field {field_name} (dtype: {arr.dtype}) is not writable" + + +def test_filter_xyz_dewarp_points_changes_spatial_mask(scan_source_path) -> None: + """Dewarping should change the XYZ mask when non-identity per-column poses are used.""" + src = cast(ScanSource, open_source(scan_source_path)) + try: + first = next(iter(src))[0] + assert first is not None + scan = copy.deepcopy(cast(LidarScan, first)) + finally: + src.close() + + assert scan.has_field(ChanField.RANGE), "RANGE field is required for XYZ filtering test" + + scan.field(ChanField.RANGE)[:] = 1000 + scan.pose[:] = np.repeat(np.eye(4, dtype=np.float64)[None, :, :], scan.w, axis=0) + + poses = np.repeat(np.eye(4, dtype=np.float64)[None, :, :], scan.w, axis=0) + poses[:scan.w // 2, 0, 3] = 2.0 + + def zero_xyz(scan_or_range: Union[LidarScan, np.ndarray]) -> np.ndarray: + range_image = ( + scan_or_range.field(ChanField.RANGE) + if isinstance(scan_or_range, LidarScan) + else scan_or_range + ) + h, w = range_image.shape + return np.zeros((h, w, 3), dtype=np.float64) + + scan_body = copy.deepcopy(scan) + scan_world = copy.deepcopy(scan) + scan_world.pose[:] = poses + + scan_ops.filter_xyz( + scan_body, + zero_xyz, + axis_idx=0, + lower=1.5, + upper=2.5, + invalid=0, + filtered_fields=[ChanField.RANGE], + dewarp_points=False, + ) + scan_ops.filter_xyz( + scan_world, + zero_xyz, + axis_idx=0, + lower=1.5, + upper=2.5, + invalid=0, + filtered_fields=[ChanField.RANGE], + dewarp_points=True, + ) + + body_zeroed = np.count_nonzero(scan_body.field(ChanField.RANGE) == 0) + world_zeroed = np.count_nonzero(scan_world.field(ChanField.RANGE) == 0) + + assert body_zeroed == 0 + assert world_zeroed == scan.h * (scan.w // 2) diff --git a/python/tests/test_viz_core.py b/python/tests/test_viz_core.py index a243af8d..80e090d3 100644 --- a/python/tests/test_viz_core.py +++ b/python/tests/test_viz_core.py @@ -518,3 +518,14 @@ def test_viz_imu_when_a_scan_is_none(): meta = SensorInfo.from_default(LidarMode._1024x10) viz = LidarScanViz([meta], MockPointViz()) viz.imu_plot([[None]], viz._imu_viz_config) + + +def test_viz_safe_gif(tmp_path): + from ouster.sdk.viz import SimpleViz + """It should not crash when the duration between frames is negative or zero.""" + import PIL.Image as PILImage + test_image = PILImage.new('RGB', (10, 10)) + meta = SensorInfo.from_default(LidarMode._1024x10) + viz = SimpleViz([meta], _override_pointviz=MockPointViz()) + viz._images = [(test_image, 100), (test_image, 50)] + viz._save_gif(str(tmp_path / 'test.gif')) # should not crash diff --git a/sdk-extensions b/sdk-extensions index 0885998c..dcd66c00 160000 --- a/sdk-extensions +++ b/sdk-extensions @@ -1 +1 @@ -Subproject commit 0885998cb7459c8879d6742c1152c4a090aedb7e +Subproject commit dcd66c00f0f7fd1473b4e7b83a831396fb63af57 diff --git a/tests/bcompat_meta_json_test.cpp b/tests/bcompat_meta_json_test.cpp index e0f7fc0e..841468d0 100644 --- a/tests/bcompat_meta_json_test.cpp +++ b/tests/bcompat_meta_json_test.cpp @@ -929,7 +929,7 @@ class MetaJsonTest : public testing::TestWithParam { "v2.1.2", LidarMode::_1024x10, "OS-1-64", - {64, 16, 1024, 0, 0, { 19, 13, 6, 0, 19, 13, 6, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 20, 14, 7, 1}, {0, 1023}, UDPProfileLidar::LEGACY, UDPProfileIMU::LEGACY, HeaderType::STANDARD, 10}, + {64, 16, 1024, 0, 0, { 19, 13, 6, 0, 19, 13, 6, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 19, 13, 7, 1, 20, 14, 7, 1}, {0, 1023}, UDPProfileLidar::OFF, UDPProfileIMU::LEGACY, HeaderType::STANDARD, 10}, { 3.073, 0.904, -1.261, -3.384, 3.048, 0.9, -1.235, -3.335, 3.029, 0.915, -1.2, -3.301, 3.026, 0.921, -1.179, -3.268, 3.032, 0.933, -1.156, -3.23, 3.028, 0.953, -1.131, -3.209, 3.059, 0.976, -1.112, -3.182, 3.071, 0.99, -1.087, -3.155, 3.097, 1.014, -1.103, -3.133, 3.118, 1.035, -1.039, -3.116, 3.144, 1.061, -1.013, -3.101, 3.178, 1.092, -0.993, -3.089, 3.217, 1.125, -0.972, -3.072, 3.265, 1.159, -0.949, -3.066, 3.321, 1.204, -0.921, -3.055, 3.381, 1.252, -0.898, -3.071}, { 16.729, 16.118, 15.543, 14.995, 14.526, 13.937, 13.381, 12.837, 12.378, 11.801, 11.251, 10.704, 10.251, 9.693, 9.138, 8.603, 8.149, 7.594, 7.049, 6.513, 6.056, 5.504, 4.961, 4.419, 3.967, 3.424, 2.881, 2.328, 1.88, 1.337, 0.787, 0.239, -0.205, -0.756, -1.39, -1.854, -2.3, -2.839, -3.386, -3.935, -4.391, -4.929, -5.472, -6.028, -6.471, -7.02, -7.563, -8.116, -8.572, -9.112, -9.66, -10.227, -10.687, -11.226, -11.777, -12.35, -12.807, -13.347, -13.902, -14.49, -14.968, -15.504, -16.078, -16.679}, 12.163, diff --git a/tests/osf_tests/writer_test.cpp b/tests/osf_tests/writer_test.cpp index 26c69cff..fe2e8762 100644 --- a/tests/osf_tests/writer_test.cpp +++ b/tests/osf_tests/writer_test.cpp @@ -18,6 +18,7 @@ #include "ouster/osf/meta_lidar_sensor.h" #include "ouster/osf/meta_streaming_info.h" #include "ouster/osf/reader.h" +#include "ouster/osf/sensor_info_stream.h" #include "ouster/osf/stream_lidar_scan.h" #include "ouster/types.h" @@ -66,15 +67,23 @@ TEST_F(WriterTest, WriteSingleLidarScan) { Reader reader(output_osf_filename); EXPECT_EQ(reader.metadata_id(), "test_session"); - auto msg_it = reader.messages().begin(); - EXPECT_NE(msg_it, reader.messages().end()); + auto lidar_stream = reader.meta_store().get(); + auto lidar_messages = reader.messages({lidar_stream->id()}); + + auto msg_it = lidar_messages.begin(); + EXPECT_NE(msg_it, lidar_messages.end()); auto ls_recovered = msg_it->decode_msg(); EXPECT_TRUE(ls_recovered); EXPECT_EQ(*ls_recovered, ls); - EXPECT_NE(++msg_it, reader.messages().end()); // sensor info message - EXPECT_EQ(++msg_it, reader.messages().end()); + + auto si_stream = reader.meta_store().get(); + auto si_messages = reader.messages({si_stream->id()}); + + auto si_msg_it = si_messages.begin(); + EXPECT_NE(si_msg_it, si_messages.end()); // sensor info message + EXPECT_EQ(++si_msg_it, si_messages.end()); // Map of all MetadataEntries of type LidarSensor auto sensors = reader.meta_store().find(); @@ -156,16 +165,17 @@ TEST_F(WriterTest, WriteSingleLidarScanStreamingLayout) { EXPECT_EQ(reader.metadata_id(), "test_session"); // TODO[pb]: Add reader validation CRC + auto lidar_stream = reader.meta_store().get(); + auto lidar_messages = reader.messages({lidar_stream->id()}); - auto msg_it = reader.messages().begin(); - EXPECT_NE(msg_it, reader.messages().end()); + auto msg_it = lidar_messages.begin(); + EXPECT_NE(msg_it, lidar_messages.end()); auto ls_recovered = msg_it->decode_msg(); EXPECT_TRUE(ls_recovered); EXPECT_EQ(*ls_recovered, ls); - EXPECT_NE(++msg_it, reader.messages().end()); // sensor info message - EXPECT_EQ(++msg_it, reader.messages().end()); + EXPECT_EQ(++msg_it, lidar_messages.end()); // Map of all MetadataEntries of type LidarSensor auto sensors = reader.meta_store().find(); @@ -216,8 +226,11 @@ TEST_F(WriterTest, WriteSlicedLidarScan) { Reader reader(output_osf_filename); EXPECT_EQ(reader.metadata_id(), "test_session"); - auto msg_it = reader.messages().begin(); - EXPECT_NE(msg_it, reader.messages().end()); + auto lidar_stream = reader.meta_store().get(); + auto lidar_messages = reader.messages({lidar_stream->id()}); + + auto msg_it = lidar_messages.begin(); + EXPECT_NE(msg_it, lidar_messages.end()); auto ls_recovered = msg_it->decode_msg(); @@ -225,8 +238,7 @@ TEST_F(WriterTest, WriteSlicedLidarScan) { EXPECT_TRUE(ls_recovered); EXPECT_EQ(*ls_recovered, ls); - EXPECT_NE(++msg_it, reader.messages().end()); // sensor info message - EXPECT_EQ(++msg_it, reader.messages().end()); + EXPECT_EQ(++msg_it, lidar_messages.end()); // Map of all MetadataEntries of type LidarSensor auto sensors = reader.meta_store().find(); @@ -278,8 +290,11 @@ TEST_F(WriterTest, WriteSlicedLegacyLidarScan) { Reader reader(output_osf_filename); EXPECT_EQ(reader.metadata_id(), "test_session"); - auto msg_it = reader.messages().begin(); - EXPECT_NE(msg_it, reader.messages().end()); + auto lidar_stream = reader.meta_store().get(); + auto lidar_messages = reader.messages({lidar_stream->id()}); + + auto msg_it = lidar_messages.begin(); + EXPECT_NE(msg_it, lidar_messages.end()); auto ls_recovered = msg_it->decode_msg(); @@ -288,8 +303,7 @@ TEST_F(WriterTest, WriteSlicedLegacyLidarScan) { EXPECT_EQ(field_types.size(), ls_recovered->field_types().size()); EXPECT_EQ(*ls_recovered, ls_reference); - EXPECT_NE(++msg_it, reader.messages().end()); // sensor info message - EXPECT_EQ(++msg_it, reader.messages().end()); + EXPECT_EQ(++msg_it, lidar_messages.end()); // Map of all MetadataEntries of type LidarSensor auto sensors = reader.meta_store().find(); @@ -363,8 +377,11 @@ TEST_F(WriterTest, WriteCustomLidarScanWithFlags) { Reader reader(output_osf_filename); EXPECT_EQ(reader.metadata_id(), "test_session"); - auto msg_it = reader.messages().begin(); - EXPECT_NE(msg_it, reader.messages().end()); + auto lidar_stream = reader.meta_store().get(); + auto lidar_messages = reader.messages({lidar_stream->id()}); + + auto msg_it = lidar_messages.begin(); + EXPECT_NE(msg_it, lidar_messages.end()); auto ls_recovered = msg_it->decode_msg(); @@ -374,8 +391,7 @@ TEST_F(WriterTest, WriteCustomLidarScanWithFlags) { ls_recovered->field_types().size()); EXPECT_EQ(*ls_recovered, ls); - EXPECT_NE(++msg_it, reader.messages().end()); // sensor info message - EXPECT_EQ(++msg_it, reader.messages().end()); + EXPECT_EQ(++msg_it, lidar_messages.end()); } // Used in WriteExample test below @@ -529,8 +545,11 @@ TEST_F(WriterTest, WriteCustomFieldsTest) { Reader reader(output_osf_filename); EXPECT_EQ(reader.metadata_id(), "test_session"); - auto msg_it = reader.messages().begin(); - EXPECT_NE(msg_it, reader.messages().end()); + auto lidar_stream = reader.meta_store().get(); + auto lidar_messages = reader.messages({lidar_stream->id()}); + + auto msg_it = lidar_messages.begin(); + EXPECT_NE(msg_it, lidar_messages.end()); auto ls_recovered = msg_it->decode_msg(); diff --git a/tests/pcaps/imu_zm_no_lidar.pcap b/tests/pcaps/imu_zm_no_lidar.pcap new file mode 100644 index 00000000..3f9baf20 Binary files /dev/null and b/tests/pcaps/imu_zm_no_lidar.pcap differ diff --git a/tests/pcaps/imu_zm_no_lidar_0.json b/tests/pcaps/imu_zm_no_lidar_0.json new file mode 100644 index 00000000..943d3f70 --- /dev/null +++ b/tests/pcaps/imu_zm_no_lidar_0.json @@ -0,0 +1 @@ +{"beam_intrinsics":{"beam_altitude_angles":[45.16,44.58,43.84,42.95,42.18,41.58,40.84,39.98,39.21,38.6,37.87,37.02,36.26,35.63,34.91,34.07,33.32,32.67,31.95,31.14,30.39,29.74,29.03,28.24,27.49,26.82,26.11,25.34,24.59,23.92,23.21,22.45,21.7,21.04,20.32,19.58,18.83,18.17,17.45,16.7,15.99,15.31,14.59,13.87,13.15,12.46,11.76,11.03,10.32,9.63,8.93,8.2,7.49,6.79,6.09,5.37,4.72,3.97,3.28,2.57,1.87,1.17,0.45,-0.24,-0.93,-1.66,-2.35,-3.05,-3.74,-4.47,-5.17,-5.85,-6.54,-7.28,-8.0,-8.66,-9.37,-10.1,-10.81,-11.5,-12.18,-12.92,-13.65,-14.32,-14.98,-15.77,-16.49,-17.14,-17.82,-18.6,-19.3,-19.99,-20.66,-21.43,-22.17,-22.84,-23.5,-24.3,-25.03,-25.67,-26.36,-27.16,-27.9,-28.54,-29.22,-30.05,-30.79,-31.42,-32.09,-32.94,-33.68,-34.32,-34.99,-35.83,-36.59,-37.25,-37.92,-38.79,-39.55,-40.18,-40.87,-41.76,-42.53,-43.13,-43.82,-44.74,-45.51,-46.12],"beam_azimuth_angles":[10.86,3.57,-3.62,-10.67,10.48,3.44,-3.48,-10.29,10.12,3.33,-3.37,-9.97,9.82,3.24,-3.27,-9.7,9.57,3.15,-3.19,-9.46,9.36,3.1,-3.12,-9.25,9.16,3.02,-3.04,-9.08,8.99,2.96,-3.0,-8.93,8.84,2.93,-2.94,-8.8,8.73,2.89,-2.9,-8.7,8.63,2.86,-2.88,-8.6,8.55,2.82,-2.84,-8.53,8.48,2.81,-2.83,-8.47,8.45,2.81,-2.81,-8.43,8.37,2.81,-2.8,-8.41,8.4,2.8,-2.8,-8.41,8.4,2.82,-2.79,-8.42,8.41,2.81,-2.79,-8.44,8.44,2.82,-2.8,-8.47,8.48,2.85,-2.82,-8.52,8.54,2.87,-2.82,-8.58,8.62,2.91,-2.85,-8.66,8.71,2.94,-2.89,-8.76,8.82,2.97,-2.92,-8.88,8.96,3.03,-2.96,-9.03,9.13,3.08,-3.01,-9.21,9.31,3.15,-3.08,-9.4,9.52,3.22,-3.15,-9.62,9.76,3.3,-3.25,-9.89,10.05,3.4,-3.34,-10.21,10.39,3.53,-3.46,-10.58,10.77,3.66,-3.6,-11.02],"beam_to_lidar_transform":[1.0,0.0,0.0,27.116,0.0,1.0,0.0,0.0,0.0,0.0,1.0,0.0,0.0,0.0,0.0,1.0],"lidar_origin_to_beam_origin_mm":27.116},"calibration_status":{"reflectivity":{"timestamp":"2023-01-25T15:11:58","valid":true}},"config_params":{"accel_fsr":"EXTENDED","azimuth_window":[0,360000],"bloom_reduction_optimization":"BALANCED","columns_per_packet":16,"gyro_fsr":"EXTENDED","header_type":"STANDARD","imu_packets_per_frame":8,"lidar_frame_azimuth_offset":0,"lidar_mode":"2048x10","min_range_threshold_cm":50,"multipurpose_io_mode":"OFF","nmea_baud_rate":"BAUD_9600","nmea_ignore_valid_char":0,"nmea_in_polarity":"ACTIVE_HIGH","nmea_leap_seconds":0,"operating_mode":"NORMAL","phase_lock_enable":false,"phase_lock_offset":0,"return_order":"STRONGEST_TO_WEAKEST","signal_multiplier":1,"sync_pulse_in_polarity":"ACTIVE_HIGH","sync_pulse_out_angle":360,"sync_pulse_out_frequency":1,"sync_pulse_out_polarity":"ACTIVE_HIGH","sync_pulse_out_pulse_width":10,"timestamp_mode":"TIME_FROM_INTERNAL_OSC","udp_dest":"fe80::655b:4978:2497:20cc","udp_dest_zm":"fe80::655b:4978:2497:20cc","udp_multicast_ttl":1,"udp_multicast_ttl_zm":1,"udp_port_imu":7513,"udp_port_lidar":0,"udp_port_zm":7514,"udp_profile_imu":"ACCEL32_GYRO32_NMEA","udp_profile_lidar":"RNG19_RFL8_SIG16_NIR16_ZONE16"},"imu_data_format":{"imu_measurements_per_packet":8,"imu_packets_per_frame":8},"imu_intrinsics":{"imu_to_sensor_transform":[1.0,0.0,0.0,-2.441,0.0,1.0,0.0,-9.725,0.0,0.0,1.0,7.533,0.0,0.0,0.0,1.0]},"lidar_data_format":{"column_window":[0,2047],"columns_per_frame":2048,"columns_per_packet":16,"fps":10,"header_type":"STANDARD","pixel_shift_by_row":[62,20,-21,-61,60,20,-20,-59,58,19,-19,-57,56,18,-19,-55,54,18,-18,-54,53,18,-18,-53,52,17,-17,-52,51,17,-17,-51,50,17,-17,-50,50,16,-16,-49,49,16,-16,-49,49,16,-16,-49,48,16,-16,-48,48,16,-16,-48,48,16,-16,-48,48,16,-16,-48,48,16,-16,-48,48,16,-16,-48,48,16,-16,-48,48,16,-16,-48,49,16,-16,-49,49,17,-16,-49,50,17,-16,-50,50,17,-17,-51,51,17,-17,-51,52,18,-17,-52,53,18,-18,-53,54,18,-18,-55,56,19,-18,-56,57,19,-19,-58,59,20,-20,-60,61,21,-20,-63],"pixels_per_column":128,"udp_profile_imu":"ACCEL32_GYRO32_NMEA","udp_profile_lidar":"RNG19_RFL8_SIG16_NIR16_ZONE16"},"lidar_intrinsics":{"lidar_to_sensor_transform":[-1.0,0.0,0.0,0.0,0.0,-1.0,0.0,0.0,0.0,0.0,1.0,38.195,0.0,0.0,0.0,1.0]},"ouster-sdk":{"client_version":"ouster_client 1.0.0","extrinsic":[1.0,0.0,0.0,0.0,0.0,1.0,0.0,0.0,0.0,0.0,1.0,0.0,0.0,0.0,0.0,1.0],"output_source":"sensor_info_to_string"},"sensor_info":{"build_date":"2026-01-23T14:17:00Z","build_rev":"b4441868c68b78c6d331577b1dd1fcf59668ef72","image_rev":"ousteros-image-prod-bootes-v3.2.0-rc.7+20260123142315","initialization_id":15079160,"prod_line":"OS-0-128","prod_pn":"840-104681-C","prod_sn":"122247000785","status":"RUNNING"},"user_data":"","zone_set":"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"} diff --git a/thirdparty/spdlog/CMakeLists.txt b/thirdparty/spdlog/CMakeLists.txt new file mode 100644 index 00000000..e21e35fa --- /dev/null +++ b/thirdparty/spdlog/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.5) +project(spdlog LANGUAGES CXX) + +add_library(spdlog INTERFACE) +add_library(spdlog::spdlog ALIAS spdlog) + +target_include_directories(spdlog INTERFACE + $ +) + +# Header-only, no install rules needed for embedded dependency diff --git a/vcpkg.json b/vcpkg.json index 3aa1040e..36a28386 100644 --- a/vcpkg.json +++ b/vcpkg.json @@ -32,8 +32,12 @@ { "name": "gtest", "version": "1.16.0" + }, + { + "name": "eigen3", + "version": "3.4.1#1" } ], - "builtin-baseline": "74e6536215718009aae747d86d84b78376bf9e09", - "version": "0.15.0" + "builtin-baseline": "66c0373dc7fca549e5803087b9487edfe3aca0a1", + "version": "0.16.1" }