Skip to content

Commit

Permalink
Add support for dual returns in sample ROS driver
Browse files Browse the repository at this point in the history
Data from the second return will be published as separate point cloud
and image topics when configured. The launch file now takes an
additional `udp_profile_lidar` parameter to set the packet profile on
startup.

Other changes:
* The supported vcpkg version has been updated to 2021.05.12
* Windows Python extensions are now built with VS 2017, per the
  packaging guidelines
* Improved heuristics for detecting lidar data in pcap files in the
  Python sdk
  • Loading branch information
Dima Garbuzov authored and dmitrig committed Dec 30, 2021
1 parent 3e6af59 commit ad837d0
Show file tree
Hide file tree
Showing 109 changed files with 2,796 additions and 2,266 deletions.
17 changes: 14 additions & 3 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -6,17 +6,20 @@ Changelog
[unreleased]
============

* update supported vcpkg tag to 2021.05.12
* add preliminary cpack and install support. It should be possible to use a pre-built SDK package
instead of including the SDK in the build tree of your project

ouster_client
-------------
* update cmake package version to 0.3.0
* avoid unnecessary DNS lookup when using numeric addresses with ``init_client()``
* disable collecting metadata when sensor is in STANDBY mode
* breaking change: ``set_config()`` will now produce more informative errors by throwing
``std::invalid_argument`` with an error message when config parameters fail validation
* use ``SO_REUSEPORT`` for UDP sockets on non-windows platforms.
* use ``SO_REUSEPORT`` for UDP sockets on non-windows platforms
* the set of fields available on ``LidarScan`` is now configurable. See the new ``LidarScan``
constructors for details.
constructors for details
* added ``RANGE2``, ``SIGNAL2`` and ``REFLECTIVITY2`` channel fields to support handling data from
the second return
* ``ScanBatcher`` will now parse and populate only the channel fields configured on the
Expand Down Expand Up @@ -56,6 +59,9 @@ ouster_pcap

ouster_ros
----------
* update ROS package version to 0.3.0
* allow setting the packet profile in ouster.launch with the ``udp_profile_lidar`` parameter
* publish additional cloud and image topics for the second return when running in dual returns mode
* fix ``os_node`` crash on shutdown due to Eigen alignment flag not being propogated by catkin
* update ROS package version to 0.2.1
* the ``udp_dest`` parameter to ouster.launch is now optional when connecting to a sensor
Expand All @@ -67,7 +73,12 @@ ouster_viz

python
------
* update ouster-sdk version to 0.3.0
* update ouster-sdk version to 0.3.0b3
* improve heuristics for identifying sensor data in pcaps, including new packet formats
* release builds for wheels on Windows now use the VS 2017 toolchain and runtime (previously 2019)
* fix potential use-after-free in ``LidarScan.fields``
* update ouster-sdk version to 0.3.0b1
* return an error when attempting to initialize ``client.Sensor`` in STANDBY mode
* check for errors while reading from a ``Sensor`` packet source and waiting for a timeout. This
should make stopping a process with ``SIGINT`` more reliable
* add PoC bindings for the ``ouster_viz`` library with a simple example driver. See the
Expand Down
8 changes: 6 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,12 @@ if(BUILD_VIZ)
add_subdirectory(ouster_viz)
endif()

if(CMAKE_PROJECT_NAME STREQUAL PROJECT_NAME AND BUILD_TESTING)
add_subdirectory(tests)
if(CMAKE_PROJECT_NAME STREQUAL PROJECT_NAME)
message(STATUS "Ouster SDK client: Using EIGEN_MAX_ALIGN_BYTES = 32")
target_compile_definitions(ouster_client PUBLIC EIGEN_MAX_ALIGN_BYTES=32)
if(BUILD_TESTING)
add_subdirectory(tests)
endif()
endif()

