Class PlaneUtils
Defined in File plane_utils.hpp
Class Documentation
-
class PlaneUtils
Public Types
Public Functions
-
PlaneUtils()
Public Static Functions
-
static float width_between_planes(Eigen::Vector4d v1, Eigen::Vector4d v2)
- Param :
-
static float width_between_planes(const situational_graphs_msgs::msg::PlaneData &plane1, const situational_graphs_msgs::msg::PlaneData &plane2)
- Param :
-
static void correct_plane_direction(int plane_type, situational_graphs_msgs::msg::PlaneData &plane)
- Param :
-
static void correct_plane_direction(int plane_type, Eigen::Vector4d &plane)
- Param :
-
static Eigen::Quaterniond euler_to_quaternion(const double roll, const double pitch, const double yaw)
-
static Eigen::Vector2d room_center(const Eigen::Vector4d &x_plane1, const Eigen::Vector4d &x_plane2, const Eigen::Vector4d &y_plane1, const Eigen::Vector4d &y_plane2)
- Param :
-
static geometry_msgs::msg::Pose room_center(const situational_graphs_msgs::msg::PlaneData &x_plane1, const situational_graphs_msgs::msg::PlaneData &x_plane2, const situational_graphs_msgs::msg::PlaneData &y_plane1, const situational_graphs_msgs::msg::PlaneData &y_plane2)
- Param :
-
static float plane_length(pcl::PointCloud<PointNormal>::Ptr cloud_seg, pcl::PointXY &p1, pcl::PointXY &p2, g2o::VertexSE3 *keyframe_node)
- Param :
-
static float plane_length(pcl::PointCloud<PointNormal>::Ptr cloud_seg, pcl::PointXY &p1, pcl::PointXY &p2)
- Param :
-
static pcl::PointXY convert_point_to_map(pcl::PointXY point_local, Eigen::Matrix4d keyframe_pose)
- Param :
-
static float get_min_segment(const pcl::PointCloud<PointNormal>::Ptr &cloud_1, const pcl::PointCloud<PointNormal>::Ptr &cloud_2)
- Param :
-
static bool check_point_neighbours(const pcl::PointCloud<PointNormal>::Ptr &cloud_1, const pcl::PointCloud<PointNormal>::Ptr &cloud_2)
- Param :
-
static bool compute_point_difference(const double plane1_point, const double plane2_point)
- Param :
-
static float plane_dot_product(const situational_graphs_msgs::msg::PlaneData &plane1, const situational_graphs_msgs::msg::PlaneData &plane2)
- Param :
-
static bool plane_dot_product(g2o::VertexPlane *plane1, g2o::VertexPlane *plane2)
-
static geometry_msgs::msg::Pose extract_infite_room_center(int plane_type, pcl::PointXY p1, pcl::PointXY p2, situational_graphs_msgs::msg::PlaneData plane1, situational_graphs_msgs::msg::PlaneData plane2, Eigen::Vector2d &cluster_center)
-
static double plane_difference(g2o::Plane3D plane1, g2o::Plane3D plane2)
- Param :
-
PlaneUtils()