YARP
Yet Another Robot Platform
fakeDepthCameraDriver.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
10 
11 #include <yarp/os/LogComponent.h>
12 #include <yarp/os/LogStream.h>
13 #include <yarp/os/Value.h>
14 
15 #include <algorithm>
16 #include <map>
17 #include <cmath>
18 
19 using namespace yarp::dev;
20 using namespace yarp::sig;
21 using namespace yarp::os;
22 using namespace std;
23 
24 namespace {
25 YARP_LOG_COMPONENT(FAKEDEPTHCAMERA, "yarp.device.fakeDepthCamera")
26 }
27 
29  rgb_h(480),
30  rgb_w(640),
31  dep_h(480),
32  dep_w(640),
33  rgb_Vfov(36),
34  rgb_Hfov(50),
35  dep_Vfov(36),
36  dep_Hfov(50),
37  dep_far(6),
38  image(nullptr)
39 {}
40 
42 
44 {
45  Property cfg;
46  cfg.fromString(config.toString());
47  cfg.unput("device");
48  cfg.put("device", "fakeFrameGrabber");
49  testgrabber.open(cfg);
50  testgrabber.view(image);
51 
52  vector<tuple<double*, string, double> > param;
53  param.emplace_back(&rgb_h, "rgb_h", 480.0);
54  param.emplace_back(&rgb_w, "rgb_w", 640.0);
55  param.emplace_back(&dep_h, "rgb_h", 480.0);
56  param.emplace_back(&dep_w, "rgb_w", 640.0);
57  param.emplace_back(&accuracy, "accuracy", 0.001);
58  param.emplace_back(&rgb_Vfov, "rgb_Vfov", 50.0);
59  param.emplace_back(&rgb_Hfov, "rgb_Hfov", 36.0);
60  param.emplace_back(&dep_Vfov, "dep_Vfov", 50.0);
61  param.emplace_back(&dep_Hfov, "dep_Hfov", 36.0);
62  param.emplace_back(&dep_near, "dep_near", 0.2);
63  param.emplace_back(&dep_far, "dep_far", 6.0);
64  for (auto p : param)
65  {
66  if (config.check(get<1>(p)))
67  {
68  *get<0>(p) = config.find(get<1>(p)).asFloat64();
69  }
70  else
71  {
72  *get<0>(p) = get<2>(p);
73  }
74 
75  }
76 
77  return true;
78 }
79 
81 {
82  return true;
83 }
84 
86 {
87  return image->height();
88 }
89 
91 {
92  return image->width();
93 }
94 
96 {
97  yCWarning(FAKEDEPTHCAMERA) << "getRgbSupportedConfigurations not implemented yet";
98  return false;
99 }
100 
101 bool fakeDepthCameraDriver::getRgbResolution(int &width, int &height)
102 {
103  width = image->width();
104  height = image->height();
105  return true;
106 }
107 
108 bool fakeDepthCameraDriver::setRgbResolution(int width, int height)
109 {
110  return false;
111 }
112 
113 bool fakeDepthCameraDriver::setDepthResolution(int width, int height)
114 {
115  return false;
116 }
117 
118 bool fakeDepthCameraDriver::setRgbFOV(double horizontalFov, double verticalFov)
119 {
120  rgb_Hfov = horizontalFov;
121  rgb_Vfov = verticalFov;
122  return true;
123 }
124 
125 bool fakeDepthCameraDriver::setDepthFOV(double horizontalFov, double verticalFov)
126 {
127  dep_Hfov = horizontalFov;
128  dep_Vfov = verticalFov;
129  return true;
130 }
131 
133 {
134  accuracy = in_accuracy;
135  return true;
136 }
137 
138 bool fakeDepthCameraDriver::getRgbFOV(double &horizontalFov, double &verticalFov)
139 {
140  horizontalFov = rgb_Hfov;
141  verticalFov = rgb_Vfov;
142  return false;
143 }
144 
146 {
147  mirror = false;
148  return true;
149 }
150 
152 {
153  return false;
154 }
155 
157 {
158  intrinsic.put("physFocalLength", 0.5);
159  intrinsic.put("focalLengthX", 512);
160  intrinsic.put("focalLengthY", 512);
161  intrinsic.put("principalPointX", 235);
162  intrinsic.put("principalPointY", 231);
163  intrinsic.put("distortionModel", "plumb_bob");
164  intrinsic.put("k1", 0);
165  intrinsic.put("k2", 0);
166  intrinsic.put("t1", 0);
167  intrinsic.put("t2", 0);
168  intrinsic.put("k3", 0);
169 
170  intrinsic.put("stamp", yarp::os::Time::now());
171  return true;
172 }
173 
175 {
176  return image->height();
177 }
178 
180 {
181  return image->width();
182 }
183 
184 bool fakeDepthCameraDriver::getDepthFOV(double& horizontalFov, double& verticalFov)
185 {
186  horizontalFov = dep_Hfov;
187  verticalFov = dep_Vfov;
188  return false;
189 }
190 
192 {
193  intrinsic.put("physFocalLength", 0.5);
194  intrinsic.put("focalLengthX", 512);
195  intrinsic.put("focalLengthY", 512);
196  intrinsic.put("principalPointX", 235);
197  intrinsic.put("principalPointY", 231);
198  intrinsic.put("distortionModel", "plumb_bob");
199  intrinsic.put("k1", 0);
200  intrinsic.put("k2", 0);
201  intrinsic.put("t1", 0);
202  intrinsic.put("t2", 0);
203  intrinsic.put("k3", 0);
204 
205  intrinsic.put("stamp", yarp::os::Time::now());
206  return true;
207 }
208 
210 {
211  return accuracy;
212 }
213 
214 bool fakeDepthCameraDriver::getDepthClipPlanes(double& nearPlane, double& farPlane)
215 {
216  nearPlane = dep_near;
217  farPlane = dep_far;
218  return true;
219 }
220 
221 bool fakeDepthCameraDriver::setDepthClipPlanes(double nearPlane, double farPlane)
222 {
223  dep_near = nearPlane;
224  dep_far = farPlane;
225  return true;
226 }
227 
229 {
230  mirror = false;
231  return true;
232 }
233 
235 {
236  return false;
237 }
238 
240 {
241  extrinsic.resize(4, 4);
242  extrinsic.zero();
243 
244  extrinsic[0][0] = 1;
245  extrinsic[1][1] = 1;
246  extrinsic[2][2] = 1;
247  extrinsic[3][3] = 1;
248  return true;
249 }
250 
252 {
253  if (!image->getImage(imageof)) {return false;}
254  rgbImage.setPixelCode(VOCAB_PIXEL_RGB);
255  rgbImage.resize(imageof);
256  memcpy((void*)rgbImage.getRawImage(), (void*)imageof.getRawImage(), imageof.getRawImageSize());
257  if(timeStamp) timeStamp->update(yarp::os::Time::now());
258  return true;
259 }
260 
262 {
263  if (!image->getImage(imageof)) {return false;}
264  depthImage.resize(imageof);
265  for (size_t i = 0; i < imageof.width(); i++)
266  {
267  for (size_t j = 0; j < imageof.height(); j++)
268  {
269  PixelRgb pix = (*(PixelRgb*)imageof.getPixelAddress(i, j));
270  *(PixelFloat*)depthImage.getPixelAddress(i, j) = (float(pix.b) / 255.0)/3.0 + (float(pix.g) / 255.0) / 3.0 + (float(pix.r) / 255.0) / 3.0;
271  }
272  }
273  if(timeStamp)
274  timeStamp->update(yarp::os::Time::now());
275  return true;
276 }
277 
278 bool fakeDepthCameraDriver::getImages(FlexImage& colorFrame, ImageOf<PixelFloat>& depthFrame, Stamp* colorStamp, Stamp* depthStamp)
279 {
280  return getRgbImage(colorFrame, colorStamp) & getDepthImage(depthFrame, depthStamp);
281 }
282 
284 {
285  return RGBD_SENSOR_OK_IN_USE;
286 }
287 
289 {
290  return "no error";
291 }
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
int getRgbHeight() override
Return the height of each frame.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool close() override
Close the DeviceDriver.
int getDepthWidth() override
Return the height of each frame.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
int getDepthHeight() override
Return the height of each frame.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
int getRgbWidth() override
Return the width of each frame.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:77
virtual bool getImage(yarp::sig::ImageOf< yarp::sig::PixelRgb > &image)=0
Get an rgb image from the frame grabber, if required demosaicking/color reconstruction is applied.
virtual int width() const =0
Return the width of each frame.
virtual int height() const =0
Return the height of each frame.
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:143
A class for storing options and configuration information.
Definition: Property.h:37
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1046
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
Definition: Property.cpp:1029
A base class for nested structures that can be searched.
Definition: Searchable.h:69
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:113
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
Image class with user control of representation details.
Definition: Image.h:403
void setPixelCode(int imgPixelCode)
Definition: Image.h:406
Typed image class.
Definition: Image.h:647
unsigned char * getPixelAddress(size_t x, size_t y) const
Get address of a pixel in memory.
Definition: Image.h:227
size_t width() const
Gets width of image in pixels.
Definition: Image.h:153
unsigned char * getRawImage() const
Access to the internal image buffer.
Definition: Image.cpp:535
size_t getRawImageSize() const
Access to the internal buffer size information (this is how much memory has been allocated for the im...
Definition: Image.cpp:544
void resize(size_t imgWidth, size_t imgHeight)
Reallocate an image to be of a desired size, throwing away its current contents.
Definition: Image.cpp:467
size_t height() const
Gets height of image in pixels.
Definition: Image.h:159
A class for a Matrix.
Definition: Matrix.h:46
void zero()
Zero the matrix.
Definition: Matrix.cpp:308
void resize(size_t r, size_t c)
Resize the matrix, if matrix is not empty preserve old content.
Definition: Matrix.cpp:251
Provides:
Definition: Vector.h:122
#define yCWarning(component,...)
Definition: LogComponent.h:146
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
@ VOCAB_PIXEL_RGB
Definition: Image.h:50
An interface for the device drivers.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:25
float PixelFloat
Floating point pixel type.
Definition: Image.h:572
Packed RGB pixel type.
Definition: Image.h:453
unsigned char g
Definition: Image.h:455
unsigned char r
Definition: Image.h:454
unsigned char b
Definition: Image.h:456