Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed Windows shared libraries build & added CI #608

Open
wants to merge 8 commits into
base: master
Choose a base branch
from
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
19 changes: 19 additions & 0 deletions .github/workflows/build_test.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,25 @@ jobs:
run: cmake --build build -j4
- name: run tests
run: cd build/ && ctest -j4 -C Debug --output-on-failure
windows-shared-libs-build:
runs-on: windows-latest
steps:
- uses: actions/checkout@v1
- name: vcpkg build
uses: johnwason/vcpkg-action@v6
id: vcpkg
with:
pkgs: jsoncpp eigen3 curl libtins glfw3 glew spdlog libpng flatbuffers gtest
triplet: x64-windows
revision: 2024.04.26
token: ${{ github.token }}
github-binarycache: true
- name: cmake configure
run: cmake . -B build -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON -DBUILD_SHARED_LIBS=ON -DCMAKE_TOOLCHAIN_FILE=D:/a/ouster-sdk/ouster-sdk/vcpkg/scripts/buildsystems/vcpkg.cmake
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What is D:/a?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just an absolute path which I had to use to get this to work, see the step above.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We could probably parameterize the BUILD_SHARED_LIBS rather than duplicating the build step.

Copy link
Author

@eivan eivan Aug 22, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Agreed. I'm not too familiar with this CI, excuse my shabby solution.

- name: cmake build
run: cmake --build build -j4
- name: run tests
run: cd build/ && ctest -j4 -C Debug --output-on-failure
windows-python-build:
runs-on: windows-latest
steps:
Expand Down
14 changes: 14 additions & 0 deletions ouster_client/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ find_package(jsoncpp REQUIRED)
find_package(CURL REQUIRED)
find_package(spdlog REQUIRED)
include(Coverage)
include(GenerateExportHeader)

