Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 8 additions & 2 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
Changelog
=========

[unreleased]
============
[20230114]
==========

ouster_client
--------------
Expand All @@ -20,13 +20,19 @@ ouster_client
* added a new method ``init_logger()`` to provide control over the logs emitted by ``ouster_client``.
* add parsing for new FW 3.0 thermal features shot_limiting and thermal_shutdown statuses and countdowns
* add frame_status to LidarScan
* introduce a new method ``cartesianT()`` which speeds up the computation of point projecion from range
image, the method also can process the cartesian product with single float precision. A new unit test
``cartesian_test`` which shows achieved speed up gains by the number of valid returns in lidar scan.
* add ``RAW_HEADERS`` ChanField to LidarScan for packing headers and footer (alpha version, may be
changed/removed without notice in the future)

python
------
* breaking change: drop defaults parameters of ``client.Sensor`` constructor.
* breaking change: change Scans interface Timeout to default to 1 second instead of None
* added a new method ``init_logger()`` to provide control over the logs emitted by ``client.Sensor``.
* add ``client.LidarScan`` methods ``__repr__()`` and ``__str__()``.
* changed default timeout from 1 seconds to 2 seconds

ouster_viz
----------
Expand Down
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@ include(DefaultBuildType)
include(VcpkgEnv)

# ==== Project Name ====
project(ouster_example VERSION 20220927)
project(ouster_example VERSION 20230114)

# generate version header
set(OusterSDK_VERSION_STRING 0.7.1.b1)
set(OusterSDK_VERSION_STRING 0.7.1)
include(VersionGen)

