1 #ifndef _RAPID_PERCEPTION_OBJECT_H_
2 #define _RAPID_PERCEPTION_OBJECT_H_
6 #include "geometry_msgs/PoseStamped.h"
7 #include "geometry_msgs/Vector3.h"
8 #include "pcl/PointIndices.h"
9 #include "pcl/point_cloud.h"
10 #include "pcl/point_types.h"
13 namespace perception {
21 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
GetCloud()
const;
25 void SetCloud(
const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
26 const pcl::PointIndices::ConstPtr& indices);
29 std::string
name()
const;
30 geometry_msgs::PoseStamped
pose()
const;
31 geometry_msgs::Vector3
scale()
const;
33 void set_name(
const std::string& name);
34 void set_pose(
const geometry_msgs::PoseStamped& ps);
35 void set_scale(
const geometry_msgs::Vector3& scale);
40 pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud_;
41 pcl::PointIndices::ConstPtr indices_;
44 geometry_msgs::PoseStamped pose_stamped_;
45 geometry_msgs::Vector3 scale_;
50 #endif // _RAPID_PERCEPTION_OBJECT_H_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr GetCloud() const
geometry_msgs::PoseStamped pose() const
geometry_msgs::Vector3 scale() const
void SetCloud(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices)
void set_pose(const geometry_msgs::PoseStamped &ps)
void set_scale(const geometry_msgs::Vector3 &scale)
void set_name(const std::string &name)