3
3
#include < pcl_conversions/pcl_conversions.h>
4
4
#include < sensor_msgs/PointCloud2.h>
5
5
6
+ #include " ouster_ros/common_point_types.h"
6
7
#include " ouster_ros/os_point.h"
7
8
#include " ouster_ros/sensor_point_types.h"
8
- #include " ouster_ros/common_point_types.h"
9
-
10
9
#include " point_meta_helpers.h"
11
10
#include " point_transform.h"
12
11
@@ -117,10 +116,9 @@ using Cloud = pcl::PointCloud<T>;
117
116
// TODO[UN]: make this a functor
118
117
template <std::size_t N, const ChanFieldTable<N>& PROFILE, typename PointT,
119
118
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,
124
122
const std::vector<int >& pixel_shift_by_row,
125
123
bool organized = false , bool destagger = true ,
126
124
int rows_step = 1 ) {
@@ -132,11 +130,12 @@ void scan_to_cloud_f(ouster_ros::Cloud<PointT>& cloud,
132
130
133
131
for (auto u = 0 ; u < ls.h ; u += rows_step) {
134
132
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;
137
135
const auto src_idx = u * ls.w + v_shift;
138
136
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 ();
140
139
141
140
if (xyz.isNaN ().any ()) {
142
141
if (organized) {
@@ -148,12 +147,15 @@ void scan_to_cloud_f(ouster_ros::Cloud<PointT>& cloud,
148
147
}
149
148
continue ;
150
149
} else {
151
- if (!organized)
152
- cloud.points .emplace_back ();
150
+ if (!organized) cloud.points .emplace_back ();
153
151
}
154
152
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 ;
157
159
158
160
// if target point and staging point has matching type bind the
159
161
// target directly and avoid performing transform_point at the end
0 commit comments