# ==== Options ====
Expand Down
2 changes: 1 addition & 1 deletion conanfile.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ def configure_cmake(self):
cmake = CMake(self)
cmake.definitions["BUILD_VIZ"] = self.options.build_viz
cmake.definitions["BUILD_PCAP"] = self.options.build_pcap
cmake.definitions["USE_EIGEN_MAX_ALIGN_BYTES_32"] = self.options.eigen_max_align_bytes
cmake.definitions["OUSTER_USE_EIGEN_MAX_ALIGN_BYTES_32"] = self.options.eigen_max_align_bytes
# alt way, but we use CMAKE_TOOLCHAIN_FILE in other pipeline so avoid overwrite
# cmake.definitions["CMAKE_TOOLCHAIN_FILE"] = os.path.join(self.build_folder, "conan_paths.cmake")
cmake.definitions[
Expand Down
4 changes: 2 additions & 2 deletions docs/cpp/building.rst
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ On macOS, install XCode and `homebrew <https://brew.sh>`_ and run:

.. code:: console
$ brew install cmake pkg-config jsoncpp eigen curl libtins glfw glew
$ brew install cmake pkg-config jsoncpp eigen curl libtins glfw glew spdlog
To build run the following commands:

Expand Down Expand Up @@ -79,7 +79,7 @@ You should be able to install dependencies with

.. code:: powershell
PS > .\vcpkg.exe install --triplet x64-windows jsoncpp eigen3 curl libtins glfw3 glew
PS > .\vcpkg.exe install --triplet x64-windows jsoncpp eigen3 curl libtins glfw3 glew spdlog
After these steps are complete, you should be able to open, build and run the ``ouster_example``
project using Visual Studio:
Expand Down
2 changes: 1 addition & 1 deletion docs/installation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
Ouster SDK Installation
=======================

Please proceed to the instructions for your language and platform of choice. Newer users may find the Python SDK more approachable.
Please proceed to the instructions for your programming language and platform of choice.

.. contents::
:local:
Expand Down
4 changes: 2 additions & 2 deletions docs/python/devel.rst
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ On macos >= 10.13, using homebrew, you should be able to run:

.. code:: console
$ brew install cmake eigen curl jsoncpp libtins python3 pybind11 glfw glew
$ brew install cmake eigen curl jsoncpp libtins python3 pybind11 glfw glew spdlog
After you have the system dependencies, you can build the SDK with:

Expand Down Expand Up @@ -74,7 +74,7 @@ package manager and run:

.. code:: powershell
PS > vcpkg install --triplet=x64-windows eigen3 jsoncpp libtins pybind11 glfw3 glad[gl-api-33]
PS > vcpkg install --triplet=x64-windows eigen3 jsoncpp libtins pybind11 glfw3 glad[gl-api-33] spdlog
The currently tested vcpkg tag is ``2022.02.23``. After that, using a developer powershell prompt:

Expand Down
2 changes: 1 addition & 1 deletion docs/reference/lidar-scan.rst
Original file line number Diff line number Diff line change
Expand Up @@ -231,4 +231,4 @@ both sampling, used in :ref:`ex-visualization-with-matplotlib`, and streaming, u
Under the hood, this class batches packets into ``LidarScans``. C++ users must batch packets
themselves using the :cpp:class:`ouster::ScanBatcher` class. To get a feel for how to use it, we recommend
reading `this example on Github
<https://github.com/ouster-lidar/ouster_example/blob/master/ouster_client/src/example.cpp#L83>`_.
<https://github.com/ouster-lidar/ouster_example/blob/master/examples/client_example.cpp#L93>`_.
27 changes: 5 additions & 22 deletions docs/sample-data.rst
Original file line number Diff line number Diff line change
Expand Up @@ -13,33 +13,16 @@ Download Data
..
[start-download-instructions]

Download one of the following samples of recorded Ouster data and unzip the contents:

.. _dual-returns-snippets:

* `OS0 128 Rev 06 Urban Drive (Dual Returns)`_ [151 MB] (`preview OS0 <https://data.ouster.dev/share/QBBY706GG0R6ZOG1?utm_source=sdk&utm_medium=sdk>`_)
* `OS1 128 Rev 06 Urban Drive (Dual Returns)`_ [173 MB] (`preview OS1 <https://data.ouster.dev/share/D03HJ28ZX3245FQQ?utm_source=sdk&utm_medium=sdk>`_)
* `OS2 128 Rev 06 Urban Drive (Dual Returns)`_ [190 MB] (`preview OS2 <https://data.ouster.dev/share/NNRMR0PCGVEMQKYM?utm_source=sdk&utm_medium=sdk>`_)
* `OS1 128 Rev 06 Urban Drive (Low Bandwidth)`_ [95 MB] (`preview OS1 LB <https://data.ouster.dev/share/SORYN8B6OAF0BVDL?utm_source=sdk?utm_medium=sdk&frame=53>`_)
* `OS2 128 Rev 05 Bridge`_ [82 MB] (`preview bridge <https://data.ouster.dev/share/U7W1P8MFUEOKT61G?utm_source=sdk&utm_medium=sdk>`_)


.. _OS0 128 Rev 06 Urban Drive (Dual Returns): https://data.ouster.io/sdk-samples/Rev-06-fw23/OS0-128_Rev-06_fw23_Urban-Drive_Dual-Returns.zip
.. _OS1 128 Rev 06 Urban Drive (Dual Returns): https://data.ouster.io/sdk-samples/Rev-06-fw23/OS1-128_Rev-06_fw23_Urban-Drive_Dual-Returns.zip
.. _OS2 128 Rev 06 Urban Drive (Dual Returns): https://data.ouster.io/sdk-samples/Rev-06-fw23/OS2-128_Rev-06_fw23_Urban-Drive_Dual-Returns.zip
.. _OS1 128 Rev 06 Urban Drive (Low Bandwidth): https://data.ouster.io/sdk-samples/Rev-06-fw23/OS1-128_Rev-06_fw23_Urban-Drive_Low-Bandwidth.zip
.. _OS2 128 Rev 05 Bridge: https://data.ouster.io/sdk-samples/Rev-05/OS2-128_Rev-05_Bridge/OS2-128_Rev-05_Bridge.zip

In your unzipped directory, you should have two files, one ``.pcap`` file and one ``.json`` file.
For example, in the unzipped recorded sample of OS1-128 Rev 06 data you should find:

* ``OS1-128_Rev-06_fw23_Urban-Drive_Dual-Returns.pcap``
* ``OS1-128_Rev-06_fw23_Urban-Drive_Dual-Returns.json``
You can download sample data from the `sensor documentation`_ by clicking through the Ouster Data
App links and using the Download button. After download, you should have two files, a ``.pcap`` file
and a ``.json`` file.

We will use ``SAMPLE_DATA_PCAP_PATH`` to refer to this pcap and ``SAMPLE_DATA_JSON_PATH`` to this
json in the following. You may find it convenient to assign the paths appropriately in your
console.

.. _sensor documentation: https://static.ouster.dev/sensor-docs/#sample-data

..
[end-download-instructions]

Expand Down
5 changes: 2 additions & 3 deletions examples/representations_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,10 +154,9 @@ int main(int argc, char* argv[]) {
std::to_string(print_column) + ")";

std::cerr << "In the staggered image, the point at " << point_string
<< " has reflectivity " << reflectivity(print_row, print_row)
<< " has reflectivity " << reflectivity(print_row, print_column)
<< " and an x coordinate of "
<< x_image_staggered(print_column, print_column) << "."
<< std::endl;
<< x_image_staggered(print_row, print_column) << "." << std::endl;
std::cerr << "In the destagged image, the point at " << point_string
<< " has reflectivity "
<< reflectivity_destaggered(print_row, print_column)
Expand Down
74 changes: 74 additions & 0 deletions ouster_client/include/ouster/impl/cartesian.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
#pragma once

#include <ouster/lidar_scan.h>

namespace ouster {

// Users can enable OpenMP within ouster_client by first enabling omp through
// the compiler and then adding '-DOUSTER_OMP' option to the DCMAKE_CXX_FLAGS
#if defined(OUSTER_OMP)
#if defined(_OPENMP)
#define __OUSTER_UTILIZE_OPENMP__
#else
#pragma message("OUSTER_OMP was defined but openmp is not detected!")
#endif
#endif

template <typename T>
using PointsT = Eigen::Array<T, -1, 3>;
using PointsD = PointsT<double>;
using PointsF = PointsT<float>;

/**
* Converts a staggered range image to Cartesian points.
*
* @param[in, out] points The resulting point cloud, should be pre-allocated and
* have the same dimensions as the direction array.
* @param[in] range a range image in the same format as the RANGE field of a
* LidarScan.
* @param[in] direction the direction of an xyz lut.
* @param[in] offset the offset of an xyz lut.
*
* @return Cartesian points where ith row is a 3D point which corresponds
* to ith pixel in LidarScan where i = row * w + col.
*/
template <typename T>
void cartesianT(PointsT<T>& points,
const Eigen::Ref<const img_t<uint32_t>>& range,
const PointsT<T>& direction, const PointsT<T>& offset) {
assert(points.rows() == direction.rows() &&
"points & direction row count mismatch");
assert(points.rows() == offset.rows() &&
"points & offset row count mismatch");
assert(points.rows() == range.size() &&
"points and range image size mismatch");

const auto pts = points.data();
const auto* const rng = range.data();
const auto* const dir = direction.data();
const auto* const ofs = offset.data();

const auto N = range.size();
const auto col_x = 0 * N; // 1st column of points (x)
const auto col_y = 1 * N; // 2nd column of points (y)
const auto col_z = 2 * N; // 3rd column of points (z)

#ifdef __OUSTER_UTILIZE_OPENMP__
#pragma omp parallel for schedule(static)
#endif
for (auto i = 0; i < N; ++i) {
const auto r = rng[i];
const auto idx_x = col_x + i;
const auto idx_y = col_y + i;
const auto idx_z = col_z + i;
if (r == 0) {
pts[idx_x] = pts[idx_y] = pts[idx_z] = static_cast<T>(0.0);
} else {
pts[idx_x] = r * dir[idx_x] + ofs[idx_x];
pts[idx_y] = r * dir[idx_y] + ofs[idx_y];
pts[idx_z] = r * dir[idx_z] + ofs[idx_z];
}
}
}

} // namespace ouster
4 changes: 3 additions & 1 deletion ouster_client/include/ouster/lidar_scan.h
Original file line number Diff line number Diff line change
Expand Up @@ -519,7 +519,8 @@ inline img_t<T> stagger(const Eigen::Ref<const img_t<T>>& img,
class ScanBatcher {
std::ptrdiff_t w;
std::ptrdiff_t h;
uint16_t next_m_id;
uint16_t next_valid_m_id;
uint16_t next_headers_m_id;
std::vector<uint8_t> cache;
bool cached_packet = false;

Expand Down Expand Up @@ -555,4 +556,5 @@ class ScanBatcher {

} // namespace ouster

#include "ouster/impl/cartesian.h"
#include "ouster/impl/lidar_scan_impl.h"
33 changes: 33 additions & 0 deletions ouster_client/include/ouster/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -655,6 +655,13 @@ std::string to_string(ShotLimitingStatus shot_limiting_status);
*/
std::string to_string(ThermalShutdownStatus thermal_shutdown_status);

/**
* Determine validity of provided signal multiplier value
*
* @param[in] signal_multiplier Signal multiplier value.
*/
void check_signal_multiplier(const double signal_multiplier);

/**
* Parse metadata text blob from the sensor into a sensor_info struct.
*
Expand Down Expand Up @@ -747,6 +754,7 @@ enum ChanField {
NEAR_IR = 7, ///< near_ir in photons
FLAGS = 8, ///< 1st return flags
FLAGS2 = 9, ///< 2nd return flags
RAW_HEADERS = 40, ///< raw headers for packet/footer/column for dev use
CUSTOM0 = 50, ///< custom user field
CUSTOM1 = 51, ///< custom user field
CUSTOM2 = 52, ///< custom user field
Expand Down Expand Up @@ -779,6 +787,15 @@ std::string to_string(ChanField field);
*/
enum ChanFieldType { VOID = 0, UINT8, UINT16, UINT32, UINT64 };

/**
* Get the size of the ChanFieldType in bytes.
*
* @param[in] ft the field type
*
* @return size of the field type in bytes
*/
size_t field_type_size(ChanFieldType ft);

/**
* Get string representation of a channel field.
*
Expand Down Expand Up @@ -827,6 +844,12 @@ class packet_format final {
const int pixels_per_column; ///< pixels per column for lidar
[[deprecated]] const int encoder_ticks_per_rev; ///< @deprecated

const size_t packet_header_size;
const size_t col_header_size;
const size_t col_footer_size;
const size_t col_size;
const size_t packet_footer_size;

/**
* Read the packet type packet header.
*
Expand Down Expand Up @@ -919,6 +942,16 @@ class packet_format final {
*/
FieldIter end() const;

/**
* Get pointer to the packet footer of a lidar buffer.
*
* @param[in] lidar_buf the lidar buffer.
*
* @return pointer to packet footer of lidar buffer, can be nullptr if
* packet format doesn't have packet footer.
*/
const uint8_t* footer(const uint8_t* lidar_buf) const;

// Measurement block accessors
/**
* Get pointer to nth column of a lidar buffer.
Expand Down
44 changes: 36 additions & 8 deletions ouster_client/src/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <cctype>
#include <cerrno>
#include <chrono>
#include <cmath>
#include <cstdio>
#include <cstring>
#include <fstream>
Expand Down Expand Up @@ -215,14 +216,13 @@ bool set_config(const std::string& hostname, const sensor_config& config,
// Signal multiplier changed from int to double for FW 3.0/2.5+, with
// corresponding change to config.signal_multiplier.
// Change values 1, 2, 3 back to ints to support older FWs
if (config_params["signal_multiplier"].asDouble() != 0.25 &&
config_params["signal_multiplier"].asDouble() != 0.5) {
config_params["signal_multiplier"] =
config_params["signal_multiplier"].asInt();
// TODO: figure out what to do when people enter invalid signal
// multiplier values between 1 and 3.99. Invalid decimal values <1 and
// >4 will be invalid in any case and the error message won't say so
// those are fine
if (config_json.isMember("signal_multiplier")) {
check_signal_multiplier(config_params["signal_multiplier"].asDouble());
if (config_params["signal_multiplier"].asDouble() != 0.25 &&
config_params["signal_multiplier"].asDouble() != 0.5) {
config_params["signal_multiplier"] =
config_params["signal_multiplier"].asInt();
}
}

// set automatic udp dest, if flag specified
Expand Down Expand Up @@ -279,6 +279,34 @@ std::string get_metadata(client& cli, int timeout_sec, bool legacy_format) {
builder["precision"] = 6;
builder["indentation"] = " ";
auto metadata_string = Json::writeString(builder, cli.meta);
if (legacy_format) {
logger().warn(
"The SDK will soon output the non-legacy metadata format by "
"default. If you parse the metadata directly instead of using the "
"SDK (which will continue to read both legacy and non-legacy "
"formats), please be advised that on the next release you will "
"either have to update your parsing or specify legacy_format = "
"true to the get_metadata function.");
}

// We can't insert this logic into the light init_client since its advantage
// is that it doesn't make netowrk calls but we need it to run every time
// there is a valid connection to the sensor So we insert it here
// TODO: remove after release of FW 3.2/3.3 (sufficient warning)
sensor_config config;
get_config(cli.hostname, config);
auto fw_version = SensorHttp::firmware_version(cli.hostname);
// only warn for people on the latest FW, as people on older FWs may not
// care
if (fw_version.major >= 3 &&
config.udp_profile_lidar == UDPProfileLidar::PROFILE_LIDAR_LEGACY) {
logger().warn(
"Please note that the Legacy Lidar Profile will be deprecated "
"in the sensor FW soon. If you plan to upgrade your FW, we "
"recommend using the Single Return Profile instead. For users "
"sticking with older FWs, the Ouster SDK will continue to parse "
"the legacy lidar profile.");
}
return legacy_format ? convert_to_legacy(metadata_string) : metadata_string;
}

Expand Down
1 change: 0 additions & 1 deletion ouster_client/src/curl_client.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include <curl/curl.h>

#include <cstring>
#include <iostream>

#include "http_client.h"

Expand Down
Loading