Skip to content

Commit

Permalink
Bugfixes for 0.5.1 and conan for Windows (#432)
Browse files Browse the repository at this point in the history
* move PCL_NO_PRECOMPILE to top of ros.h
* fix sensor_config equality check missing members
* support for build with conan for Windows
  • Loading branch information
kairenw authored Sep 15, 2022
1 parent da9ba6f commit 02fe2a9
Show file tree
Hide file tree
Showing 24 changed files with 145 additions and 56 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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
-----------
Expand Down
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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 ====
Expand Down
2 changes: 1 addition & 1 deletion cmake/VersionGen.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
4 changes: 3 additions & 1 deletion conan/test_package/conanfile.py
Original file line number Diff line number Diff line change
Expand Up @@ -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))
14 changes: 4 additions & 10 deletions conanfile.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand All @@ -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)
Expand Down
22 changes: 20 additions & 2 deletions docs/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 ---------------------------------------------------

Expand Down
4 changes: 2 additions & 2 deletions examples/config_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
2 changes: 1 addition & 1 deletion examples/lidar_scan_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
4 changes: 4 additions & 0 deletions ouster_client/src/parsing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
Expand All @@ -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;
Expand Down
13 changes: 8 additions & 5 deletions ouster_client/src/types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
10 changes: 1 addition & 9 deletions ouster_ros/include/ouster_ros/os_client_base_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <nodelet/nodelet.h>
#include <ros/ros.h>

#include "ouster/impl/build.h"
#include "ouster/client.h"
#include "ouster/types.h"
#include "ouster_ros/ros.h"

namespace nodelets_os {

Expand Down
3 changes: 1 addition & 2 deletions ouster_ros/include/ouster_ros/point.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,11 @@
*/

#pragma once
#define PCL_NO_PRECOMPILE

#include <pcl/point_types.h>

#include <Eigen/Core>
#include <chrono>
#include <functional>

#include "ouster/lidar_scan.h"

Expand Down
6 changes: 5 additions & 1 deletion ouster_ros/include/ouster_ros/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,15 @@

#pragma once

#include <geometry_msgs/TransformStamped.h>
#define PCL_NO_PRECOMPILE
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>

#include <geometry_msgs/TransformStamped.h>

#include <chrono>
#include <string>

Expand Down
2 changes: 1 addition & 1 deletion ouster_ros/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>ouster_ros</name>
<version>0.5.0</version>
<version>0.5.1</version>
<description>Ouster example ROS client</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license>BSD</license>
Expand Down
1 change: 1 addition & 0 deletions ouster_ros/src/os_client_base_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
7 changes: 2 additions & 5 deletions ouster_ros/src/os_cloud_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,25 +6,22 @@
* @brief A nodelet to publish point clouds and imu topics
*/

#include "ouster_ros/ros.h"

#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <ros/console.h>
#include <ros/ros.h>
#include <ros/service.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf2_ros/static_transform_broadcaster.h>

#include <algorithm>
#include <chrono>
#include <memory>
#include <queue>

#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;
Expand Down
8 changes: 2 additions & 6 deletions ouster_ros/src/os_image_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@
* vision applications, use higher bit depth values in /os_cloud_node/points
*/

#include "ouster_ros/ros.h"

#include <nodelet/nodelet.h>
#include <pcl/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pluginlib/class_list_macros.h>
#include <ros/ros.h>
Expand All @@ -26,14 +26,10 @@
#include <iostream>
#include <sstream>
#include <string>
#include <thread>
#include <vector>

#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;
Expand Down
2 changes: 2 additions & 0 deletions ouster_ros/src/os_sensor_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
* @brief A nodelet that connects to a live ouster sensor
*/

#include "ouster_ros/ros.h"

#include <pluginlib/class_list_macros.h>

#include <fstream>
Expand Down
3 changes: 0 additions & 3 deletions ouster_ros/src/ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,10 @@
#include <tf2/LinearMath/Transform.h>
#include <tf2_eigen/tf2_eigen.h>

#include <cassert>
#include <chrono>
#include <string>
#include <vector>

#include "ouster/types.h"

namespace ouster_ros {

namespace sensor = ouster::sensor;
Expand Down
4 changes: 2 additions & 2 deletions python/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,15 @@
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")

# 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)
groups = re.search("set\(OusterSDK_VERSION_STRING ([^-\)]+)(.(.*))?\)", content)
return groups.group(1) + (groups.group(3) or "")

class CMakeExtension(Extension):
Expand Down
5 changes: 4 additions & 1 deletion python/src/ouster/client/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
6 changes: 5 additions & 1 deletion python/src/ouster/pcap/pcap.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Loading

0 comments on commit 02fe2a9

Please sign in to comment.