#include <geometry_msgs/Point.h>#include <geometry_msgs/Point32.h>#include <geometry_msgs/PointStamped.h>#include <sensor_msgs/PointCloud.h>#include <geometry_msgs/Polygon.h>#include <door_handle_detector/geometry/point.h>#include <door_handle_detector/geometry/nearest.h>#include <Eigen/Core>

Go to the source code of this file.
Namespaces | |
| namespace | cloud_geometry |
| namespace | cloud_geometry::angles |
Functions | |
| void | cloud_geometry::angles::flipNormalTowardsViewpoint (Eigen::Vector4d &normal, const geometry_msgs::Point32 &point, const geometry_msgs::PointStamped &viewpoint) |
| Flip (in place) the estimated normal of a point towards a given viewpoint. | |
| void | cloud_geometry::angles::flipNormalTowardsViewpoint (Eigen::Vector4d &normal, const geometry_msgs::Point32 &point, const geometry_msgs::Point &viewpoint) |
| Flip (in place) the estimated normal of a point towards a given viewpoint. | |
| void | cloud_geometry::angles::flipNormalTowardsViewpoint (Eigen::Vector4d &normal, const geometry_msgs::Point32 &point, const geometry_msgs::Point32 &viewpoint) |
| Flip (in place) the estimated normal of a point towards a given viewpoint. | |
| void | cloud_geometry::angles::flipNormalTowardsViewpoint (std::vector< double > &normal, const geometry_msgs::Point32 &point, const geometry_msgs::PointStamped &viewpoint) |
| Flip (in place) the estimated normal of a point towards a given viewpoint. | |
| void | cloud_geometry::angles::flipNormalTowardsViewpoint (std::vector< double > &normal, const geometry_msgs::Point32 &point, const geometry_msgs::Point32 &viewpoint) |
| Flip (in place) the estimated normal of a point towards a given viewpoint. | |
| double | cloud_geometry::angles::getAngle2D (const double point[2]) |
| Compute the angle in the [ 0, 2*PI ) interval of a point (direction) with a reference (0, 0) in 2D. | |
| double | cloud_geometry::angles::getAngle2D (double x, double y) |
| Compute the angle in the [ 0, 2*PI ) interval of a point (direction) with a reference (0, 0) in 2D. | |
| double | cloud_geometry::angles::getAngle3D (const geometry_msgs::Point32 &v1, const geometry_msgs::Point32 &v2) |
| Compute the smallest angle between two vectors in the [ 0, PI ) interval in 3D. | |
| double | cloud_geometry::angles::getAngle3D (const geometry_msgs::Point &v1, const geometry_msgs::Point &v2) |
| Compute the smallest angle between two vectors in the [ 0, PI ) interval in 3D. | |
| double | cloud_geometry::angles::getAngle3D (const geometry_msgs::Point32 &v1, const geometry_msgs::Point &v2) |
| Compute the smallest angle between two vectors in the [ 0, PI ) interval in 3D. | |
| double | cloud_geometry::angles::getAngle3D (const geometry_msgs::Point &v1, const geometry_msgs::Point32 &v2) |
| Compute the smallest angle between two vectors in the [ 0, PI ) interval in 3D. | |
| double | cloud_geometry::angles::getAngleBetweenPlanes (const std::vector< double > &plane_a, const std::vector< double > &plane_b) |
| Get the angle between two planes. | |
| double | cloud_geometry::angles::getAngleBetweenPlanes (const geometry_msgs::Point32 &plane_a, const geometry_msgs::Point32 &plane_b) |
| Get the angle between two planes. | |
| double | cloud_geometry::angles::getAngleBetweenPlanes (const geometry_msgs::Point32 &plane_a, const std::vector< double > &plane_b) |
| Get the angle between two planes. | |
| double | cloud_geometry::angles::getAngleBetweenPlanes (const std::vector< double > &plane_a, const geometry_msgs::Point32 &plane_b) |
| Get the angle between two planes. | |