diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 158c63d4..7acce7cd 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog ========= + +[20220927] +========== + +ouster_client +-------------- +* fix a bug in longform init_client which was not setting timestamp_mode and lidar_mode correctly + + [20220826] ========== @@ -43,7 +52,8 @@ ouster_ros * drop FW 1.13 compatibility for sensors and recorded bags * remove setting of EIGEN_MAX_ALIGN_BYTES * add two new ros services /ouster/get_config and /ouster/set_config (experimental) -* Add new timestamp_mode TIME_FROM_ROS_TIME +* add new timestamp_mode TIME_FROM_ROS_TIME +* declare PCL_NO_PRECOMPILE ahead of all PCL library includes [20220608] diff --git a/CMakeLists.txt b/CMakeLists.txt index 763f75ee..ca7d1f6d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,10 +7,10 @@ include(DefaultBuildType) include(VcpkgEnv) # ==== Project Name ==== -project(ouster_example VERSION 20220826) +project(ouster_example VERSION 20220927) # generate version header -set(OusterSDK_VERSION_STRING 0.5.1) +set(OusterSDK_VERSION_STRING 0.5.2) include(VersionGen) # ==== Options ==== diff --git a/docs/ros/index.rst b/docs/ros/index.rst index 3a958849..b2e4beea 100644 --- a/docs/ros/index.rst +++ b/docs/ros/index.rst @@ -72,6 +72,11 @@ Additionally, the launch file has following list of arguments that you can use: - ``udp_dest:=`` to specify the hostname or IP to which the sensor should send data - ``lidar_mode:=`` where mode is one of ``512x10``, ``512x20``, ``1024x10``, ``1024x20``, or ``2048x10``, and +- ``timestamp_mode`` choose any value of the following timestamp modes: ``TIME_FROM_INTERNAL_OSC``, + ``TIME_FROM_SYNC_PULSE_IN``, ``TIME_FROM_PTP_1588``, or ``TIME_FROM_ROS_TIME``. You can read about + the first three modes in `Ouster Sensor Guide `_. The last + mode ``TIME_FROM_ROS_TIME`` is specific to the ouster_ros driver; when this mode is set, the + driver uses ROS time as the timestamp for published IMU and Lidar messages. - ``viz:=true/false`` to visualize the sensor output, if you have the rviz ROS package installed diff --git a/examples/client_example.cpp b/examples/client_example.cpp index 36320c14..881a5e2d 100644 --- a/examples/client_example.cpp +++ b/examples/client_example.cpp @@ -9,8 +9,8 @@ #include #include -#include "ouster/impl/build.h" #include "ouster/client.h" +#include "ouster/impl/build.h" #include "ouster/lidar_scan.h" #include "ouster/types.h" diff --git a/ouster_client/src/client.cpp b/ouster_client/src/client.cpp index 82fb47de..3508dfe0 100644 --- a/ouster_client/src/client.cpp +++ b/ouster_client/src/client.cpp @@ -300,12 +300,11 @@ std::shared_ptr init_client(const std::string& hostname, // if specified (not UNSPEC), set the lidar and timestamp modes if (mode) { - sensor_http->set_config_param("lidar_mode", std::to_string(mode)); + sensor_http->set_config_param("lidar_mode", to_string(mode)); } if (ts_mode) { - sensor_http->set_config_param("timestamp_mode", - std::to_string(ts_mode)); + sensor_http->set_config_param("timestamp_mode", to_string(ts_mode)); } // wake up from STANDBY, if necessary