# ==== Install ====
Expand Down
15 changes: 8 additions & 7 deletions README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,10 @@ for dependencies. Follow the official documentation to set up your build environ
<https://docs.microsoft.com/en-us/cpp/build/cmake-projects-in-visual-studio?view=vs-2019>`_
* `Visual Studio CPP Support
<https://docs.microsoft.com/en-us/cpp/build/vscpp-step-0-installation?view=vs-2019>`_
* `Vcpkg, at tag "2020.11-1" installed and integrated with Visual Studio
* `Vcpkg, at tag "2021.05.12" installed and integrated with Visual Studio
<https://docs.microsoft.com/en-us/cpp/build/vcpkg?view=msvc-160#installation>`_

**Note** You'll need to run ``git checkout 2020.11-1`` in the vcpkg directory before bootstrapping
**Note** You'll need to run ``git checkout 2021.05.12`` in the vcpkg directory before bootstrapping
to use the correct versions of the dependencies. Building may fail unexpectedly if you skip this
step.

Expand Down Expand Up @@ -141,13 +141,14 @@ keyboard:
Keyboard controls:

============= ============================================
key what it does
Key What it does
============= ============================================
``p`` Increase point size
``o`` Decrease point size
``m`` Cycle point cloud coloring mode
``v`` Toggle range cycling
``n`` Toggle display near-IR image from the sensor
``b`` Cycle top 2D image
``n`` Cycle bottom 2D image
``shift + r`` Reset camera
``e`` Change size of displayed 2D images
``;`` Increase spacing in range markers
Expand All @@ -157,7 +158,8 @@ Keyboard controls:
``s`` Camera pitch down
``a`` Camera yaw left
``d`` Camera yaw right
``1`` Toggle point cloud visibility
``1`` Toggle first return point cloud visibility
``2`` Toggle second return point cloud visibility
``0`` Toggle orthographic camera
``=`` Zoom in
``-`` Zoom out
Expand All @@ -182,8 +184,7 @@ Building

The build dependencies include those of the sample code::

sudo apt install build-essential cmake libglfw3-dev libglew-dev libeigen3-dev \
libjsoncpp-dev libtclap-dev
sudo apt install build-essential cmake libeigen3-dev libjsoncpp-dev

Additionally, you should install the ros dependencies::

Expand Down
49 changes: 40 additions & 9 deletions cmake/FindGTest.cmake
Original file line number Diff line number Diff line change
@@ -1,19 +1,50 @@
# Attempt to deal with gtest cmake differences across platforms

function(find_gtest)
# use system find module in this scope
set(CMAKE_MODULE_PATH "")

find_package(GTest QUIET)
# using the cmake-provided find module succeeds, but the resulting GTest::GTest and
# GTest::Maintargets cause link errors with vcpkg 2021.05.12 on macos. Try CONFIG-only first
find_package(GTest CONFIG QUIET)

if(GTEST_FOUND)
find_package_handle_standard_args(GTest DEFAULT_MSG GTEST_LIBRARY)
else()
message(STATUS "Looking for GTest source in /usr/src/gtest")
add_subdirectory("/usr/src/gtest" gtest)
add_library(GTest::GTest ALIAS gtest)
add_library(GTest::Main ALIAS gtest_main)
message(STATUS "Found GTest source")
if (GTest_CONFIG AND TARGET GTest::gtest AND TARGET GTest::gtest_main)
find_package_handle_standard_args(GTest DEFAULT_MSG GTest_CONFIG)
return()
endif()

# next, try using a find module. Requires temporarily turning off REQUIRED to avoid failing at the
# call to find_package()
set(GTest_FIND_REQUIRED_SAVED ${GTest_FIND_REQUIRED})
set(GTest_FIND_REQUIRED 0)
find_package(GTest MODULE QUIET)
set(GTest_FIND_REQUIRED ${GTest_FIND_REQUIRED_SAVED})

if (GTEST_FOUND)
find_package_handle_standard_args(GTest DEFAULT_MSG GTEST_LIBRARY GTEST_MAIN_LIBRARY)

# aliases to cmake >= 3.20 targets. More portable than IMPORTED_GLOBAL
# https://cmake.org/cmake/help/v3.22/module/FindGTest.html#imported-targets
if(NOT TARGET GTest::gtest)
add_library(GTest::gtest INTERFACE IMPORTED)
target_link_libraries(GTest::gtest INTERFACE GTest::GTest)
endif()
if(NOT TARGET GTest::gtest_main)
add_library(GTest::gtest_main INTERFACE IMPORTED)
target_link_libraries(GTest::gtest_main INTERFACE GTest::Main)
endif()