# ==== Libraries ====
add_library(ouster_client src/client.cpp src/types.cpp src/sensor_info.cpp src/netcompat.cpp src/lidar_scan.cpp
Expand Down Expand Up @@ -41,6 +42,19 @@ target_include_directories(ouster_client SYSTEM PUBLIC
$<INSTALL_INTERFACE:include/optional-lite>
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include/optional-lite>)

# ==== Export header ====

set(ouster_client_export_filename
ouster_client/ouster/ouster_client_export.h)

generate_export_header(ouster_client
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Generating ouster_client_export.h here, on CMAKE build, using a standard CMAKE approach.
Then, I'm using OUSTER_CLIENT_EXPORT in code to export the symbols, a macro is defined in the generated header, marking functions, classes, etc.
During a Windows build this basically translates to __declspec(__dllexport). With this macro one can fine-tune which symbols to export.

For ouster_osf, ouster_pcap and ouster_viz It seemed safe to just go with exporting all symbols, see this line as an example:

set_property (TARGET ouster_osf PROPERTY WINDOWS_EXPORT_ALL_SYMBOLS ON)

EXPORT_FILE_NAME ${PROJECT_BINARY_DIR}/${ouster_client_export_filename})

target_include_directories(ouster_client PUBLIC
$<BUILD_INTERFACE:${PROJECT_BINARY_DIR}/ouster_client>)

install(FILES ${PROJECT_BINARY_DIR}/${ouster_client_export_filename} DESTINATION include/ouster)

# ==== Install ====
install(TARGETS ouster_client
EXPORT ouster-sdk-targets
Expand Down
59 changes: 34 additions & 25 deletions ouster_client/include/ouster/client.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <string>

#include "ouster/defaults.h"
#include "ouster/ouster_client_export.h"
#include "ouster/types.h"
#include "ouster/version.h"

Expand Down Expand Up @@ -57,9 +58,11 @@ const util::version min_version = {1, 12, 0, "", "", "", ""};
*
* @return true on success, otherwise false.
*/
bool init_logger(const std::string& log_level,
const std::string& log_file_path = "", bool rotating = false,
int max_size_in_bytes = 0, int max_files = 0);
OUSTER_CLIENT_EXPORT bool init_logger(const std::string& log_level,
const std::string& log_file_path = "",
bool rotating = false,
int max_size_in_bytes = 0,
int max_files = 0);

/** \defgroup ouster_client_init Ouster Client Client Initialization
* @{
Expand All @@ -74,8 +77,8 @@ bool init_logger(const std::string& log_level,
*
* @return pointer owning the resources associated with the connection.
*/
std::shared_ptr<client> init_client(const std::string& hostname, int lidar_port,
int imu_port);
OUSTER_CLIENT_EXPORT std::shared_ptr<client> init_client(
const std::string& hostname, int lidar_port, int imu_port);

/**
* Connect to and configure the sensor and start listening for data.
Expand All @@ -94,7 +97,7 @@ std::shared_ptr<client> init_client(const std::string& hostname, int lidar_port,
*
* @return pointer owning the resources associated with the connection.
*/
std::shared_ptr<client> init_client(
OUSTER_CLIENT_EXPORT std::shared_ptr<client> init_client(
const std::string& hostname, const std::string& udp_dest_host,
lidar_mode ld_mode = MODE_UNSPEC, timestamp_mode ts_mode = TIME_FROM_UNSPEC,
int lidar_port = 0, int imu_port = 0,
Expand All @@ -120,7 +123,7 @@ std::shared_ptr<client> init_client(
* the sensor, otherwise only the port values within the config object will be
* used and the rest will be ignored.
*/
std::shared_ptr<client> mtp_init_client(
OUSTER_CLIENT_EXPORT std::shared_ptr<client> mtp_init_client(
const std::string& hostname, const sensor_config& config,
const std::string& mtp_dest_host, bool main,
int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS,
Expand All @@ -141,7 +144,8 @@ std::shared_ptr<client> mtp_init_client(
* LIDAR_DATA) is true if lidar data is ready to read, and (s & IMU_DATA) is
* true if imu data is ready to read.
*/
client_state poll_client(const client& cli, int timeout_sec = 1);
OUSTER_CLIENT_EXPORT client_state poll_client(const client& cli,
int timeout_sec = 1);

/**
* Read lidar data from the sensor. Will not block.
Expand All @@ -153,8 +157,8 @@ client_state poll_client(const client& cli, int timeout_sec = 1);
*
* @return true if a lidar packet was successfully read.
*/
bool read_lidar_packet(const client& cli, uint8_t* buf,
const packet_format& pf);
OUSTER_CLIENT_EXPORT bool read_lidar_packet(const client& cli, uint8_t* buf,
const packet_format& pf);

/**
* Read lidar data from the sensor. Will not block.
Expand All @@ -166,7 +170,8 @@ bool read_lidar_packet(const client& cli, uint8_t* buf,
*
* @return true if a lidar packet was successfully read.
*/
bool read_lidar_packet(const client& cli, uint8_t* buf, size_t bytes);
OUSTER_CLIENT_EXPORT bool read_lidar_packet(const client& cli, uint8_t* buf,
size_t bytes);

/**
* Read lidar data from the sensor. Will not block.
Expand All @@ -178,7 +183,8 @@ bool read_lidar_packet(const client& cli, uint8_t* buf, size_t bytes);
*
* @return true if a lidar packet was successfully read.
*/
bool read_lidar_packet(const client& cli, LidarPacket& packet);
OUSTER_CLIENT_EXPORT bool read_lidar_packet(const client& cli,
LidarPacket& packet);

/**
* Read imu data from the sensor. Will not block.
Expand All @@ -190,7 +196,8 @@ bool read_lidar_packet(const client& cli, LidarPacket& packet);
*
* @return true if a lidar packet was successfully read.
*/
bool read_imu_packet(const client& cli, uint8_t* buf, size_t bytes);
OUSTER_CLIENT_EXPORT bool read_imu_packet(const client& cli, uint8_t* buf,
size_t bytes);

/**
* Read imu data from the sensor. Will not block.
Expand All @@ -202,7 +209,8 @@ bool read_imu_packet(const client& cli, uint8_t* buf, size_t bytes);
*
* @return true if an imu packet was successfully read.
*/
bool read_imu_packet(const client& cli, uint8_t* buf, const packet_format& pf);
OUSTER_CLIENT_EXPORT bool read_imu_packet(const client& cli, uint8_t* buf,
const packet_format& pf);

/**
* Read imu data from the sensor. Will not block.
Expand All @@ -214,7 +222,7 @@ bool read_imu_packet(const client& cli, uint8_t* buf, const packet_format& pf);
*
* @return true if an imu packet was successfully read.
*/
bool read_imu_packet(const client& cli, ImuPacket& packet);
OUSTER_CLIENT_EXPORT bool read_imu_packet(const client& cli, ImuPacket& packet);

/**
* Get metadata text blob from the sensor.
Expand All @@ -232,7 +240,7 @@ bool read_imu_packet(const client& cli, ImuPacket& packet);
*
* @return a text blob of metadata parseable into a sensor_info struct.
*/
std::string get_metadata(
OUSTER_CLIENT_EXPORT std::string get_metadata(
client& cli, int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS);

/**
Expand All @@ -248,9 +256,9 @@ std::string get_metadata(
*
* @return true if sensor config successfully populated.
*/
bool get_config(const std::string& hostname, sensor_config& config,
bool active = true,
int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS);
OUSTER_CLIENT_EXPORT bool get_config(
const std::string& hostname, sensor_config& config, bool active = true,
int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS);

// clang-format off
/**
Expand Down Expand Up @@ -278,9 +286,10 @@ enum config_flags : uint8_t {
*
* @return true if config params successfuly set on sensor.
*/
bool set_config(const std::string& hostname, const sensor_config& config,
uint8_t config_flags = 0,
int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS);
OUSTER_CLIENT_EXPORT bool set_config(
const std::string& hostname, const sensor_config& config,
uint8_t config_flags = 0,
int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS);

/**
* Return the port used to listen for lidar UDP data.
Expand All @@ -289,7 +298,7 @@ bool set_config(const std::string& hostname, const sensor_config& config,
*
* @return the port number.
*/
int get_lidar_port(const client& cli);
OUSTER_CLIENT_EXPORT int get_lidar_port(const client& cli);

/**
* Return the port used to listen for imu UDP data.
Expand All @@ -298,7 +307,7 @@ int get_lidar_port(const client& cli);
*
* @return the port number.
*/
int get_imu_port(const client& cli);
OUSTER_CLIENT_EXPORT int get_imu_port(const client& cli);

/**
* Check if ip address in multicast range.
Expand All @@ -307,7 +316,7 @@ int get_imu_port(const client& cli);
*
* @return true if addr is in multicast range.
*/
bool in_multicast(const std::string& addr);
OUSTER_CLIENT_EXPORT bool in_multicast(const std::string& addr);

} // namespace sensor
} // namespace ouster
42 changes: 22 additions & 20 deletions ouster_client/include/ouster/field.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include <vector>

#include "ouster/array_view.h"
#include "ouster/ouster_client_export.h"
#include "ouster/types.h"

namespace ouster {
Expand All @@ -29,7 +30,8 @@ namespace impl {
*
* @return vector of stride offsets
*/
std::vector<size_t> calculate_strides(const std::vector<size_t>& shape);
OUSTER_CLIENT_EXPORT std::vector<size_t> calculate_strides(
const std::vector<size_t>& shape);

} // namespace impl

Expand All @@ -39,24 +41,24 @@ namespace impl {
// clang-format off

template <typename T> int type_size() { return sizeof(T); }
template <> int type_size<void>();
template <> OUSTER_CLIENT_EXPORT int type_size<void>();

template <typename T> size_t type_hash() { return typeid(T).hash_code(); }
template <> size_t type_hash<void>();
template <> OUSTER_CLIENT_EXPORT size_t type_hash<void>();

template <typename T>
ChanFieldType type_cft() { return ChanFieldType::UNREGISTERED; }
template <> ChanFieldType type_cft<void>();
template <> ChanFieldType type_cft<uint8_t>();
template <> ChanFieldType type_cft<uint16_t>();
template <> ChanFieldType type_cft<uint32_t>();
template <> ChanFieldType type_cft<uint64_t>();
template <> ChanFieldType type_cft<int8_t>();
template <> ChanFieldType type_cft<int16_t>();
template <> ChanFieldType type_cft<int32_t>();
template <> ChanFieldType type_cft<int64_t>();
template <> ChanFieldType type_cft<float>();
template <> ChanFieldType type_cft<double>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<void>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<uint8_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<uint16_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<uint32_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<uint64_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<int8_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<int16_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<int32_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<int64_t>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<float>();
template <> OUSTER_CLIENT_EXPORT ChanFieldType type_cft<double>();

// clang-format on

Expand All @@ -68,7 +70,7 @@ template <> ChanFieldType type_cft<double>();
* Unlike FieldType this fully describes a Field's dimensions rather than
* abstract away the lidar width and height or packet count.
*/
struct FieldDescriptor {
struct OUSTER_CLIENT_EXPORT FieldDescriptor {
/**
* type hash of the described field
*/
Expand Down Expand Up @@ -266,7 +268,7 @@ auto fd_array(sensor::ChanFieldType tag, Args&&... args) -> FieldDescriptor {
* Non-owning wrapper over a memory pointer that allows for type safe
* conversion to typed pointer, eigen array or ArrayView
*/
class FieldView {
class OUSTER_CLIENT_EXPORT FieldView {
protected:
void* ptr_;
FieldDescriptor desc_;
Expand Down Expand Up @@ -639,15 +641,15 @@ enum class FieldClass {
*
* @return string representation of the FieldClass, or "UNKNOWN".
*/
std::string to_string(FieldClass f);
OUSTER_CLIENT_EXPORT std::string to_string(FieldClass f);

/**
* RAII memory-owning container for arbitrary typed and sized arrays and POD
* structs with optional type checking
*
* For usage examples, check unit tests
*/
class Field : public FieldView {
class OUSTER_CLIENT_EXPORT Field : public FieldView {
protected:
FieldClass class_;

Expand Down Expand Up @@ -730,7 +732,7 @@ class Field : public FieldView {
*
* @return reinterpreted view of uint8_t, uint16_t, uint32_t or uint64_t type
*/
FieldView uint_view(const FieldView& other);
OUSTER_CLIENT_EXPORT FieldView uint_view(const FieldView& other);

} // namespace ouster

Expand All @@ -742,6 +744,6 @@ namespace std {
* @param[in] a Field to swap with b
* @param[in] b Field to swap with a
*/
void swap(ouster::Field& a, ouster::Field& b);
OUSTER_CLIENT_EXPORT void swap(ouster::Field& a, ouster::Field& b);

} // namespace std
5 changes: 3 additions & 2 deletions ouster_client/include/ouster/image_processing.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,14 @@

#include <Eigen/Core>

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

namespace ouster {
namespace viz {

/** Adjusts brightness to between 0 and 1. */
class AutoExposure {
class OUSTER_CLIENT_EXPORT AutoExposure {
const double lo_percentile, hi_percentile; // percentiles used for scaling
const int ae_update_every;

Expand Down Expand Up @@ -79,7 +80,7 @@ class AutoExposure {
* thereby correcting subtle horizontal line artifacts in images, especially the
* ambient image.
*/
class BeamUniformityCorrector {
class OUSTER_CLIENT_EXPORT BeamUniformityCorrector {
private:
int counter = 0;
Eigen::ArrayXd dark_count;
Expand Down
3 changes: 2 additions & 1 deletion ouster_client/include/ouster/impl/lidar_scan_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,8 @@ struct zero_field {
* @param[in] pf packet format
* @param[in] ls lidar scan to check for RAW_HEADERS field presence.
*/
bool raw_headers_enabled(const sensor::packet_format& pf, const LidarScan& ls);
OUSTER_CLIENT_EXPORT bool raw_headers_enabled(const sensor::packet_format& pf,
const LidarScan& ls);

/**
* OutputItT - STL compatible output iterator over LidarPacket value type
Expand Down
Loading
Loading