Skip to content

Commit 92ab33d

Browse files
authored
ROS-350[NOETIC]: 't' timestamp field content is not plausible (#386)
Align timestamps based on staggered/destaggered option + CHANGELOG + workflows
1 parent b96de20 commit 92ab33d

File tree

6 files changed

+34
-42
lines changed

6 files changed

+34
-42
lines changed

.github/ISSUE_TEMPLATE/bug_report.md

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,14 @@ assignees: ''
77

88
---
99

10+
> **IMPORTANT**
11+
> Before reporting a new bug make sure you have:
12+
> - [ ] Checked existing issues https://github.com/ouster-lidar/ouster-ros/issues
13+
> - [ ] Checked existing issues https://github.com/ouster-lidar/ouster-ros/issues
14+
> - [ ] Checked ouster community https://community.ouster.com/
15+
> If you couldn't find relevant information and you think this is rather a driver
16+
> problem then proceed with bug reporting.
17+
1018
**Describe the bug**
1119
A clear and concise description of what the bug is.
1220

.github/ISSUE_TEMPLATE/question.md

Lines changed: 0 additions & 24 deletions
This file was deleted.

CHANGELOG.rst

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,14 @@
22
Changelog
33
=========
44

5-
[ouster_ros v0.13.0]
6-
====================
5+
6+
[unreleased]
7+
============
8+
* [BUGFIX]: correctly align timestamps to the generated point cloud
9+
10+
11+
ouster_ros v0.13.0
12+
==================
713

814
ouster_ros(1)
915
-------------

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="3">
33
<name>ouster_ros</name>
4-
<version>0.13.0</version>
4+
<version>0.13.1</version>
55
<description>Ouster ROS driver</description>
66
<maintainer email="[email protected]">ouster developers</maintainer>
77
<license file="LICENSE">BSD</license>

src/os_sensor_nodelet.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -116,9 +116,9 @@ void OusterSensor::onInit() {
116116
create_services();
117117
create_publishers();
118118
attempt_reconnect = getPrivateNodeHandle().param("attempt_reconnect", false);
119-
dormant_period_between_reconnects =
119+
dormant_period_between_reconnects =
120120
getPrivateNodeHandle().param("dormant_period_between_reconnects", 1.0);
121-
reconnect_attempts_available =
121+
reconnect_attempts_available =
122122
getPrivateNodeHandle().param("max_failed_reconnect_attempts", INT_MAX);
123123
attempt_start();
124124
}

src/point_cloud_compose.h

Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,9 @@
33
#include <pcl_conversions/pcl_conversions.h>
44
#include <sensor_msgs/PointCloud2.h>
55

6+
#include "ouster_ros/common_point_types.h"
67
#include "ouster_ros/os_point.h"
78
#include "ouster_ros/sensor_point_types.h"
8-
#include "ouster_ros/common_point_types.h"
9-
109
#include "point_meta_helpers.h"
1110
#include "point_transform.h"
1211

@@ -117,10 +116,9 @@ using Cloud = pcl::PointCloud<T>;
117116
// TODO[UN]: make this a functor
118117
template <std::size_t N, const ChanFieldTable<N>& PROFILE, typename PointT,
119118
typename PointS>
120-
void scan_to_cloud_f(ouster_ros::Cloud<PointT>& cloud,
121-
PointS& staging_point,
122-
const ouster::PointsF& points,
123-
uint64_t scan_ts, const ouster::LidarScan& ls,
119+
void scan_to_cloud_f(ouster_ros::Cloud<PointT>& cloud, PointS& staging_point,
120+
const ouster::PointsF& points, uint64_t scan_ts,
121+
const ouster::LidarScan& ls,
124122
const std::vector<int>& pixel_shift_by_row,
125123
bool organized = false, bool destagger = true,
126124
int rows_step = 1) {
@@ -132,11 +130,12 @@ void scan_to_cloud_f(ouster_ros::Cloud<PointT>& cloud,
132130

133131
for (auto u = 0; u < ls.h; u += rows_step) {
134132
for (auto v = 0; v < ls.w; ++v) { // TODO[UN]: consider cols_step in future
135-
const auto v_shift = destagger ?
136-
(v + ls.w - pixel_shift_by_row[u]) % ls.w : v;
133+
const auto v_shift =
134+
destagger ? (v + ls.w - pixel_shift_by_row[u]) % ls.w : v;
137135
const auto src_idx = u * ls.w + v_shift;
138136
const auto xyz = points.row(src_idx);
139-
const auto tgt_idx = organized ? (u / rows_step) * ls.w + v : cloud.size();
137+
const auto tgt_idx =
138+
organized ? (u / rows_step) * ls.w + v : cloud.size();
140139

141140
if (xyz.isNaN().any()) {
142141
if (organized) {
@@ -148,12 +147,15 @@ void scan_to_cloud_f(ouster_ros::Cloud<PointT>& cloud,
148147
}
149148
continue;
150149
} else {
151-
if (!organized)
152-
cloud.points.emplace_back();
150+
if (!organized) cloud.points.emplace_back();
153151
}
154152

155-
auto ts = timestamp[v_shift];
156-
ts = ts > scan_ts ? ts - scan_ts : 0UL;
153+
// as opposed to the point cloud destaggering if it is disabled
154+
// then timestamps needs to be staggered.
155+
auto ts_idx =
156+
destagger ? v : (v + ls.w + pixel_shift_by_row[u]) % ls.w;
157+
auto ts =
158+
timestamp[ts_idx] > scan_ts ? timestamp[ts_idx] - scan_ts : 0UL;
157159

158160
// if target point and staging point has matching type bind the
159161
// target directly and avoid performing transform_point at the end

0 commit comments

Comments
 (0)