diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 509954a4..158c63d4 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -20,6 +20,7 @@ ouster_client * use of sensor http interface for comms with sensors for FW 2.1+ * propogate C++ 17 usage requirement in cmake for C++ libraries built as C++17 * allow vcpkg configuration via environment variables +* fix a bug in sensor_config struct equality comparison operator ouster_pcap ----------- diff --git a/CMakeLists.txt b/CMakeLists.txt index 6d5140b4..763f75ee 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ include(VcpkgEnv) project(ouster_example VERSION 20220826) # generate version header -set(OusterSDK_VERSION_STRING 0.5.0) +set(OusterSDK_VERSION_STRING 0.5.1) include(VersionGen) # ==== Options ==== diff --git a/cmake/VersionGen.cmake b/cmake/VersionGen.cmake index 83b84bab..0b986166 100644 --- a/cmake/VersionGen.cmake +++ b/cmake/VersionGen.cmake @@ -24,7 +24,7 @@ if(CMAKE_SCRIPT_MODE_FILE) ${VERSION_GEN_OUT_DIR}/build.h @ONLY) elseif(NOT TARGET ouster_build) # in configuration stage: expects OusterSDK_VERSION_STRING to be set - if(OusterSDK_VERSION_STRING MATCHES "^([0-9]+\.[0-9]+\.[0-9]+)(-([.0-9A-z]+))?$") + if(OusterSDK_VERSION_STRING MATCHES "^([0-9]+\.[0-9]+\.[0-9]+)(.([.0-9A-z]+))?$") set(OusterSDK_VERSION "${CMAKE_MATCH_1}") set(OusterSDK_VERSION_SUFFIX "${CMAKE_MATCH_3}") else() diff --git a/conan/test_package/conanfile.py b/conan/test_package/conanfile.py index 782c8272..304bd30d 100644 --- a/conan/test_package/conanfile.py +++ b/conan/test_package/conanfile.py @@ -24,4 +24,6 @@ def imports(self): def test(self): if not tools.cross_building(self): os.chdir("examples") - self.run(".%sclient_example" % os.sep) + # on Windows VS puts execulables under `./Release` or `./Debug` folders + exec_path = f"{os.sep}{self.settings.build_type}" if self.settings.os == "Windows" else "" + self.run(".%s%sclient_example" % (exec_path, os.sep)) diff --git a/conanfile.py b/conanfile.py index 82d9f1d2..fb5d64ef 100644 --- a/conanfile.py +++ b/conanfile.py @@ -63,16 +63,10 @@ def requirements(self): if self.options.build_pcap: self.requires("libtins/4.3") - # override due to conflict b/w libtins and libcurl - self.requires("openssl/1.1.1q") - if self.options.build_viz: - self.requires("glad/0.1.35") - # glew is optional, and probably will not be needed - # self.requires("glew/2.2.0") - # glfw pulls in xorg/system, the latest revision of which (7c17659) requires updates - # pin to older revision which doesn't require install/update, thus overriding glfw's xorg/system - self.requires("xorg/system@#60bff7b91495dc0366ae6a9ae60d73a9") + self.requires("glad/0.1.34") + if self.settings.os != "Windows": + self.requires("xorg/system") self.requires("glfw/3.3.6") # maybe needed for cpp examples, but not for the lib # self.requires("tclap/1.2.4") @@ -89,7 +83,7 @@ def configure_cmake(self): self.build_folder, "conan_paths.cmake") cmake.definitions["BUILD_SHARED_LIBS"] = True if self.options.shared else False cmake.definitions["CMAKE_POSITION_INDEPENDENT_CODE"] = ( - True if self.options.fPIC else False + True if "fPIC" in self.options and self.options.fPIC else False ) # we use this option until we remove nonstd::optional from SDK codebase (soon) diff --git a/docs/conf.py b/docs/conf.py index a7acf8fb..9352b51c 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -23,14 +23,32 @@ import shutil import os import sys +import re project = 'Ouster Sensor SDK' copyright = '2022, Ouster, Inc.' author = 'Ouster SW' +# use SDK source location from environment or try to guess +SRC_PATH = os.path.dirname(os.path.abspath(__file__)) +OUSTER_SDK_PATH = os.getenv('OUSTER_SDK_PATH') +if OUSTER_SDK_PATH is None: + OUSTER_SDK_PATH = os.path.join(SRC_PATH, "sdk") +if not os.path.exists(OUSTER_SDK_PATH): + OUSTER_SDK_PATH = os.path.dirname(SRC_PATH) +if not os.path.exists(os.path.join(OUSTER_SDK_PATH, "cmake")): + raise RuntimeError("Could not guess OUSTER_SDK_PATH") +print(OUSTER_SDK_PATH) + +# https://packaging.python.org/en/latest/guides/single-sourcing-package-version/ +def parse_version(): + with open(os.path.join(OUSTER_SDK_PATH, 'CMakeLists.txt')) as listfile: + content = listfile.read() + groups = re.search("set\(OusterSDK_VERSION_STRING ([^-\)]+)(-(.*))?\)", content) + return groups.group(1) + (groups.group(3) or "") + # The full version, including alpha/beta/rc tags -version = '0.5.0' -release = '0.5.0' +version = release = parse_version() # -- General configuration --------------------------------------------------- diff --git a/examples/config_example.cpp b/examples/config_example.cpp index 15718dd8..7047fcd9 100644 --- a/examples/config_example.cpp +++ b/examples/config_example.cpp @@ -94,13 +94,13 @@ int main(int argc, char* argv[]) { << std::endl; return EXIT_FAILURE; } - } catch (std::invalid_argument& ia) { + } catch (const std::invalid_argument&) { // expected result std::cerr << "..success! Got expected failure to set udp_dest while " "auto flag is set." << std::endl; - } catch (std::runtime_error& e) { + } catch (const std::runtime_error& e) { std::cerr << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/examples/lidar_scan_example.cpp b/examples/lidar_scan_example.cpp index 2c921509..3aa50050 100644 --- a/examples/lidar_scan_example.cpp +++ b/examples/lidar_scan_example.cpp @@ -123,7 +123,7 @@ int main(int argc, char* argv[]) { try { auto signal_field = reduced_fields_scan.field(ChanField::SIGNAL); std::cerr << signal_field(0, 0) << std::endl; - } catch (const std::out_of_range& e) { + } catch (const std::out_of_range&) { std::cerr << " ..received expected out of range error. Continuing..." << std::endl; } diff --git a/ouster_client/src/parsing.cpp b/ouster_client/src/parsing.cpp index 471d3c5c..b5e4cd68 100644 --- a/ouster_client/src/parsing.cpp +++ b/ouster_client/src/parsing.cpp @@ -261,6 +261,7 @@ packet_format::FieldIter packet_format::end() const { uint16_t packet_format::packet_type(const uint8_t* lidar_buf) const { if (udp_profile_lidar == UDPProfileLidar::PROFILE_LIDAR_LEGACY) { + // LEGACY profile has no packet_type - use 0 to code as 'legacy' return 0; } else { uint16_t res; @@ -281,6 +282,7 @@ uint16_t packet_format::frame_id(const uint8_t* lidar_buf) const { uint32_t packet_format::init_id(const uint8_t* lidar_buf) const { if (udp_profile_lidar == UDPProfileLidar::PROFILE_LIDAR_LEGACY) { + // LEGACY profile has no init_id - use 0 to code as 'legacy' return 0; } else { uint32_t res; @@ -291,6 +293,8 @@ uint32_t packet_format::init_id(const uint8_t* lidar_buf) const { uint64_t packet_format::prod_sn(const uint8_t* lidar_buf) const { if (udp_profile_lidar == UDPProfileLidar::PROFILE_LIDAR_LEGACY) { + // LEGACY profile has no prod_sn (serial number) - use 0 to code as + // 'legacy' return 0; } else { uint64_t res; diff --git a/ouster_client/src/types.cpp b/ouster_client/src/types.cpp index 13c42311..6187f75f 100644 --- a/ouster_client/src/types.cpp +++ b/ouster_client/src/types.cpp @@ -149,20 +149,23 @@ bool operator==(const sensor_config& lhs, const sensor_config& rhs) { lhs.udp_port_imu == rhs.udp_port_imu && lhs.ts_mode == rhs.ts_mode && lhs.ld_mode == rhs.ld_mode && lhs.operating_mode == rhs.operating_mode && + lhs.multipurpose_io_mode == rhs.multipurpose_io_mode && lhs.azimuth_window == rhs.azimuth_window && lhs.signal_multiplier == rhs.signal_multiplier && - lhs.sync_pulse_out_angle == rhs.sync_pulse_out_angle && - lhs.sync_pulse_out_pulse_width == rhs.sync_pulse_out_pulse_width && lhs.nmea_in_polarity == rhs.nmea_in_polarity && - lhs.nmea_baud_rate == rhs.nmea_baud_rate && lhs.nmea_ignore_valid_char == rhs.nmea_ignore_valid_char && + lhs.nmea_baud_rate == rhs.nmea_baud_rate && lhs.nmea_leap_seconds == rhs.nmea_leap_seconds && - lhs.multipurpose_io_mode == rhs.multipurpose_io_mode && lhs.sync_pulse_in_polarity == rhs.sync_pulse_in_polarity && lhs.sync_pulse_out_polarity == rhs.sync_pulse_out_polarity && + lhs.sync_pulse_out_angle == rhs.sync_pulse_out_angle && + lhs.sync_pulse_out_pulse_width == rhs.sync_pulse_out_pulse_width && lhs.sync_pulse_out_frequency == rhs.sync_pulse_out_frequency && lhs.phase_lock_enable == rhs.phase_lock_enable && - lhs.phase_lock_offset == rhs.phase_lock_offset); + lhs.phase_lock_offset == rhs.phase_lock_offset && + lhs.columns_per_packet == rhs.columns_per_packet && + lhs.udp_profile_lidar == rhs.udp_profile_lidar && + lhs.udp_profile_imu == rhs.udp_profile_imu); } bool operator!=(const sensor_config& lhs, const sensor_config& rhs) { diff --git a/ouster_ros/include/ouster_ros/os_client_base_nodelet.h b/ouster_ros/include/ouster_ros/os_client_base_nodelet.h index 287b0d55..f19779db 100644 --- a/ouster_ros/include/ouster_ros/os_client_base_nodelet.h +++ b/ouster_ros/include/ouster_ros/os_client_base_nodelet.h @@ -3,22 +3,14 @@ * All rights reserved. * * @file - * @brief Example node to publish raw sensor output on ROS topics + * @brief Base class for ouster_ros sensor and replay nodelets * - * ROS Parameters - * sensor_hostname: hostname or IP in dotted decimal form of the sensor - * udp_dest: hostname or IP where the sensor will send data packets - * lidar_port: port to which the sensor should send lidar data - * imu_port: port to which the sensor should send imu data */ #include #include -#include "ouster/impl/build.h" -#include "ouster/client.h" #include "ouster/types.h" -#include "ouster_ros/ros.h" namespace nodelets_os { diff --git a/ouster_ros/include/ouster_ros/point.h b/ouster_ros/include/ouster_ros/point.h index 4fcb150d..64332389 100644 --- a/ouster_ros/include/ouster_ros/point.h +++ b/ouster_ros/include/ouster_ros/point.h @@ -7,12 +7,11 @@ */ #pragma once -#define PCL_NO_PRECOMPILE + #include #include #include -#include #include "ouster/lidar_scan.h" diff --git a/ouster_ros/include/ouster_ros/ros.h b/ouster_ros/include/ouster_ros/ros.h index f420068e..cc087dbe 100644 --- a/ouster_ros/include/ouster_ros/ros.h +++ b/ouster_ros/include/ouster_ros/ros.h @@ -9,11 +9,15 @@ #pragma once -#include +#define PCL_NO_PRECOMPILE #include +#include + #include #include +#include + #include #include diff --git a/ouster_ros/package.xml b/ouster_ros/package.xml index e3a9a5ec..a8c5a5cb 100644 --- a/ouster_ros/package.xml +++ b/ouster_ros/package.xml @@ -1,7 +1,7 @@ ouster_ros - 0.5.0 + 0.5.1 Ouster example ROS client ouster developers BSD diff --git a/ouster_ros/src/os_client_base_nodelet.cpp b/ouster_ros/src/os_client_base_nodelet.cpp index fed0d382..926e7a50 100644 --- a/ouster_ros/src/os_client_base_nodelet.cpp +++ b/ouster_ros/src/os_client_base_nodelet.cpp @@ -8,6 +8,7 @@ #include "ouster_ros/os_client_base_nodelet.h" +#include "ouster/impl/build.h" #include "ouster_ros/GetMetadata.h" namespace sensor = ouster::sensor; diff --git a/ouster_ros/src/os_cloud_nodelet.cpp b/ouster_ros/src/os_cloud_nodelet.cpp index eb49b5f1..ead09022 100644 --- a/ouster_ros/src/os_cloud_nodelet.cpp +++ b/ouster_ros/src/os_cloud_nodelet.cpp @@ -6,11 +6,12 @@ * @brief A nodelet to publish point clouds and imu topics */ +#include "ouster_ros/ros.h" + #include #include #include #include -#include #include #include #include @@ -18,13 +19,9 @@ #include #include #include -#include -#include "ouster/lidar_scan.h" -#include "ouster/types.h" #include "ouster_ros/GetMetadata.h" #include "ouster_ros/PacketMsg.h" -#include "ouster_ros/ros.h" namespace sensor = ouster::sensor; using ouster_ros::PacketMsg; diff --git a/ouster_ros/src/os_image_nodelet.cpp b/ouster_ros/src/os_image_nodelet.cpp index 3b400aa9..1d17ff81 100644 --- a/ouster_ros/src/os_image_nodelet.cpp +++ b/ouster_ros/src/os_image_nodelet.cpp @@ -11,10 +11,10 @@ * vision applications, use higher bit depth values in /os_cloud_node/points */ +#include "ouster_ros/ros.h" + #include #include -#include -#include #include #include #include @@ -26,14 +26,10 @@ #include #include #include -#include #include -#include "ouster/client.h" #include "ouster/image_processing.h" -#include "ouster/types.h" #include "ouster_ros/GetMetadata.h" -#include "ouster_ros/ros.h" namespace sensor = ouster::sensor; namespace viz = ouster::viz; diff --git a/ouster_ros/src/os_sensor_nodelet.cpp b/ouster_ros/src/os_sensor_nodelet.cpp index 5f8fc5c7..35e8e463 100644 --- a/ouster_ros/src/os_sensor_nodelet.cpp +++ b/ouster_ros/src/os_sensor_nodelet.cpp @@ -6,6 +6,8 @@ * @brief A nodelet that connects to a live ouster sensor */ +#include "ouster_ros/ros.h" + #include #include diff --git a/ouster_ros/src/ros.cpp b/ouster_ros/src/ros.cpp index a8396b2f..5de92af6 100644 --- a/ouster_ros/src/ros.cpp +++ b/ouster_ros/src/ros.cpp @@ -10,13 +10,10 @@ #include #include -#include #include #include #include -#include "ouster/types.h" - namespace ouster_ros { namespace sensor = ouster::sensor; diff --git a/python/setup.py b/python/setup.py index f5d77b15..49852c45 100644 --- a/python/setup.py +++ b/python/setup.py @@ -17,7 +17,7 @@ if OUSTER_SDK_PATH is None: OUSTER_SDK_PATH = os.path.join(SRC_PATH, "sdk") if not os.path.exists(OUSTER_SDK_PATH): - OUSTER_SDK_PATH = os.path.join(SRC_PATH, "..") + OUSTER_SDK_PATH = os.path.dirname(SRC_PATH) if not os.path.exists(os.path.join(OUSTER_SDK_PATH, "cmake")): raise RuntimeError("Could not guess OUSTER_SDK_PATH") @@ -25,7 +25,7 @@ def parse_version(): with open(os.path.join(OUSTER_SDK_PATH, 'CMakeLists.txt')) as listfile: content = listfile.read() - groups = re.search("set\(OusterSDK_VERSION_STRING ([^-\)]+)(-(.*))?\)", content) + groups = re.search("set\(OusterSDK_VERSION_STRING ([^-\)]+)(.(.*))?\)", content) return groups.group(1) + (groups.group(3) or "") class CMakeExtension(Extension): diff --git a/python/src/ouster/client/core.py b/python/src/ouster/client/core.py index e44d4348..82432908 100644 --- a/python/src/ouster/client/core.py +++ b/python/src/ouster/client/core.py @@ -250,8 +250,11 @@ def __iter__(self) -> Iterator[Packet]: else: break except ValueError: - # TODO: bad packet size or init_id here: this can happen when + # bad packet size or init_id here: this can happen when # packets are buffered by the OS, not necessarily an error + # same pass as in data.py + # TODO: introduce status for PacketSource to indicate frequency + # of bad packet size or init_id errors pass def flush(self, n_frames: int = 3, *, full=False) -> int: diff --git a/python/src/ouster/pcap/pcap.py b/python/src/ouster/pcap/pcap.py index 38602356..314a3646 100644 --- a/python/src/ouster/pcap/pcap.py +++ b/python/src/ouster/pcap/pcap.py @@ -229,7 +229,11 @@ def __iter__(self) -> Iterator[Packet]: elif (packet_info.dst_port == self._metadata.udp_port_imu): yield ImuPacket(buf[0:n], self._metadata, timestamp) except ValueError: - # TODO: bad packet size or init_id here, use specific exceptions + # bad packet size or init_id here: this can happen when + # packets are buffered by the OS, not necessarily an error + # same pass as in core.py + # TODO: introduce status for PacketSource to indicate frequency + # of bad packet size or init_id errors pass @property diff --git a/python/tests/test_config.py b/python/tests/test_config.py index a907932b..11daace4 100644 --- a/python/tests/test_config.py +++ b/python/tests/test_config.py @@ -3,11 +3,13 @@ All rights reserved. """ -from copy import copy +from copy import copy, deepcopy from os import path import pytest +import warnings +import inspect from ouster import client @@ -192,6 +194,37 @@ def complete_config_string() -> str: return complete_config_string +@pytest.fixture() +def all_different_config_string() -> str: + """All different from complete_config_string except for udp_profile_imu""" + all_different_config_string = """ + {"azimuth_window": [180000, 360000], + "columns_per_packet": 16, + "lidar_mode": "512x10", + "multipurpose_io_mode": "INPUT_NMEA_UART", + "nmea_baud_rate": "BAUD_115200", + "nmea_ignore_valid_char": 1, + "nmea_in_polarity": "ACTIVE_LOW", + "nmea_leap_seconds": 10, + "operating_mode": "STANDBY", + "phase_lock_enable": true, + "phase_lock_offset": 180000, + "signal_multiplier": 3, + "sync_pulse_in_polarity": "ACTIVE_LOW", + "sync_pulse_out_angle": 180, + "sync_pulse_out_frequency": 10, + "sync_pulse_out_polarity": "ACTIVE_LOW", + "sync_pulse_out_pulse_width": 1, + "timestamp_mode": "TIME_FROM_SYNC_PULSE_IN", + "udp_dest": "1.1.1.1", + "udp_port_imu": 8503, + "udp_port_lidar": 8502, + "udp_profile_imu": "LEGACY", + "udp_profile_lidar": "RNG15_RFL8_NIR8"} + """ + return all_different_config_string + + def test_read_config(complete_config_string: str) -> None: """Check reading from and writing to string.""" config = client.SensorConfig(complete_config_string) # read from string @@ -218,6 +251,8 @@ def test_read_config(complete_config_string: str) -> None: assert config.udp_port_imu == 7503 assert config.udp_port_lidar == 7502 assert config.udp_profile_lidar == client.UDPProfileLidar.PROFILE_LIDAR_LEGACY + assert config.udp_profile_imu == client.UDPProfileIMU.PROFILE_IMU_LEGACY + assert config.columns_per_packet == 8 # check output of string @@ -225,7 +260,7 @@ def test_read_config(complete_config_string: str) -> None: complete_config_string.split()) -def test_equality_config(complete_config_string: str) -> None: +def test_equality_config(complete_config_string: str, all_different_config_string: str) -> None: """Check equality comparisons.""" complete_config_1 = client.SensorConfig(complete_config_string) @@ -257,6 +292,24 @@ def test_equality_config(complete_config_string: str) -> None: assert partial_config_1 != empty_config_1 assert partial_config_2 != empty_config_1 + config_attributes = inspect.getmembers(client.SensorConfig, lambda a: not inspect.isroutine(a)) + config_properties = [a for a in config_attributes if not a[0].startswith('__')] + + base_config = client.SensorConfig(complete_config_string) + different_config = client.SensorConfig(all_different_config_string) + + for config_property in config_properties: + copy_config = deepcopy(base_config) # reset to initial + property_name = config_property[0] # config_property is a tuple of (property_name as string, property) + if property_name == "udp_profile_imu": + warnings.warn(UserWarning("Skipping equality check on udp profile IMU while eUDP IMU is not implemented")) + else: + property_value = getattr(different_config, property_name) + setattr(copy_config, property_name, property_value) + assert copy_config != base_config + + assert len(config_properties) == 23, "Don't forget to update tests and the config == operator!" + def test_copy_config(complete_config_string: str) -> None: """Check that copy() works.""" diff --git a/python/tests/test_metadata.py b/python/tests/test_metadata.py index 8d121c4a..61cd07ed 100644 --- a/python/tests/test_metadata.py +++ b/python/tests/test_metadata.py @@ -8,6 +8,7 @@ import json import numpy import pytest +import inspect from ouster import client @@ -188,3 +189,21 @@ def test_parse_info() -> None: metadata['lidar_origin_to_beam_origin_mm'] = 'foo' with pytest.raises(RuntimeError): client.SensorInfo(json.dumps(metadata)) + + +def test_info_length() -> None: + """Check length of info to ensure we've added appropriately to the == operator""" + + info_attributes = inspect.getmembers(client.SensorInfo, lambda a: not inspect.isroutine(a)) + info_properties = [a for a in info_attributes if not (a[0].startswith('__') and a[0].endswith('__'))] + + assert len(info_properties) == 15, "Don't forget to update tests and the sensor_info == operator!" + + +def test_equality_format() -> None: + """Check length of data format to ensure we've added appropriately to the == operator""" + + data_format_attributes = inspect.getmembers(client.DataFormat, lambda a: not inspect.isroutine(a)) + data_format_properties = [a for a in data_format_attributes if not (a[0].startswith('__') and a[0].endswith('__'))] + + assert len(data_format_properties) == 7, "Don't forget to update tests and the data_format == operator!"