diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index feae2efc..ca57c99a 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -7,6 +7,14 @@ assignees: '' --- +> **IMPORTANT** +> Before reporting a new bug make sure you have: +> - [ ] Checked existing issues https://github.com/ouster-lidar/ouster-ros/issues +> - [ ] Checked existing issues https://github.com/ouster-lidar/ouster-ros/issues +> - [ ] Checked ouster community https://community.ouster.com/ +> If you couldn't find relevant information and you think this is rather a driver +> problem then proceed with bug reporting. + **Describe the bug** A clear and concise description of what the bug is. diff --git a/.github/ISSUE_TEMPLATE/question.md b/.github/ISSUE_TEMPLATE/question.md deleted file mode 100644 index 61a2ea55..00000000 --- a/.github/ISSUE_TEMPLATE/question.md +++ /dev/null @@ -1,24 +0,0 @@ -[IMPORTANT: PLEASE CONSIDER POSTING YOUR QUESTION TO THE ROS TOPIC ON https://forum.ouster.com]: # - ---- -name: Question -about: Do you have a specific question -title: '' -labels: question -assignees: '' - ---- - -**Describe your question** -A clear and concise description of your question. - -**Screenshots** -If applicable, add screenshots to help explain your problem. - -**Platform (please complete the following information):** -- Ouster Sensor? \[e.g. OS-0, OS-1, ..\] -- Ouster Firmware Version? \[e.g. 2.3, 2.4, ..\] -- ROS version/distro? \[e.g. noetic, foxy, humble, ..\] -- Operating System? \[e.g. Linux, Windows, MacOS\] -- Machine Architecture? \[e.g. x64, arm\] -- git commit hash (if not the latest). diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 413b8615..d3f1295e 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,14 @@ Changelog ========= -[ouster_ros v0.13.0] -==================== + +[unreleased] +============ +* [BUGFIX]: correctly align timestamps to the generated point cloud + + +ouster_ros v0.13.0 +================== ouster_ros(1) ------------- diff --git a/src/os_sensor_nodelet.cpp b/src/os_sensor_nodelet.cpp index 57cde7eb..e0d0d521 100644 --- a/src/os_sensor_nodelet.cpp +++ b/src/os_sensor_nodelet.cpp @@ -116,9 +116,9 @@ void OusterSensor::onInit() { create_services(); create_publishers(); attempt_reconnect = getPrivateNodeHandle().param("attempt_reconnect", false); - dormant_period_between_reconnects = + dormant_period_between_reconnects = getPrivateNodeHandle().param("dormant_period_between_reconnects", 1.0); - reconnect_attempts_available = + reconnect_attempts_available = getPrivateNodeHandle().param("max_failed_reconnect_attempts", INT_MAX); attempt_start(); } diff --git a/src/point_cloud_compose.h b/src/point_cloud_compose.h index 37ecc17b..00e6b070 100644 --- a/src/point_cloud_compose.h +++ b/src/point_cloud_compose.h @@ -152,7 +152,10 @@ void scan_to_cloud_f(ouster_ros::Cloud& cloud, cloud.points.emplace_back(); } - auto ts = timestamp[v]; + // as opposed to the point cloud destaggering if it is disabled + // then timestamps needs to be staggered. + auto ts = destagger ? + timestamp[v] : timestamp[(v + ls.w + pixel_shift_by_row[u]) % ls.w]; ts = ts > scan_ts ? ts - scan_ts : 0UL; // if target point and staging point has matching type bind the