rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
scene.h
Go to the documentation of this file.
1 #ifndef _RAPID_PERCEPTION_SCENE_H_
2 #define _RAPID_PERCEPTION_SCENE_H_
3 
4 #include <string>
5 
6 #include "geometry_msgs/PoseStamped.h"
7 #include "geometry_msgs/Vector3.h"
8 #include "pcl/point_cloud.h"
9 #include "pcl/point_types.h"
10 
12 
13 namespace rapid {
14 namespace perception {
15 // A Scene is a semantic representation of a point cloud.
16 //
17 // Currently, it models a single horizontal surface (HSurface) with objects on
18 // top of it.
19 class Scene {
20  public:
21  Scene();
22 
23  // Getters/setters.
24  pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud() const;
25  geometry_msgs::PoseStamped pose();
26  HSurface primary_surface() const;
27  geometry_msgs::Vector3 scale();
28  void set_cloud(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud);
29  void set_pose(const geometry_msgs::PoseStamped& ps);
30  void set_primary_surface(const HSurface& surface);
31  void set_scale(const geometry_msgs::Vector3& scale);
32 
33  // Look up an object by name. If the object exists, returns it.
34  //
35  // Returns false if the object is not found, true otherwise.
36  bool GetObject(const std::string& name, Object* object);
37 
38  private:
39  pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud_;
40  HSurface primary_surface_;
41 
42  // Pose and scale represent the bounding box of the cropped scene.
43  geometry_msgs::PoseStamped pose_;
44  geometry_msgs::Vector3 scale_;
45 };
46 } // namespace rapid
47 } // namespace perception
48 #endif // _RAPID_PERCEPTION_SCENE_H_
geometry_msgs::Vector3 scale()
void set_pose(const geometry_msgs::PoseStamped &ps)
void set_scale(const geometry_msgs::Vector3 &scale)
pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr cloud() const
bool GetObject(const std::string &name, Object *object)
HSurface primary_surface() const
void set_primary_surface(const HSurface &surface)
geometry_msgs::PoseStamped pose()
void set_cloud(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud)