1 #ifndef _RAPID_PERCEPTION_SCENE_H_
2 #define _RAPID_PERCEPTION_SCENE_H_
6 #include "geometry_msgs/PoseStamped.h"
7 #include "geometry_msgs/Vector3.h"
8 #include "pcl/point_cloud.h"
9 #include "pcl/point_types.h"
14 namespace perception {
24 pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr
cloud()
const;
25 geometry_msgs::PoseStamped
pose();
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);
31 void set_scale(
const geometry_msgs::Vector3& scale);
39 pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud_;
43 geometry_msgs::PoseStamped pose_;
44 geometry_msgs::Vector3 scale_;
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)