Skip to content

Commit

Permalink
formatting code
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Oct 10, 2024
1 parent ff1d0d6 commit f33c3c6
Showing 1 changed file with 13 additions and 14 deletions.
27 changes: 13 additions & 14 deletions src/point_cloud_compose.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,9 @@
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>

#include "ouster_ros/common_point_types.h"
#include "ouster_ros/os_point.h"
#include "ouster_ros/sensor_point_types.h"
#include "ouster_ros/common_point_types.h"

#include "point_meta_helpers.h"
#include "point_transform.h"

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

for (auto u = 0; u < ls.h; u += rows_step) {
for (auto v = 0; v < ls.w; ++v) { // TODO[UN]: consider cols_step in future
const auto v_shift = destagger ?
(v + ls.w - pixel_shift_by_row[u]) % ls.w : v;
const auto v_shift =
destagger ? (v + ls.w - pixel_shift_by_row[u]) % ls.w : v;
const auto src_idx = u * ls.w + v_shift;
const auto xyz = points.row(src_idx);
const auto tgt_idx = organized ? (u / rows_step) * ls.w + v : cloud.size();
const auto tgt_idx =
organized ? (u / rows_step) * ls.w + v : cloud.size();

if (xyz.isNaN().any()) {
if (organized) {
Expand All @@ -148,15 +147,15 @@ void scan_to_cloud_f(ouster_ros::Cloud<PointT>& cloud,
}
continue;
} else {
if (!organized)
cloud.points.emplace_back();
if (!organized) cloud.points.emplace_back();
}

// 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;
auto ts_idx =
destagger ? v : (v + ls.w + pixel_shift_by_row[u]) % ls.w;
auto ts =
timestamp[ts_idx] > scan_ts ? timestamp[ts_idx] - scan_ts : 0UL;

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

0 comments on commit f33c3c6

Please sign in to comment.