Skip to content

Commit c51ed2e

Browse files
authored
massive speedup of plane finder (#191)
* roughly 30x faster on VGA point cloud filtering * KDL was 3x faster than using Eigen
1 parent faaf824 commit c51ed2e

File tree

1 file changed

+37
-35
lines changed

1 file changed

+37
-35
lines changed

robot_calibration/src/finders/plane_finder.cpp

Lines changed: 37 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -227,72 +227,74 @@ bool PlaneFinder::find(robot_calibration_msgs::msg::CalibrationData * msg)
227227
void PlaneFinder::removeInvalidPoints(sensor_msgs::msg::PointCloud2& cloud,
228228
double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)
229229
{
230-
// Remove any point that is invalid or not with our tolerance
231230
size_t num_points = cloud.width * cloud.height;
232231
sensor_msgs::PointCloud2ConstIterator<float> xyz(cloud, "x");
233232
sensor_msgs::PointCloud2Iterator<float> cloud_iter(cloud, "x");
234233

235-
bool do_transform = transform_frame_ != "none"; // This can go away once the cloud gets transformed outside loop
234+
// Optionally transform the point cloud to the transform_frame_
235+
KDL::Frame transform = KDL::Frame::Identity();
236+
if (transform_frame_ != "none")
237+
{
238+
try
239+
{
240+
auto t = tf2_buffer_->lookupTransform(transform_frame_,
241+
cloud_.header.frame_id,
242+
tf2::TimePointZero);
243+
transform = KDL::Frame(
244+
KDL::Rotation::Quaternion(
245+
t.transform.rotation.x, t.transform.rotation.y,
246+
t.transform.rotation.z, t.transform.rotation.w),
247+
KDL::Vector(
248+
t.transform.translation.x, t.transform.translation.y,
249+
t.transform.translation.z));
250+
}
251+
catch (tf2::TransformException& ex)
252+
{
253+
RCLCPP_ERROR(LOGGER, "%s", ex.what());
254+
return;
255+
}
256+
}
257+
258+
// Remove any point that is invalid or not with our tolerance
236259
size_t j = 0;
237260
for (size_t i = 0; i < num_points; i++)
238261
{
239-
geometry_msgs::msg::PointStamped p;
240-
p.point.x = (xyz + i)[X];
241-
p.point.y = (xyz + i)[Y];
242-
p.point.z = (xyz + i)[Z];
262+
// Construct point
263+
KDL::Vector p((xyz + i)[X], (xyz + i)[Y], (xyz + i)[Z]);
243264

244265
// Remove the NaNs in the point cloud
245-
if (!std::isfinite(p.point.x) || !std::isfinite(p.point.y) || !std::isfinite(p.point.z))
266+
if (!std::isfinite(p[X]) || !std::isfinite(p[Y]) || !std::isfinite(p[Z]))
246267
{
247268
continue;
248269
}
249270

250271
// Remove the points immediately in front of the camera in the point cloud
251272
// NOTE : This is to handle sensors that publish zeros instead of NaNs in the point cloud
252-
if (p.point.z == 0)
273+
if (p[Z] == 0)
253274
{
254275
continue;
255276
}
256277

257278
// Get transform (if any)
258-
geometry_msgs::msg::PointStamped p_out;
259-
if (do_transform)
260-
{
261-
p.header.stamp.sec = 0;
262-
p.header.stamp.nanosec = 0;
263-
p.header.frame_id = cloud_.header.frame_id;
264-
try
265-
{
266-
tf2_buffer_->transform(p, p_out, transform_frame_);
267-
}
268-
catch (tf2::TransformException& ex)
269-
{
270-
RCLCPP_ERROR(LOGGER, "%s", ex.what());
271-
rclcpp::sleep_for(std::chrono::seconds(1));
272-
continue;
273-
}
274-
}
275-
else
276-
{
277-
p_out = p;
278-
}
279+
KDL::Vector p_out = transform * p;
279280

280-
// Test the transformed point
281-
if (p_out.point.x < min_x || p_out.point.x > max_x || p_out.point.y < min_y || p_out.point.y > max_y ||
282-
p_out.point.z < min_z || p_out.point.z > max_z)
281+
// Test the transformed point against the tolerances
282+
if (p_out[X] < min_x || p_out[X] > max_x || p_out[Y] < min_y || p_out[Y] > max_y ||
283+
p_out[Z] < min_z || p_out[Z] > max_z)
283284
{
284285
continue;
285286
}
286287

287288
// This is a valid point, move it forward
288-
(cloud_iter + j)[X] = (xyz + i)[X];
289-
(cloud_iter + j)[Y] = (xyz + i)[Y];
290-
(cloud_iter + j)[Z] = (xyz + i)[Z];
289+
(cloud_iter + j)[X] = p[X];
290+
(cloud_iter + j)[Y] = p[Y];
291+
(cloud_iter + j)[Z] = p[Z];
291292
j++;
292293
}
293294
cloud.height = 1;
294295
cloud.width = j;
295296
cloud.data.resize(cloud.width * cloud.point_step);
297+
RCLCPP_INFO(LOGGER, "Filtered cloud to %lu valid points", j);
296298
}
297299

298300
sensor_msgs::msg::PointCloud2 PlaneFinder::extractPlane(sensor_msgs::msg::PointCloud2& cloud)

0 commit comments

Comments
 (0)