|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
48 cfg.
put(
"device",
"fakeFrameGrabber");
49 testgrabber.
open(cfg);
50 testgrabber.
view(image);
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);
66 if (config.
check(get<1>(p)))
72 *get<0>(p) = get<2>(p);
92 return image->
width();
97 yCWarning(FAKEDEPTHCAMERA) <<
"getRgbSupportedConfigurations not implemented yet";
103 width = image->
width();
120 rgb_Hfov = horizontalFov;
121 rgb_Vfov = verticalFov;
127 dep_Hfov = horizontalFov;
128 dep_Vfov = verticalFov;
134 accuracy = in_accuracy;
140 horizontalFov = rgb_Hfov;
141 verticalFov = rgb_Vfov;
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);
181 return image->
width();
186 horizontalFov = dep_Hfov;
187 verticalFov = dep_Vfov;
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);
216 nearPlane = dep_near;
223 dep_near = nearPlane;
253 if (!image->
getImage(imageof)) {
return false;}
256 memcpy((
void*)rgbImage.
getRawImage(), (
void*)imageof.getRawImage(), imageof.getRawImageSize());
263 if (!image->
getImage(imageof)) {
return false;}
265 for (
size_t i = 0; i < imageof.width(); i++)
267 for (
size_t j = 0; j < imageof.height(); 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;
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
A base class for nested structures that can be searched.
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
#define yCWarning(component,...)
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
#define YARP_LOG_COMPONENT(name,...)
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool view(T *&x)
Get an interface to the device driver.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool open(const std::string &txt)
Construct and configure a device by its common name.
int getDepthHeight() override
Return the height of each frame.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
An interface for the device drivers.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
float PixelFloat
Floating point pixel type.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
Image class with user control of representation details.
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.
void setPixelCode(int imgPixelCode)
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
void resize(size_t imgWidth, size_t imgHeight)
Reallocate an image to be of a desired size, throwing away its current contents.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
int getRgbWidth() override
Return the width of each frame.
int getRgbHeight() override
Return the height of each frame.
void resize(size_t r, size_t c)
Resize the matrix, if matrix is not empty preserve old content.
An abstraction for a time stamp and/or sequence number.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
An interface to the operating system, including Port based communication.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
int getDepthWidth() override
Return the height of each frame.
virtual int height() const =0
Return the height of each frame.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
void zero()
Zero the matrix.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
virtual int width() const =0
Return the width of each frame.
bool close() override
Close the DeviceDriver.
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
unsigned char * getRawImage() const
Access to the internal image buffer.
A class for storing options and configuration information.
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.