Functions | |
| void | pointsToPlane (const geometry_msgs::Polygon &p, geometry_msgs::Polygon &q, const std::vector< double > &plane_coefficients) |
| Project a set of points onto a plane defined by ax+by+cz+d=0. | |
| void | pointsToPlane (sensor_msgs::PointCloud &p, const std::vector< int > &indices, const std::vector< double > &plane_coefficients) |
| Project a set of points (in place) onto a plane defined by ax+by+cz+d=0. | |
| void | pointsToPlane (const sensor_msgs::PointCloud &p, const std::vector< int > &indices, sensor_msgs::PointCloud &q, const std::vector< double > &plane_coefficients) |
| Project a set of points onto a plane defined by ax+by+cz+d=0. | |
| void | pointToPlane (const geometry_msgs::Point32 &p, geometry_msgs::Point32 &q, const std::vector< double > &plane_coefficients) |
| Project a point onto a plane defined by ax+by+cz+d=0. | |
| void | pointToPlane (const geometry_msgs::Point32 &p, geometry_msgs::Point32 &q, const std::vector< double > &plane_coefficients, double &distance) |
| Project a point onto a plane defined by ax+by+cz+d=0, and return the point to plane distance. | |
| void cloud_geometry::projections::pointsToPlane | ( | const geometry_msgs::Polygon & | p, |
| geometry_msgs::Polygon & | q, | ||
| const std::vector< double > & | plane_coefficients | ||
| ) | [inline] |
Project a set of points onto a plane defined by ax+by+cz+d=0.
| p | the points to project |
| q | the resultant projected points |
| plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 72 of file projections.h.
| void cloud_geometry::projections::pointsToPlane | ( | sensor_msgs::PointCloud & | p, |
| const std::vector< int > & | indices, | ||
| const std::vector< double > & | plane_coefficients | ||
| ) | [inline] |
Project a set of points (in place) onto a plane defined by ax+by+cz+d=0.
| p | the point cloud to project (in place) |
| indices | use only these point indices from the given cloud |
| plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 86 of file projections.h.
| void cloud_geometry::projections::pointsToPlane | ( | const sensor_msgs::PointCloud & | p, |
| const std::vector< int > & | indices, | ||
| sensor_msgs::PointCloud & | q, | ||
| const std::vector< double > & | plane_coefficients | ||
| ) | [inline] |
Project a set of points onto a plane defined by ax+by+cz+d=0.
| p | the point cloud to project |
| indices | use only these point indices from the given cloud |
| q | the resultant projected points |
| plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 100 of file projections.h.
| void cloud_geometry::projections::pointToPlane | ( | const geometry_msgs::Point32 & | p, |
| geometry_msgs::Point32 & | q, | ||
| const std::vector< double > & | plane_coefficients | ||
| ) | [inline] |
Project a point onto a plane defined by ax+by+cz+d=0.
| p | the point to project |
| q | the resultant projected point |
| plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 53 of file projections.h.
| void cloud_geometry::projections::pointToPlane | ( | const geometry_msgs::Point32 & | p, |
| geometry_msgs::Point32 & | q, | ||
| const std::vector< double > & | plane_coefficients, | ||
| double & | distance | ||
| ) | [inline] |
Project a point onto a plane defined by ax+by+cz+d=0, and return the point to plane distance.
| p | the point to project |
| q | the resultant projected point |
| plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
| distance | the computed distance from p to the plane |
Definition at line 115 of file projections.h.