41 double sample_distance,
size_t max_points,
42 std::vector<geometry_msgs::PointStamped>& sampled_points)
45 double max_dist_sq = sample_distance * sample_distance;
49 for (
size_t i = 0; i < points.width; ++i)
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];
58 bool include_point =
true;
59 for (
auto point : sampled_points)
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;
65 double dist_sq = dx * dx + dy * dy + dz * dz;
66 if (dist_sq < max_dist_sq)
68 include_point =
false;
76 sampled_points.push_back(rgbd);
79 if (sampled_points.size() >= max_points)
86 ROS_INFO(
"Extracted %lu points with sampling distance of %f", sampled_points.size(), sample_distance);
88 return sampled_points.size();
92 tf_listener_(tf_buffer_), waiting_(false)
103 std::string topic_name;
104 nh.
param<std::string>(
"topic", topic_name,
"/points");
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);
147 cos_normal_angle_ =
cos(cos_normal_angle_);
211 double min_x,
double max_x,
double min_y,
double max_y,
double min_z,
double max_z)
214 size_t num_points = cloud.width * cloud.height;
220 for (
size_t i = 0; i < num_points; i++)
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];
228 if (!std::isfinite(p.point.x) || !std::isfinite(p.point.y) || !std::isfinite(p.point.z))
241 geometry_msgs::PointStamped p_out;
245 p.header.frame_id =
cloud_.header.frame_id;
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)
270 (cloud_iter + j)[X] = (xyz + i)[
X];
271 (cloud_iter + j)[Y] = (xyz + i)[
Y];
272 (cloud_iter + j)[Z] = (xyz + i)[
Z];
277 cloud.data.resize(cloud.width * cloud.point_step);
285 Eigen::MatrixXd points(3, cloud.width);
286 for (
size_t i = 0; i < cloud.width; ++i)
288 points(0, i) = (xyz + i)[X];
289 points(1, i) = (xyz + i)[Y];
290 points(2, i) = (xyz + i)[Z];
294 Eigen::Vector3d best_normal(0, 0, 1);
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);
310 Eigen::Vector3d normal;
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);
337 Eigen::Vector3d transformed(transformed_normal.vector.x,
338 transformed_normal.vector.y,
339 transformed_normal.vector.z);
351 for (
size_t i = 0; i < cloud.width; ++i)
354 double dist = normal(0) * (xyz + i)[X] + normal(1) * (xyz + i)[Y] + normal(2) * (xyz + i)[Z] + d;
361 if (fit_count > best_fit)
364 best_fit = fit_count;
365 best_normal = normal;
370 ROS_INFO(
"Found plane with parameters: %f %f %f %f", best_normal(0), best_normal(1), best_normal(2), best_d);
373 sensor_msgs::PointCloud2 plane_cloud;
374 plane_cloud.width = 0;
375 plane_cloud.height = 0;
377 plane_cloud.header.frame_id = cloud.header.frame_id;
380 plane_cloud_mod.
resize(cloud.width);
385 size_t plane_points = 0;
386 size_t cloud_points = 0;
387 for (
size_t i = 0; i < cloud.width; ++i)
390 double dist = best_normal(0) * (xyz + i)[X] + best_normal(1) * (xyz + i)[Y] + best_normal(2) * (xyz + i)[Z] + best_d;
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];
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];
412 cloud.width = cloud_points;
413 cloud.data.resize(cloud.width * cloud.point_step);
415 plane_cloud.height = 1;
416 plane_cloud.width = plane_points;
417 plane_cloud.data.resize(plane_cloud.width * plane_cloud.point_step);
419 ROS_INFO(
"Extracted plane with %d points", plane_cloud.width);
425 const sensor_msgs::PointCloud2& cloud,
426 robot_calibration_msgs::CalibrationData * msg,
429 if (static_cast<int>(cloud.width) == 0)
431 ROS_WARN(
"No points in observation, skipping");
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);
440 sensor_msgs::PointCloud2 viz_cloud;
442 viz_cloud.height = 0;
444 viz_cloud.header.frame_id = cloud.header.frame_id;
447 cloud_mod.
resize(points_total);
450 int idx_cam = msg->observations.size();
451 msg->observations.resize(msg->observations.size() + 1);
452 msg->observations[idx_cam].sensor_name = sensor_name;
456 std::vector<geometry_msgs::PointStamped> sampled_points;
458 while (sampled_points.size() < points_total)
460 sampleCloud(cloud, sample_distance, points_total, sampled_points);
461 sample_distance /= 2;
467 for (
auto rgbd : sampled_points)
470 msg->observations[idx_cam].features.push_back(rgbd);
473 viz_cloud_iter[0] = rgbd.point.x;
474 viz_cloud_iter[1] = rgbd.point.y;
475 viz_cloud_iter[2] = rgbd.point.z;
482 msg->observations[idx_cam].cloud = cloud;
ros::Publisher publisher_
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
virtual bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
Base class for a feature finder.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
DepthCameraInfoManager depth_camera_manager_
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.
double initial_sampling_distance_
std::string plane_sensor_name_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo()
virtual sensor_msgs::PointCloud2 extractPlane(sensor_msgs::PointCloud2 &cloud)
Extract a plane from the point cloud.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
bool init(ros::NodeHandle &n)
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
tf2_ros::Buffer tf_buffer_
std::string transform_frame_
sensor_msgs::PointCloud2 cloud_
virtual bool waitForCloud()
Wait until a new cloud has arrived.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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...
std::string getName()
Get the name of this feature finder.
Calibration code lives under this namespace.
bool getPlane(Eigen::MatrixXd points, Eigen::Vector3d &normal, double &d)
Find the plane parameters for a point cloud.
#define ROS_INFO_STREAM(args)
ros::Subscriber subscriber_
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
ROSCPP_DECL void spinOnce()
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.
void setPointCloud2FieldsByString(int n_fields,...)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
int sampleCloud(const sensor_msgs::PointCloud2 &points, double sample_distance, size_t max_points, std::vector< geometry_msgs::PointStamped > &sampled_points)
Finds the largest plane in a point cloud.
Eigen::Vector3d desired_normal_
virtual void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
ROS callback - updates cloud_ and resets waiting_ to false.