ed
measurement.h
Go to the documentation of this file.
1 #ifndef measurement_h_
2 #define measurement_h_
3 
4 #include "ed/types.h"
5 #include "ed/mask.h"
6 #include "ed/rgbd_data.h"
7 
8 namespace ed
9 {
10 
12 {
13 
14 public:
15 
16  Measurement();
17 
18  Measurement(rgbd::ImageConstPtr image, const ImageMask& image_mask, const geo::Pose3D& sensor_pose);
19 
20  Measurement(const RGBDData& rgbd_data, const PointCloudMaskPtr& mask, unsigned int seq = 0);
21 
22  const geo::Pose3D& sensorPose() const { return rgbd_data_.sensor_pose; }
24  PointCloudMaskConstPtr mask() const { return mask_; }
25  const ImageMask& imageMask() const { return image_mask_; }
26  double timestamp() const { return timestamp_; }
27 
28 protected:
29 
33  double timestamp_;
34  unsigned int seq_;
35 
36 };
37 
38 }
39 
40 #endif
ed::Measurement::sensorPose
const geo::Pose3D & sensorPose() const
Definition: measurement.h:22
std::shared_ptr< const Image >
ed::Measurement::image
rgbd::ImageConstPtr image() const
Definition: measurement.h:23
types.h
ed::RGBDData::image
rgbd::ImageConstPtr image
Original RGBD image received from the sensor.
Definition: rgbd_data.h:25
ed::Measurement::seq_
unsigned int seq_
Definition: measurement.h:34
geo::Transform3T
ed::RGBDData
Definition: rgbd_data.h:22
ed::PointCloudMaskConstPtr
pcl::IndicesConstPtr PointCloudMaskConstPtr
Definition: rgbd_data.h:16
ed::Measurement::image_mask_
ImageMask image_mask_
Definition: measurement.h:32
ed::Measurement::mask
PointCloudMaskConstPtr mask() const
Definition: measurement.h:24
ed::Measurement::rgbd_data_
RGBDData rgbd_data_
Definition: measurement.h:30
ed::PointCloudMaskPtr
pcl::IndicesPtr PointCloudMaskPtr
Definition: rgbd_data.h:15
mask.h
ed::Measurement
Definition: measurement.h:11
ed::Measurement::timestamp_
double timestamp_
Definition: measurement.h:33
ed::Measurement::timestamp
double timestamp() const
Definition: measurement.h:26
ed::Measurement::imageMask
const ImageMask & imageMask() const
Definition: measurement.h:25
ed::RGBDData::sensor_pose
geo::Pose3D sensor_pose
Definition: rgbd_data.h:27
rgbd_data.h
ed::Measurement::mask_
PointCloudMaskPtr mask_
Definition: measurement.h:31
ed::ImageMask
Definition: mask.h:17
ed
Definition: convex_hull.h:8
ed::Measurement::Measurement
Measurement()
Definition: measurement.cpp:10