Class RoomAnalyzer

Class Documentation

class RoomAnalyzer

Class that provides tools for different analysis over open space clusters to generate rooms.

Public Functions

RoomAnalyzer(room_analyzer_params params)

Constructor of class RoomAnalyzer.

Parameters:
  • private_nh

  • plane_utils_ptr

~RoomAnalyzer()
void analyze_skeleton_graph(const visualization_msgs::msg::MarkerArray::SharedPtr &skeleton_graph_msg)
Parameters:

skeleton_graph_msg

inline std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> extract_cloud_clusters()
Returns:

Cloud clusters

inline visualization_msgs::msg::MarkerArray extract_marker_array_clusters()
Returns:

Connected clusters marker array

pcl::PointCloud<pcl::PointXYZRGB>::Ptr extract_room_planes(RoomInfo &room_info, RoomPlanes &room_planes, pcl::PointXY p_min, pcl::PointXY p_max)
Parameters:
  • current_x_vert_planes

  • current_y_vert_planes

  • p_min

  • p_max

  • cloud_hull

  • x_plane1

  • x_plane2

  • y_plane1

  • y_plane2

  • found_x1_plane

  • found_x2_plane

  • found_y1_plane

  • found_y2_plane

Returns:

void extract_convex_hull(pcl::PointCloud<pcl::PointXYZRGB>::Ptr skeleton_cloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &cloud_hull, float &area)
Parameters:
  • skeleton_cloud

  • cloud_hull

  • area

void extract_cluster_endpoints(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &skeleton_cloud, pcl::PointXY &p1, pcl::PointXY &p2)
Parameters:
  • skeleton_cloud

  • p1

  • p2

bool extract_centroid_location(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &skeleton_cloud, const pcl::PointXY &p1, const pcl::PointXY &p2)
Parameters:
  • skeleton_cloud

  • p1

  • p2

Returns:

Success or Failure

bool extract_centroid_location(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &skeleton_cloud, const geometry_msgs::msg::Point &room_center)
Parameters:
  • skeleton_cloud

  • room_center

Returns:

Success or Failure

geometry_msgs::msg::Point extract_room_length(const pcl::PointXY &p1, const pcl::PointXY &p2)

Compute the distance between 2 points, p1 and p2.

Parameters:
  • p1

  • p2

Returns:

Distance between point p1 and point p2.

geometry_msgs::msg::Point extract_infinite_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)

Compute the center of a room.

Parameters:
  • plane_type

  • p1

  • p2

  • plane1

  • plane2

  • cluster_center

Returns:

The center point of the room.

bool perform_room_segmentation(RoomInfo &room_info, pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster, std::vector<situational_graphs_msgs::msg::RoomData> &room_candidates_vec, const visualization_msgs::msg::MarkerArray &cloud_marker_array)
Parameters:
  • current_x_vert_planes

  • current_y_vert_planes

  • cloud_cluster

  • cloud_hull

  • room_candidates_vec

Returns:

Success or Failure.

void downsample_cloud_data(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &cloud_hull)
Parameters:

cloud_hull