plane_finder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2015-2017 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Niharika Arora, Michael Ferguson
20 
21 #include <math.h>
22 #include <stdlib.h>
23 
29 
31 
32 namespace robot_calibration
33 {
34 
35 const unsigned X = 0;
36 const unsigned Y = 1;
37 const unsigned Z = 2;
38 
39 // Helper function to sample points from a cloud
40 int sampleCloud(const sensor_msgs::PointCloud2& points,
41  double sample_distance, size_t max_points,
42  std::vector<geometry_msgs::PointStamped>& sampled_points)
43 {
44  // Square distance for efficiency
45  double max_dist_sq = sample_distance * sample_distance;
46 
47  // Iterate through cloud
48  sensor_msgs::PointCloud2ConstIterator<float> points_iter(points, "x");
49  for (size_t i = 0; i < points.width; ++i)
50  {
51  // Get (untransformed) 3d point
52  geometry_msgs::PointStamped rgbd;
53  rgbd.point.x = (points_iter + i)[X];
54  rgbd.point.y = (points_iter + i)[Y];
55  rgbd.point.z = (points_iter + i)[Z];
56 
57  // Is this far enough from our current points?
58  bool include_point = true;
59  for (auto point : sampled_points)
60  {
61  double dx = point.point.x - rgbd.point.x;
62  double dy = point.point.y - rgbd.point.y;
63  double dz = point.point.z - rgbd.point.z;
64 
65  double dist_sq = dx * dx + dy * dy + dz * dz;
66  if (dist_sq < max_dist_sq)
67  {
68  include_point = false;
69  break;
70  }
71  }
72 
73  if (include_point)
74  {
75  // Add this to samples
76  sampled_points.push_back(rgbd);
77  }
78 
79  if (sampled_points.size() >= max_points)
80  {
81  // Done sampling
82  break;
83  }
84  }
85 
86  ROS_INFO("Extracted %lu points with sampling distance of %f", sampled_points.size(), sample_distance);
87 
88  return sampled_points.size();
89 }
90 
92  tf_listener_(tf_buffer_), waiting_(false)
93 {
94 }
95 
96 bool PlaneFinder::init(const std::string& name,
97  ros::NodeHandle & nh)
98 {
99  if (!FeatureFinder::init(name, nh))
100  return false;
101 
102  // We subscribe to a PointCloud2
103  std::string topic_name;
104  nh.param<std::string>("topic", topic_name, "/points");
105  subscriber_ = nh.subscribe(topic_name,
106  1,
108  this);
109 
110  // Name of the sensor model that will be used during optimization
111  nh.param<std::string>("camera_sensor_name", plane_sensor_name_, "camera");
112 
113  // Maximum number of valid points to include in the observation
114  nh.param<int>("points_max", points_max_, 60);
115 
116  // When downsampling cloud, start by selecting points at least this far apart
117  nh.param<double>("initial_sample_distance", initial_sampling_distance_, 0.2);
118 
119  // Maximum distance from plane that point can be located
120  nh.param<double>("tolerance", plane_tolerance_, 0.02);
121 
122  // Frame to transform point cloud into before applying limits below
123  // if specified as "none", cloud will be processed in sensor frame
124  nh.param<std::string>("transform_frame", transform_frame_, "base_link");
125 
126  // Valid points must lie within this box, in the transform_frame
127  nh.param<double>("min_x", min_x_, -2.0);
128  nh.param<double>("max_x", max_x_, 2.0);
129  nh.param<double>("min_y", min_y_, -2.0);
130  nh.param<double>("max_y", max_y_, 2.0);
131  nh.param<double>("min_z", min_z_, 0.0);
132  nh.param<double>("max_z", max_z_, 2.0);
133 
134  // Parameters for RANSAC
135  nh.param<int>("ransac_iterations", ransac_iterations_, 100);
136  nh.param<int>("ransac_points", ransac_points_, 35);
137 
138  // Optional normal vector that found plane should align with
139  // Leave all parameters set to 0 to disable check and simply take best fitting plane
140  double a, b, c;
141  nh.param<double>("normal_a", a, 0.0);
142  nh.param<double>("normal_b", b, 0.0);
143  nh.param<double>("normal_c", c, 0.0);
144  desired_normal_ = Eigen::Vector3d(a, b, c);
145  // If normal vector is defined, the plane normal must be aligned within this angle (in radians)
146  nh.param<double>("normal_angle", cos_normal_angle_, 0.349065); // Default is 20 degrees
148 
149  // Should we include debug image/cloud in observations
150  nh.param<bool>("debug", output_debug_, false);
151 
152  // Publish the observation as a PointCloud2
153  publisher_ = nh.advertise<sensor_msgs::PointCloud2>(getName() + "_points", 10);
154 
155  // Make sure we have CameraInfo before starting
156  if (!depth_camera_manager_.init(nh))
157  {
158  // Error will have been printed by manager
159  return false;
160  }
161 
162  return true;
163 }
164 
165 void PlaneFinder::cameraCallback(const sensor_msgs::PointCloud2& cloud)
166 {
167  if (waiting_)
168  {
169  cloud_ = cloud;
170  waiting_ = false;
171  }
172 }
173 
175 {
176  ros::Duration(1/10.0).sleep();
177 
178  waiting_ = true;
179  int count = 250;
180  while (--count)
181  {
182  if (!waiting_)
183  {
184  // success
185  return true;
186  }
187  ros::Duration(0.01).sleep();
188  ros::spinOnce();
189  }
190  ROS_ERROR("Failed to get cloud");
191  return !waiting_;
192 }
193 
194 bool PlaneFinder::find(robot_calibration_msgs::CalibrationData * msg)
195 {
196  if (!waitForCloud())
197  {
198  ROS_ERROR("No point cloud data");
199  return false;
200  }
201 
203  sensor_msgs::PointCloud2 plane = extractPlane(cloud_);
205 
206  // Report success
207  return true;
208 }
209 
210 void PlaneFinder::removeInvalidPoints(sensor_msgs::PointCloud2& cloud,
211  double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)
212 {
213  // Remove any point that is invalid or not with our tolerance
214  size_t num_points = cloud.width * cloud.height;
216  sensor_msgs::PointCloud2Iterator<float> cloud_iter(cloud, "x");
217 
218  bool do_transform = transform_frame_ != "none"; // This can go away once the cloud gets transformed outside loop
219  size_t j = 0;
220  for (size_t i = 0; i < num_points; i++)
221  {
222  geometry_msgs::PointStamped p;
223  p.point.x = (xyz + i)[X];
224  p.point.y = (xyz + i)[Y];
225  p.point.z = (xyz + i)[Z];
226 
227  // Remove the NaNs in the point cloud
228  if (!std::isfinite(p.point.x) || !std::isfinite(p.point.y) || !std::isfinite(p.point.z))
229  {
230  continue;
231  }
232 
233  // Remove the points immediately in front of the camera in the point cloud
234  // NOTE : This is to handle sensors that publish zeros instead of NaNs in the point cloud
235  if (p.point.z == 0)
236  {
237  continue;
238  }
239 
240  // Get transform (if any)
241  geometry_msgs::PointStamped p_out;
242  if (do_transform)
243  {
244  p.header.stamp = ros::Time(0);
245  p.header.frame_id = cloud_.header.frame_id;
246  try
247  {
249  }
250  catch (tf2::TransformException& ex)
251  {
252  ROS_ERROR("%s", ex.what());
253  ros::Duration(1.0).sleep();
254  continue;
255  }
256  }
257  else
258  {
259  p_out = p;
260  }
261 
262  // Test the transformed point
263  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 ||
264  p_out.point.z < min_z || p_out.point.z > max_z)
265  {
266  continue;
267  }
268 
269  // This is a valid point, move it forward
270  (cloud_iter + j)[X] = (xyz + i)[X];
271  (cloud_iter + j)[Y] = (xyz + i)[Y];
272  (cloud_iter + j)[Z] = (xyz + i)[Z];
273  j++;
274  }
275  cloud.height = 1;
276  cloud.width = j;
277  cloud.data.resize(cloud.width * cloud.point_step);
278 }
279 
280 sensor_msgs::PointCloud2 PlaneFinder::extractPlane(sensor_msgs::PointCloud2& cloud)
281 {
283 
284  // Copy cloud to eigen matrix for SVD
285  Eigen::MatrixXd points(3, cloud.width);
286  for (size_t i = 0; i < cloud.width; ++i)
287  {
288  points(0, i) = (xyz + i)[X];
289  points(1, i) = (xyz + i)[Y];
290  points(2, i) = (xyz + i)[Z];
291  }
292 
293  // Find the best fit plane
294  Eigen::Vector3d best_normal(0, 0, 1);
295  double best_d = 0.0;
296  int best_fit = -1;
297  for (int i = 0; i < ransac_iterations_; ++i)
298  {
299  // Select random points
300  Eigen::MatrixXd test_points(3, ransac_points_);
301  for (int p = 0; p < ransac_points_; ++p)
302  {
303  int index = rand() % cloud.width;
304  test_points(0, p) = points(0, index);
305  test_points(1, p) = points(1, index);
306  test_points(2, p) = points(2, index);
307  }
308 
309  // Get plane for this test set
310  Eigen::Vector3d normal;
311  double d = 0.0;
312  getPlane(test_points, normal, d);
313 
314  // If we have desired normal, check if plane is well enough aligned
315  if (desired_normal_.norm() > 0.1)
316  {
317  // We might have to transform the normal to a different frame
318  geometry_msgs::Vector3Stamped transformed_normal;
319  transformed_normal.header = cloud.header;
320  transformed_normal.vector.x = normal(0);
321  transformed_normal.vector.y = normal(1);
322  transformed_normal.vector.z = normal(2);
323 
324  if (transform_frame_ != "none")
325  {
326  try
327  {
328  tf_buffer_.transform(transformed_normal, transformed_normal, transform_frame_);
329  }
330  catch (tf2::TransformException& ex)
331  {
332  ROS_ERROR("%s", ex.what());
333  continue;
334  }
335  }
336 
337  Eigen::Vector3d transformed(transformed_normal.vector.x,
338  transformed_normal.vector.y,
339  transformed_normal.vector.z);
340 
341  // a.dot(b) = norm(a) * norm(b) * cos(angle between a & b)
342  double angle = transformed.dot(desired_normal_) / desired_normal_.norm() / transformed.norm();
343  if (std::fabs(angle) < cos_normal_angle_)
344  {
345  continue;
346  }
347  }
348 
349  // Test how many fit
350  int fit_count = 0;
351  for (size_t i = 0; i < cloud.width; ++i)
352  {
353  // Compute distance to plane
354  double dist = normal(0) * (xyz + i)[X] + normal(1) * (xyz + i)[Y] + normal(2) * (xyz + i)[Z] + d;
355  if (std::fabs(dist) < plane_tolerance_)
356  {
357  ++fit_count;
358  }
359  }
360 
361  if (fit_count > best_fit)
362  {
363  // Accept this as our best fit
364  best_fit = fit_count;
365  best_normal = normal;
366  best_d = d;
367  }
368  }
369  // Note: parameters are in cloud.header.frame_id and not transform_frame
370  ROS_INFO("Found plane with parameters: %f %f %f %f", best_normal(0), best_normal(1), best_normal(2), best_d);
371 
372  // Create a point cloud for the plane
373  sensor_msgs::PointCloud2 plane_cloud;
374  plane_cloud.width = 0;
375  plane_cloud.height = 0;
376  plane_cloud.header.stamp = ros::Time::now();
377  plane_cloud.header.frame_id = cloud.header.frame_id;
378  sensor_msgs::PointCloud2Modifier plane_cloud_mod(plane_cloud);
379  plane_cloud_mod.setPointCloud2FieldsByString(1, "xyz");
380  plane_cloud_mod.resize(cloud.width);
381  sensor_msgs::PointCloud2Iterator<float> plane_iter(plane_cloud, "x");
382 
383  // Extract points close to plane
384  sensor_msgs::PointCloud2Iterator<float> cloud_iter(cloud, "x");
385  size_t plane_points = 0;
386  size_t cloud_points = 0;
387  for (size_t i = 0; i < cloud.width; ++i)
388  {
389  // Compute distance to plane
390  double dist = best_normal(0) * (xyz + i)[X] + best_normal(1) * (xyz + i)[Y] + best_normal(2) * (xyz + i)[Z] + best_d;
391 
392  if (std::fabs(dist) < plane_tolerance_)
393  {
394  // Part of the plane
395  (plane_iter + plane_points)[X] = (xyz + i)[X];
396  (plane_iter + plane_points)[Y] = (xyz + i)[Y];
397  (plane_iter + plane_points)[Z] = (xyz + i)[Z];
398  ++plane_points;
399  }
400  else
401  {
402  // Part of cloud, move it forward
403  (cloud_iter + cloud_points)[X] = (xyz + i)[X];
404  (cloud_iter + cloud_points)[Y] = (xyz + i)[Y];
405  (cloud_iter + cloud_points)[Z] = (xyz + i)[Z];
406  ++cloud_points;
407  }
408  }
409 
410  // Resize clouds
411  cloud.height = 1;
412  cloud.width = cloud_points;
413  cloud.data.resize(cloud.width * cloud.point_step);
414 
415  plane_cloud.height = 1;
416  plane_cloud.width = plane_points;
417  plane_cloud.data.resize(plane_cloud.width * plane_cloud.point_step);
418 
419  ROS_INFO("Extracted plane with %d points", plane_cloud.width);
420 
421  return plane_cloud;
422 }
423 
424 void PlaneFinder::extractObservation(const std::string& sensor_name,
425  const sensor_msgs::PointCloud2& cloud,
426  robot_calibration_msgs::CalibrationData * msg,
427  ros::Publisher* publisher)
428 {
429  if (static_cast<int>(cloud.width) == 0)
430  {
431  ROS_WARN("No points in observation, skipping");
432  return;
433  }
434 
435  // Determine number of points to output
436  size_t points_total = std::min(points_max_, static_cast<int>(cloud.width));
437  ROS_INFO_STREAM("Got " << cloud.width << " points for observation, using " << points_total);
438 
439  // Create PointCloud2 to publish
440  sensor_msgs::PointCloud2 viz_cloud;
441  viz_cloud.width = 0;
442  viz_cloud.height = 0;
443  viz_cloud.header.stamp = ros::Time::now();
444  viz_cloud.header.frame_id = cloud.header.frame_id;
445  sensor_msgs::PointCloud2Modifier cloud_mod(viz_cloud);
446  cloud_mod.setPointCloud2FieldsByString(1, "xyz");
447  cloud_mod.resize(points_total);
448 
449  // Setup observation
450  int idx_cam = msg->observations.size();
451  msg->observations.resize(msg->observations.size() + 1);
452  msg->observations[idx_cam].sensor_name = sensor_name;
453  msg->observations[idx_cam].ext_camera_info = depth_camera_manager_.getDepthCameraInfo();
454 
455  // Get observation points
456  std::vector<geometry_msgs::PointStamped> sampled_points;
457  double sample_distance = initial_sampling_distance_;
458  while (sampled_points.size() < points_total)
459  {
460  sampleCloud(cloud, sample_distance, points_total, sampled_points);
461  sample_distance /= 2;
462  }
463 
464  // Fill in observation
465  sensor_msgs::PointCloud2Iterator<float> viz_cloud_iter(viz_cloud, "x");
467  for (auto rgbd : sampled_points)
468  {
469  // Add to observation
470  msg->observations[idx_cam].features.push_back(rgbd);
471 
472  // Copy to cloud for publishing
473  viz_cloud_iter[0] = rgbd.point.x;
474  viz_cloud_iter[1] = rgbd.point.y;
475  viz_cloud_iter[2] = rgbd.point.z;
476  ++viz_cloud_iter;
477  }
478 
479  // Add debug cloud to message
480  if (output_debug_)
481  {
482  msg->observations[idx_cam].cloud = cloud;
483  }
484 
485  if (publisher)
486  {
487  // Publish debug info
488  publisher->publish(viz_cloud);
489  }
490 }
491 
492 } // namespace robot_calibration
robot_calibration::PlaneFinder::cos_normal_angle_
double cos_normal_angle_
Definition: plane_finder.h:104
robot_calibration::PlaneFinder::output_debug_
bool output_debug_
Definition: plane_finder.h:109
robot_calibration::PlaneFinder::waiting_
bool waiting_
Definition: plane_finder.h:91
robot_calibration::PlaneFinder::publisher_
ros::Publisher publisher_
Definition: plane_finder.h:86
robot_calibration::PlaneFinder
Finds the largest plane in a point cloud.
Definition: plane_finder.h:34
point_cloud2_iterator.h
robot_calibration::PlaneFinder::points_max_
int points_max_
Definition: plane_finder.h:97
robot_calibration::sampleCloud
int sampleCloud(const sensor_msgs::PointCloud2 &points, double sample_distance, size_t max_points, std::vector< geometry_msgs::PointStamped > &sampled_points)
Definition: plane_finder.cpp:40
ros::Publisher
robot_calibration::Y
const unsigned Y
Definition: checkerboard_finder.cpp:33
robot_calibration::X
const unsigned X
Definition: checkerboard_finder.cpp:32
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
robot_calibration::DepthCameraInfoManager::init
bool init(ros::NodeHandle &n)
Definition: depth_camera.h:38
robot_calibration::FeatureFinder
Base class for a feature finder.
Definition: feature_finder.h:33
robot_calibration::PlaneFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Definition: plane_finder.cpp:96
ros::spinOnce
ROSCPP_DECL void spinOnce()
robot_calibration::PlaneFinder::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: plane_finder.h:88
robot_calibration::PlaneFinder::max_x_
double max_x_
Definition: plane_finder.h:100
robot_calibration::PlaneFinder::min_z_
double min_z_
Definition: plane_finder.h:102
robot_calibration::PlaneFinder::removeInvalidPoints
virtual void removeInvalidPoints(sensor_msgs::PointCloud2 &cloud, double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)
Remove invalid points from a cloud.
Definition: plane_finder.cpp:210
robot_calibration::PlaneFinder::depth_camera_manager_
DepthCameraInfoManager depth_camera_manager_
Definition: plane_finder.h:93
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
robot_calibration::PlaneFinder::find
virtual bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called....
Definition: plane_finder.cpp:194
sensor_msgs::PointCloud2ConstIterator
robot_calibration::PlaneFinder::max_z_
double max_z_
Definition: plane_finder.h:102
robot_calibration::PlaneFinder::min_y_
double min_y_
Definition: plane_finder.h:101
robot_calibration::PlaneFinder::initial_sampling_distance_
double initial_sampling_distance_
Definition: plane_finder.h:98
robot_calibration::PlaneFinder::subscriber_
ros::Subscriber subscriber_
Definition: plane_finder.h:85
robot_calibration::PlaneFinder::desired_normal_
Eigen::Vector3d desired_normal_
Definition: plane_finder.h:103
robot_calibration::PlaneFinder::ransac_points_
int ransac_points_
Definition: plane_finder.h:107
eigen_geometry.h
sensor_msgs::PointCloud2Iterator
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
robot_calibration::PlaneFinder::plane_sensor_name_
std::string plane_sensor_name_
Definition: plane_finder.h:96
name
std::string name
plane_finder.h
ROS_ERROR
#define ROS_ERROR(...)
robot_calibration::PlaneFinder::cameraCallback
virtual void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
ROS callback - updates cloud_ and resets waiting_ to false.
Definition: plane_finder.cpp:165
robot_calibration::PlaneFinder::transform_frame_
std::string transform_frame_
Definition: plane_finder.h:105
ROS_WARN
#define ROS_WARN(...)
d
d
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
robot_calibration::PlaneFinder::waitForCloud
virtual bool waitForCloud()
Wait until a new cloud has arrived.
Definition: plane_finder.cpp:174
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
robot_calibration::FeatureFinder::init
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
Definition: feature_finder.h:47
robot_calibration::PlaneFinder::cloud_
sensor_msgs::PointCloud2 cloud_
Definition: plane_finder.h:92
robot_calibration::PlaneFinder::min_x_
double min_x_
Definition: plane_finder.h:100
point
std::chrono::system_clock::time_point point
robot_calibration::PlaneFinder::ransac_iterations_
int ransac_iterations_
Definition: plane_finder.h:106
robot_calibration::Z
const unsigned Z
Definition: checkerboard_finder.cpp:34
robot_calibration::FeatureFinder::getName
std::string getName()
Get the name of this feature finder.
Definition: feature_finder.h:57
tf2_ros::BufferInterface::transform
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
ros::Time
robot_calibration::getPlane
bool getPlane(Eigen::MatrixXd points, Eigen::Vector3d &normal, double &d)
Find the plane parameters for a point cloud.
Definition: eigen_geometry.h:64
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::PlaneFinder::max_y_
double max_y_
Definition: plane_finder.h:101
sensor_msgs::PointCloud2Modifier
robot_calibration::PlaneFinder::extractObservation
virtual void extractObservation(const std::string &sensor_name, const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg, ros::Publisher *publisher)
Extract points from a cloud into a calibration message.
Definition: plane_finder.cpp:424
class_list_macros.hpp
index
unsigned int index
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2_geometry_msgs.h
ros::Duration::sleep
bool sleep() const
robot_calibration::PlaneFinder::extractPlane
virtual sensor_msgs::PointCloud2 extractPlane(sensor_msgs::PointCloud2 &cloud)
Extract a plane from the point cloud.
Definition: plane_finder.cpp:280
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
robot_calibration::DepthCameraInfoManager::getDepthCameraInfo
robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo()
Definition: depth_camera.h:75
ros::Duration
robot_calibration::PlaneFinder::PlaneFinder
PlaneFinder()
Definition: plane_finder.cpp:91
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
robot_calibration::PlaneFinder::plane_tolerance_
double plane_tolerance_
Definition: plane_finder.h:99
ros::NodeHandle
ros::Time::now
static Time now()


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01