Program Listing for File room_analyzer.hpp

Return to documentation for file (include/s_graphs/frontend/room_analyzer.hpp)

/*
Copyright (c) 2023, University of Luxembourg
All rights reserved.

Redistributions and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this
   list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice,
   this list of conditions and the following disclaimer in the documentation
   and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its
   contributors may be used to endorse or promote products derived from
   this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS'
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
*/

#ifndef ROOM_ANALYZER_HPP
#define ROOM_ANALYZER_HPP

#include <math.h>
#include <pcl/common/angles.h>
#include <pcl/common/common.h>
#include <pcl/common/distances.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/surface/convex_hull.h>

#include <boost/format.hpp>
#include <cmath>
#include <iostream>
#include <s_graphs/common/plane_utils.hpp>
#include <string>

#include "geometry_msgs/msg/point.hpp"
#include "rclcpp/rclcpp.hpp"
#include "situational_graphs_msgs/msg/plane_data.hpp"
#include "situational_graphs_msgs/msg/planes_data.hpp"
#include "situational_graphs_msgs/msg/rooms_data.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

namespace s_graphs {

struct room_analyzer_params {
  long int vertex_neigh_thres;
};

struct RoomInfo {
 public:
  const std::vector<situational_graphs_msgs::msg::PlaneData>& current_x_vert_planes;
  const std::vector<situational_graphs_msgs::msg::PlaneData>& current_y_vert_planes;
  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster;
};

struct RoomPlanes {
 public:
  situational_graphs_msgs::msg::PlaneData& x_plane1;
  situational_graphs_msgs::msg::PlaneData& x_plane2;
  situational_graphs_msgs::msg::PlaneData& y_plane1;
  situational_graphs_msgs::msg::PlaneData& y_plane2;
  bool found_x1_plane;
  bool found_x2_plane;
  bool found_y1_plane;
  bool found_y2_plane;
};

class RoomAnalyzer {
 public:
  RoomAnalyzer(room_analyzer_params params);
  ~RoomAnalyzer();

  void analyze_skeleton_graph(
      const visualization_msgs::msg::MarkerArray::SharedPtr& skeleton_graph_msg);

  std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> extract_cloud_clusters() {
    return cloud_clusters;
  }

  visualization_msgs::msg::MarkerArray extract_marker_array_clusters() {
    return 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);

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

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

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

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

  geometry_msgs::msg::Point extract_room_length(const pcl::PointXY& p1,
                                                const pcl::PointXY& 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);

  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);

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

 private:
  bool is_x1_plane_aligned_w_y(
      const std::vector<geometry_msgs::msg::Vector3> x_plane1_points,
      const std::vector<geometry_msgs::msg::Vector3> y_plane_points);

  bool is_x2_plane_aligned_w_y(
      const std::vector<geometry_msgs::msg::Vector3> x_plane2_points,
      const std::vector<geometry_msgs::msg::Vector3> y_plane_point);

  bool is_y1_plane_aligned_w_x(
      const std::vector<geometry_msgs::msg::Vector3> y_plane1_points,
      const std::vector<geometry_msgs::msg::Vector3> x_plane_points);

  bool is_y2_plane_aligned_w_x(
      const std::vector<geometry_msgs::msg::Vector3> y_plane2_points,
      const std::vector<geometry_msgs::msg::Vector3> x_plane_points);

 private:
  int vertex_neigh_thres;

  std::mutex skeleton_graph_mutex;
  std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> cloud_clusters;
  std::vector<std::pair<int, int>> subgraphs;
  visualization_msgs::msg::MarkerArray clusters_marker_array;

 private:
  std::vector<float> find_plane_points(
      const pcl::PointXY& start_point,
      const pcl::PointXY& end_point,
      const situational_graphs_msgs::msg::PlaneData& plane);

  int find_plane_points(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud_hull,
                        const situational_graphs_msgs::msg::PlaneData& plane,
                        pcl::PointCloud<pcl::PointXYZRGB>::Ptr& sub_cloud_cluster);

  pcl::PointXYZRGB compute_centroid(const pcl::PointXYZRGB& p1,
                                    const pcl::PointXYZRGB& p2);
};
}  // namespace s_graphs

#endif  // ROOM_ANALYZER_HPP