Skip to content

Commit

Permalink
multi threaded transform
Browse files Browse the repository at this point in the history
  • Loading branch information
spelletier1996 committed Jun 11, 2024
1 parent 513a109 commit 0653620
Showing 1 changed file with 38 additions and 8 deletions.
46 changes: 38 additions & 8 deletions src/utils/tf2_sensor_msgs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@

#include <unordered_set>

#include <boost/asio.hpp>

namespace robot_body_filter {

const static std::unordered_map<std::string, CloudChannelType> XYZ_CHANNELS({
Expand All @@ -32,6 +34,31 @@ bool fieldNameMatchesChannel(const std::string& fieldName, const std::string& ch
}
}

void ApplyTransform(CloudConstIter& x_in, CloudConstIter& y_in, CloudConstIter& z_in, CloudIter& x_out,
CloudIter& y_out, CloudIter& z_out, const Eigen::Isometry3f& t, size_t sp, size_t ep) {
Eigen::Vector3f point;
for (size_t i = sp; i < ep; ++i) {
point = t * Eigen::Vector3f(*(x_in + i), *(y_in + i), *(z_in + i)); // apply the whole transform
*(x_out + i) = point.x();
*(y_out + i) = point.y();
*(z_out + i) = point.z();
}
}

void SegmentTransform(size_t np, size_t threads, CloudConstIter& x_in, CloudConstIter& y_in, CloudConstIter& z_in,
CloudIter& x_out, CloudIter& y_out, CloudIter& z_out, const Eigen::Isometry3f& t) {
//Given a number of points and a number of threads, this function will divide the points into segments
//Making this threadpool static is causing issues with the transform?
boost::asio::thread_pool pool(threads);
for (size_t i = 0; i < threads; ++i) {
size_t sp = i * np / threads;
size_t ep = (i + 1) * np / threads;
boost::asio::post(pool, std::bind(ApplyTransform, std::ref(x_in), std::ref(y_in), std::ref(z_in), std::ref(x_out),
std::ref(y_out), std::ref(z_out), std::ref(t), sp, ep));
}
pool.join();
}

void transformChannel(const sensor_msgs::msg::PointCloud2& cloudIn, sensor_msgs::msg::PointCloud2& cloudOut,
const Eigen::Isometry3f& t, const std::string& channelPrefix, const CloudChannelType type)
{
Expand All @@ -48,18 +75,21 @@ void transformChannel(const sensor_msgs::msg::PointCloud2& cloudIn, sensor_msgs:
CloudIter z_out(cloudOut, channelPrefix + "z");

Eigen::Vector3f point;
size_t np = num_points(cloudIn);

// the switch has to be outside the for loop for performance reasons
switch (type)
{
case CloudChannelType::POINT:
for (; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out)
{
point = t * Eigen::Vector3f(*x_in, *y_in, *z_in); // apply the whole transform
*x_out = point.x();
*y_out = point.y();
*z_out = point.z();
}
case CloudChannelType::POINT: {
// for (; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out) {
// point = t * Eigen::Vector3f(*x_in, *y_in, *z_in); // apply the whole transform
// *x_out = point.x();
// *y_out = point.y();
// *z_out = point.z();
// }
SegmentTransform(np, 16, std::ref(x_in), std::ref(y_in), std::ref(z_in), std::ref(x_out), std::ref(y_out), std::ref(z_out), t);
break;
}
case CloudChannelType::DIRECTION:
for (; x_out != x_out.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out)
{
Expand Down

0 comments on commit 0653620

Please sign in to comment.