rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
object.h
Go to the documentation of this file.
1 #ifndef _RAPID_PERCEPTION_OBJECT_H_
2 #define _RAPID_PERCEPTION_OBJECT_H_
3 
4 #include <string>
5 
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"
11 
12 namespace rapid {
13 namespace perception {
14 // Represents an object that can be picked/placed.
15 class Object {
16  public:
17  // Default constructor.
18  Object();
19 
20  // Get a PointCloud representation of this Object.
21  pcl::PointCloud<pcl::PointXYZRGB>::Ptr GetCloud() const;
22 
23  // Set the point cloud containing this Object, and the indices of that point
24  // cloud representing this Object.
25  void SetCloud(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
26  const pcl::PointIndices::ConstPtr& indices);
27 
28  // Getters / setters.
29  std::string name() const;
30  geometry_msgs::PoseStamped pose() const;
31  geometry_msgs::Vector3 scale() const;
32 
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);
36 
37  // void Visualize();
38 
39  private:
40  pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud_;
41  pcl::PointIndices::ConstPtr indices_;
42 
43  std::string name_; // Name of this HSurface, e.g., "table"
44  geometry_msgs::PoseStamped pose_stamped_; // Pose of table's center.
45  geometry_msgs::Vector3 scale_; // Dimensions along x, y, and z, in meters.
46 };
47 } // namespace perception
48 } // namespace rapid
49 
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)
std::string name() const
void set_scale(const geometry_msgs::Vector3 &scale)
void set_name(const std::string &name)