36 #define BOOST_PARAMETER_MAX_ARITY 7 44 point_(point), direction_(direction), radius_(radius)
50 const double threshold,
51 pcl::PointIndices& output)
54 output.indices.clear();
55 for (
size_t i = 0; i < cloud.points.size(); i++) {
56 Eigen::Vector3f
p = cloud.points[i].getVector3fMap();
58 if (d < radius_ + threshold && d >
radius_ - threshold) {
59 output.indices.push_back(i);
65 const pcl::PointIndices& indices,
66 Eigen::Vector3f& center,
71 for (
size_t i = 0; i < indices.indices.size(); i++) {
72 int point_index = indices.indices[i];
73 points.push_back(cloud.points[point_index].getVector3fMap());
76 Eigen::Vector3f min_point = min_max.get<0>();
77 Eigen::Vector3f max_point = min_max.get<1>();
78 Eigen::Vector3f min_point_projected, max_point_projected;
79 line.
foot(min_point, min_point_projected);
80 line.
foot(max_point, max_point_projected);
81 height = (min_point_projected - max_point_projected).norm();
82 center = (min_point_projected + max_point_projected) / 2.0;
86 const Eigen::Vector3f& center,
87 const Eigen::Vector3f& uz,
90 marker.type = visualization_msgs::Marker::CYLINDER;
91 marker.pose.position.x = center[0];
92 marker.pose.position.y = center[1];
93 marker.pose.position.z = center[2];
94 Eigen::Vector3f orig_z(0, 0, 1);
96 q.setFromTwoVectors(orig_z, uz);
97 marker.pose.orientation.x = q.x();
98 marker.pose.orientation.y = q.y();
99 marker.pose.orientation.z = q.z();
100 marker.pose.orientation.w = q.w();
104 marker.color.a = 1.0;
105 marker.color.g = 1.0;
106 marker.color.b = 1.0;
Cylinder(Eigen::Vector3f point, Eigen::Vector3f direction, double radius)
virtual void foot(const Eigen::Vector3f &point, Eigen::Vector3f &output) const
compute a point which gives perpendicular projection.
virtual void toMarker(visualization_msgs::Marker &marker, const Eigen::Vector3f ¢er, const Eigen::Vector3f &uz, const double height)
virtual PointPair findEndPoints(const Vertices &points) const
Extract end points from the points on the lines.
virtual Eigen::Vector3f getDirection()
virtual void filterPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const double threshold, pcl::PointIndices &output)
virtual double distanceToPoint(const Eigen::Vector3f &from) const
compute a distance to a point
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
virtual void estimateCenterAndHeight(const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::PointIndices &indices, Eigen::Vector3f ¢er, double &height)
boost::tuple< Point, Point > PointPair
Eigen::Vector3f direction_
Class to represent 3-D straight line.