ed
measurement.cpp
Go to the documentation of this file.
1 #include "ed/measurement.h"
2 
3 #include <rgbd/image.h>
4 
5 namespace ed
6 {
7 
8 // ----------------------------------------------------------------------------------------------------
9 
10 Measurement::Measurement() : timestamp_(0)
11 {
12 }
13 
14 // ----------------------------------------------------------------------------------------------------
15 
16 Measurement::Measurement(rgbd::ImageConstPtr image, const ImageMask& image_mask, const geo::Pose3D& sensor_pose) :
17  image_mask_(image_mask),
18  timestamp_(image->getTimestamp())
19 {
21  rgbd_data_.sensor_pose = sensor_pose;
22 }
23 
24 // ----------------------------------------------------------------------------------------------------
25 
26 Measurement::Measurement(const RGBDData& rgbd_data, const PointCloudMaskPtr& mask, unsigned int seq) :
27  rgbd_data_(rgbd_data),
28  mask_(mask),
29  timestamp_(rgbd_data.image->getTimestamp()),
30  seq_(seq)
31 {
32  // Calculate image mask
33  image_mask_.setSize(rgbd_data.image->getDepthImage().cols, rgbd_data.image->getDepthImage().rows);
34  for(PointCloudMask::const_iterator it = mask_->begin(); it != mask_->end(); ++it)
35  {
37  for(std::vector<int>::const_iterator it2 = pixel_idxs.begin(); it2 != pixel_idxs.end(); ++it2)
38  image_mask_.addPoint(*it2);
39  }
40 
41 }
42 
43 }
std::shared_ptr< const Image >
ed::Measurement::image
rgbd::ImageConstPtr image() const
Definition: measurement.h:23
std::vector< int >
ed::RGBDData::image
rgbd::ImageConstPtr image
Original RGBD image received from the sensor.
Definition: rgbd_data.h:25
geo::Transform3T
ed::RGBDData
Definition: rgbd_data.h:22
image
cv::Mat image
Definition: view_model.cpp:42
ed::Measurement::image_mask_
ImageMask image_mask_
Definition: measurement.h:32
image.h
ed::Measurement::rgbd_data_
RGBDData rgbd_data_
Definition: measurement.h:30
measurement.h
ed::ImageMask::addPoint
void addPoint(const cv::Point2i &p)
Definition: mask.h:71
ed::PointCloudMaskPtr
pcl::IndicesPtr PointCloudMaskPtr
Definition: rgbd_data.h:15
ed::RGBDData::sensor_pose
geo::Pose3D sensor_pose
Definition: rgbd_data.h:27
std::vector::begin
T begin(T... args)
ed::Measurement::mask_
PointCloudMaskPtr mask_
Definition: measurement.h:31
ed::ImageMask
Definition: mask.h:17
ed::RGBDData::point_cloud_to_pixels_mapping
PointCloudToPixelsMapping point_cloud_to_pixels_mapping
Mapping from point cloud to pixel indices in the full resolution depth image.
Definition: rgbd_data.h:36
ed
Definition: convex_hull.h:8
std::vector::end
T end(T... args)
ed::Measurement::Measurement
Measurement()
Definition: measurement.cpp:10
ed::ImageMask::setSize
void setSize(int width, int height)
Definition: mask.h:37