return()
endif()

# finally, try src location for libgtest-dev for debian-based distros where
# the find module appears to be broken (xenial, bionic)
find_path(GTEST_ROOT CMakeLists.txt "/usr/src/gtest")
find_package_handle_standard_args(GTest DEFAULT_MSG GTEST_ROOT)
add_subdirectory(${GTEST_ROOT} gtest)
add_library(GTest::gtest ALIAS gtest)
add_library(GTest::gtest_main ALIAS gtest_main)

endfunction()

find_gtest()
4 changes: 2 additions & 2 deletions ouster_client/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.1.0)

# ==== Project Name ====
project(ouster_client VERSION 0.3.0)
set(ouster_client_VERSION_SUFFIX ".dev2")
set(ouster_client_VERSION_SUFFIX "b3")

# ==== Requirements ====
find_package(Eigen3 REQUIRED)
Expand Down Expand Up @@ -30,7 +30,7 @@ add_library(ouster_client src/client.cpp src/types.cpp src/netcompat.cpp src/lid
target_link_libraries(ouster_client
PUBLIC Eigen3::Eigen $<BUILD_INTERFACE:ouster_build>
PRIVATE jsoncpp_lib)
target_compile_definitions(ouster_client PUBLIC EIGEN_MAX_ALIGN_BYTES=32 PRIVATE EIGEN_MPL2_ONLY)
target_compile_definitions(ouster_client PRIVATE EIGEN_MPL2_ONLY)
add_library(OusterSDK::ouster_client ALIAS ouster_client)

if(WIN32)
Expand Down
16 changes: 16 additions & 0 deletions ouster_client/include/ouster/buffered_udp_source.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ class BufferedUDPSource {
// client handle
std::mutex cli_mtx_;
std::shared_ptr<ouster::sensor::client> cli_;
uint32_t lidar_port_;
uint32_t imu_port_;

// protect read/write_ind_ and stop_
std::mutex cv_mtx_;
Expand Down Expand Up @@ -140,6 +142,20 @@ class BufferedUDPSource {
* @param pf the packet format associated with the UDP stream
*/
void produce(const ouster::sensor::packet_format& pf);

/**
* Return the port used to listen for lidar UDP data
*
* @return the lidar UDP port or 0 if shut down
*/
int get_lidar_port();

/**
* Return the port used to listen for imu UDP data
*
* @return the lidar UDP port or 0 if shut down
*/
int get_imu_port();
};

} // namespace impl
Expand Down
16 changes: 15 additions & 1 deletion ouster_client/include/ouster/client.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,6 @@ std::string get_metadata(client& cli, int timeout_sec = 60,
bool get_config(const std::string& hostname, sensor_config& config,
bool active = true);


/**
* Flags for set_config()
*/
Expand All @@ -137,5 +136,20 @@ enum config_flags : uint8_t {
*/
bool set_config(const std::string& hostname, const sensor_config& config,
uint8_t config_flags = 0);

/**
* Return the port used to listen for lidar UDP data
*
* @param cli client returned by init_client associated with the connection
*/
int get_lidar_port(client& cli);

/**
* Return the port used to listen for imu UDP data
*
* @param cli client returned by init_client associated with the connection
*/
int get_imu_port(client& cli);

} // namespace sensor
} // namespace ouster
2 changes: 1 addition & 1 deletion ouster_client/include/ouster/image_processing.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

#pragma once

#include <Eigen/Dense>
#include <Eigen/Core>
#include <vector>

#include "ouster/types.h"
Expand Down
16 changes: 16 additions & 0 deletions ouster_client/include/ouster/impl/lidar_scan_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
#include <cstdint>
#include <stdexcept>

#include <Eigen/Core>

#include "ouster/lidar_scan.h"
#include "ouster/types.h"

Expand Down Expand Up @@ -52,15 +54,19 @@ struct FieldSlot {
break;
case ChanFieldType::UINT8:
new (&f8) img_t<uint8_t>{h, w};
f8.setZero();
break;
case ChanFieldType::UINT16:
new (&f16) img_t<uint16_t>{h, w};
f16.setZero();
break;
case ChanFieldType::UINT32:
new (&f32) img_t<uint32_t>{h, w};
f32.setZero();
break;
case ChanFieldType::UINT64:
new (&f64) img_t<uint64_t>{h, w};
f64.setZero();
break;
}
}
Expand Down Expand Up @@ -225,6 +231,16 @@ inline Eigen::Ref<const img_t<uint64_t>> FieldSlot::get_unsafe() const {
/*
* Call a generic operation op<T>(f, Args..) with the type parameter T having
* the correct (dynamic) field type for the LidarScan channel field f
* Example code for the operation<T>:
* \code
* struct print_field_size {
* template <typename T>
* void operator()(Eigen::Ref<img_t<T>> field) {
* std::cout << "Rows: " + field.rows() << std::endl;
* std::cout << "Cols: " + field.cols() << std::endl;
* }
* };
* \endcode
*/
template <typename SCAN, typename OP, typename... Args>
void visit_field(SCAN&& ls, sensor::ChanField f, OP&& op, Args&&... args) {
Expand Down
19 changes: 13 additions & 6 deletions ouster_client/include/ouster/lidar_scan.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

#pragma once

#include <Eigen/Dense>
#include <Eigen/Core>
#include <chrono>
#include <cstddef>
#include <map>
Expand Down Expand Up @@ -225,7 +225,7 @@ struct XYZLut {
};

/**
* Generate a set of lookup tables useful for computing cartesian coordinates
* Generate a set of lookup tables useful for computing Cartesian coordinates
* from ranges.
*
* The lookup tables are:
Expand Down Expand Up @@ -267,21 +267,21 @@ inline XYZLut make_xyz_lut(const sensor::sensor_info& sensor) {
}

/**
* Convert LidarScan to cartesian points.
* Convert LidarScan to Cartesian points.
*
* @param scan a LidarScan
* @param xyz_lut lookup tables generated by make_xyz_lut
* @return cartesian points where ith row is a 3D point which corresponds
* @return Cartesian points where ith row is a 3D point which corresponds
* to ith pixel in LidarScan where i = row * w + col
*/
LidarScan::Points cartesian(const LidarScan& scan, const XYZLut& lut);

/**
* Convert a staggered range image to cartesian points.
* Convert a staggered range image to Cartesian points.
*
* @param a range image in the same format as the RANGE field of a LidarScan
* @param xyz_lut lookup tables generated by make_xyz_lut
* @return cartesian points where ith row is a 3D point which corresponds
* @return Cartesian points where ith row is a 3D point which corresponds
* to ith pixel in LidarScan where i = row * w + col
*/
LidarScan::Points cartesian(const Eigen::Ref<const img_t<uint32_t>>& range,
Expand Down Expand Up @@ -345,6 +345,13 @@ class ScanBatcher {
*/
ScanBatcher(size_t w, const sensor::packet_format& pf);

/**
* Create a batcher given information about the scan and packet format.
*
* @param info sensor metadata returned from the client
*/
ScanBatcher(const sensor::sensor_info& info);

/**
* Add a packet to the scan.
*
Expand Down
6 changes: 4 additions & 2 deletions ouster_client/include/ouster/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

#pragma once

#include <Eigen/Dense>
#include <Eigen/Core>
#include <array>
#include <cstdint>
#include <map>
Expand Down Expand Up @@ -400,6 +400,8 @@ enum ChanField {
REFLECTIVITY2 = 6,
AMBIENT = 7, // deprecated
NEAR_IR = 7,
FLAGS = 8,
FLAGS2 = 9,
CHAN_FIELD_MAX = 64,
};

Expand Down Expand Up @@ -498,7 +500,7 @@ class packet_format final {
* Copy the specified channel field out of a packet measurement block.
*
* T should be an unsigned integer type large enough to store values of the
* specified field.
* specified field. Otherwise, data will be truncated.
*
* @param col_buf a measurement block pointer returned by `nth_col()`
* @param field the channel field to copy
Expand Down
Loading

0 comments on commit ad837d0

Please sign in to comment.