19using namespace openni;
21#ifndef RETURN_FALSE_STATUS_NOT_OK
22#define RETURN_FALSE_STATUS_NOT_OK(s) if(s != STATUS_OK) { yCError(DEPTHCAMERA) << OpenNI::getExtendedError(); return false; }
27constexpr char accuracy [] =
"accuracy";
30constexpr char depthRes [] =
"depthResolution";
31constexpr char rgb_Fov [] =
"rgb_Fov";
32constexpr char rgbRes [] =
"rgbResolution";
37static std::map<std::string, RGBDSensorParamParser::RGBDParam>
params_map =
57 openni::PixelFormat
pixF{openni::PixelFormat::PIXEL_FORMAT_DEPTH_1_MM};
80 void onNewFrame(openni::VideoStream& stream)
override;
81 openni::VideoFrameRef frameRef;
89void streamFrameListener::onNewFrame(openni::VideoStream& stream)
92 stream.readFrame(&frameRef);
94 if (!frameRef.isValid() || !frameRef.getData())
102 pixF = stream.getVideoMode().getPixelFormat();
104 w = frameRef.getWidth();
105 h = frameRef.getHeight();
137 m_depthRegistration =
true;
159 delete m_paramParser;
163bool depthCameraDriver::initializeOpeNIDevice()
167 rc = OpenNI::initialize();
186 yCError(
DEPTHCAMERA) <<
"Couldn't create color stream," << OpenNI::getExtendedError();
191 rc = m_imageStream.start();
194 yCError(
DEPTHCAMERA) <<
"Couldn't start the color stream," << OpenNI::getExtendedError();
203 yCError(
DEPTHCAMERA) <<
"Couldn't create depth stream," << OpenNI::getExtendedError();
208 if (m_depthRegistration)
227 rc = m_depthStream.start();
230 yCError(
DEPTHCAMERA) <<
"Couldn't start the depth stream," << OpenNI::getExtendedError();
234 m_imageStream.addNewFrameListener(m_imageFrame);
235 m_depthStream.addNewFrameListener(m_depthFrame);
241void depthCameraDriver::settingErrorMsg(
const std::string&
error,
bool&
ret)
247bool depthCameraDriver::setParams()
289 if (!
p1.isFloat64() || !
p2.isFloat64()) {
307 if (!
p1.isFloat64() || !
p2.isFloat64() )
309 settingErrorMsg(
"Param " +
params_map[
rgb_Fov].name +
" is not a double as it should be.",
ret);
325 if (!
p1.isInt32() || !
p2.isInt32() )
343 if (!
p1.isInt32() || !
p2.isInt32() )
345 settingErrorMsg(
"Param " +
params_map[
rgbRes].name +
" is not a int as it should be.",
ret);
369 for (
int t = 0; t < 5; t++)
371 yCInfo(
DEPTHCAMERA) <<
"Trying to set rgb mirroring parameter for the" << t+1 <<
"time/s";
399 for (
int t = 0; t < 5; t++)
401 yCInfo(
DEPTHCAMERA) <<
"Trying to set depth mirroring parameter for the" << t+1 <<
"time/s";
421 std::vector<RGBDSensorParamParser::RGBDParam*> params;
424 params.push_back(&(p.second));
427 if (!m_paramParser->
parseParam(config, params))
434 m_depthRegistration = !(config.
check(
"registered") && config.
find(
"registered").isBool() && config.
find(
"registered").asBool() ==
false);
436 if (!initializeOpeNIDevice())
452 m_imageStream.stop();
453 m_imageStream.destroy();
454 m_depthStream.stop();
455 m_depthStream.destroy();
468 return m_imageStream.getVideoMode().getResolutionY();
478 return m_imageStream.getVideoMode().getResolutionX();
494 width = m_imageStream.getVideoMode().getResolutionX();
495 height = m_imageStream.getVideoMode().getResolutionY();
508 return setResolution(width, height, m_depthStream);
511ReturnValue depthCameraDriver::setResolution(
int width,
int height, VideoStream& stream)
516 vm = stream.getVideoMode();
517 vm.setResolution(width, height);
519 bRet = (stream.setVideoMode(
vm) == STATUS_OK);
537 return setResolution(width, height, m_imageStream);
540ReturnValue depthCameraDriver::setFOV(
double horizontalFov,
double verticalFov, VideoStream& stream)
553 return setFOV(horizontalFov, verticalFov, m_depthStream);
562 return setFOV(horizontalFov, verticalFov, m_depthStream);
576 yCError(
DEPTHCAMERA) <<
"Supporting accuracy of 1mm (0.001) or 100um (0.0001) only at the moment";
584 vm = m_imageStream.getVideoMode();
587 vm.setPixelFormat(
pf);
588 m_depthStream.stop();
589 ret = m_depthStream.setVideoMode(
vm) == STATUS_OK;
607 horizontalFov = m_imageStream.getHorizontalFieldOfView() *
RAD2DEG;
608 verticalFov = m_imageStream.getVerticalFieldOfView() *
RAD2DEG;
620 mirror = m_imageStream.getMirroringEnabled();
631 if (m_imageStream.setMirroringEnabled(mirror) != STATUS_OK)
638 return (
ret == mirror);
643 values.toProperty(intrinsic);
649 return setIntrinsic(intrinsic, m_paramParser->
rgbIntrinsic);
658 return m_depthStream.getVideoMode().getResolutionY();
667 return m_depthStream.getVideoMode().getResolutionX();
678 horizontalFov = m_depthStream.getHorizontalFieldOfView() *
RAD2DEG;
679 verticalFov = m_depthStream.getVerticalFieldOfView() *
RAD2DEG;
685 return setIntrinsic(intrinsic, m_paramParser->
rgbIntrinsic);
707 nearPlane = m_depthStream.getMinPixelValue() *
factor;
708 farPlane = m_depthStream.getMaxPixelValue() *
factor;
731 mirror = m_depthStream.getMirroringEnabled();
745 return (
ret == mirror);
756 return getImage(
rgbImage, timeStamp, m_imageFrame);
761 return getImage(
depthImage, timeStamp, m_depthFrame);
834 if (
sourceFrame->dataSize !=
size_t(h * w *
sizeof(
short)) ||
852 for(i = 0; i < w * h; i++)
862 return getImage(
colorFrame, colorStamp, m_imageFrame) & getImage(
depthFrame, depthStamp, m_depthFrame);
867 openni::DeviceState status;
869 if (m_device.isValid() &&
870 m_imageStream.isValid() &&
871 m_depthStream.isValid() &&
894 return OpenNI::getExtendedError();
913 if (std::find(m_supportedFeatures.begin(), m_supportedFeatures.end(),
f) != m_supportedFeatures.end())
947 vm = m_imageStream.getVideoMode();
948 vm.setFps(
int(value));
951 m_depthStream.getVideoMode();
952 vm.setFps(
int(value));
957 yCError(
DEPTHCAMERA) <<
"No manual mode for white_balance. call hasManual() to know if a specific feature support Manual mode instead of wasting my time";
979 *value = m_imageStream.getCameraSettings()->getExposure();
982 *value = m_imageStream.getCameraSettings()->getGain();
985 *value = (m_imageStream.getVideoMode().getFps());
988 yCError(
DEPTHCAMERA) <<
"No manual mode for white_balance. call hasManual() to know if a specific feature support Manual mode";
1038 yCError(
DEPTHCAMERA) <<
"Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1070 yCError(
DEPTHCAMERA) <<
"Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1074 *
isActive = m_imageStream.getCameraSettings()->getAutoWhiteBalanceEnabled();
yarp::dev::ReturnValue getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
yarp::dev::ReturnValue setMode(int feature, FeatureMode mode) override
yarp::dev::ReturnValue setActive(int feature, bool onoff) override
yarp::dev::ReturnValue setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
yarp::dev::ReturnValue getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
yarp::dev::ReturnValue setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
int getDepthHeight() override
Return the height of each frame.
yarp::dev::ReturnValue hasFeature(int feature, bool *hasFeature) override
yarp::dev::ReturnValue setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
int getRgbHeight() override
Return the height of each frame.
RGBDSensor_status getSensorStatus() override
yarp::dev::ReturnValue getCameraDescription(CameraDescriptor *camera) override
yarp::dev::ReturnValue getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool close() override
Close the DeviceDriver.
yarp::dev::ReturnValue getDepthAccuracy(double &accuracy) override
Get the minimum detectable variation in distance [meter].
yarp::dev::ReturnValue getActive(int feature, bool *isActive) override
yarp::dev::ReturnValue getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
yarp::dev::ReturnValue getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
yarp::dev::ReturnValue setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
yarp::dev::ReturnValue getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
yarp::dev::ReturnValue getMode(int feature, FeatureMode *mode) override
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
yarp::dev::ReturnValue getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
yarp::dev::ReturnValue hasAuto(int feature, bool *hasAuto) override
yarp::dev::ReturnValue getFeature(int feature, double *value) override
int getRgbWidth() override
Return the width of each frame.
int getDepthWidth() override
Return the height of each frame.
yarp::dev::ReturnValue getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
yarp::dev::ReturnValue setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
yarp::dev::ReturnValue hasManual(int feature, bool *hasManual) override
yarp::dev::ReturnValue getRgbSupportedConfigurations(std::vector< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
yarp::dev::ReturnValue hasOnOff(int feature, bool *HasOnOff) override
yarp::dev::ReturnValue getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
yarp::dev::ReturnValue getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
static int pixFormatToCode(openni::PixelFormat p)
yarp::dev::ReturnValue setFeature(int feature, double value) override
yarp::dev::ReturnValue setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
yarp::dev::ReturnValue setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
yarp::dev::ReturnValue getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
yarp::dev::ReturnValue setOnePush(int feature) override
yarp::dev::ReturnValue setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
yarp::dev::ReturnValue getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
yarp::dev::ReturnValue hasOnePush(int feature, bool *hasOnePush) override
bool getImage(FlexImage &inputImage)
yarp::sig::FlexImage image
yarp::os::Stamp getStamp()
@ RGBD_SENSOR_GENERIC_ERROR
The RGBDSensorParamParser class.
yarp::sig::Matrix transformationMatrix
bool parseParam(const yarp::os::Searchable &config, std::vector< RGBDParam * > ¶ms)
parseParam, parse the params stored in a Searchable.
yarp::sig::IntrinsicParams rgbIntrinsic
A mini-server for performing network communication in the background.
A class for storing options and configuration information.
A base class for nested structures that can be searched.
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.
An abstraction for a time stamp and/or sequence number.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
static void delaySystem(double seconds)
A single value (typically within a Bottle).
virtual bool isBool() const
Checks if value is a boolean.
virtual bool asBool() const
Get boolean value.
Image class with user control of representation details.
void setPixelCode(int imgPixelCode)
unsigned char * getRawImage() const
Access to the internal image buffer.
size_t getRawImageSize() const
Access to the internal buffer size information (this is how much memory has been allocated for the im...
void resize(size_t imgWidth, size_t imgHeight)
Reallocate an image to be of a desired size, throwing away its current contents.
#define RETURN_FALSE_STATUS_NOT_OK(s)
static std::map< std::string, RGBDSensorParamParser::RGBDParam > params_map
#define yCInfo(component,...)
#define yCError(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
@ YARP_FEATURE_FRAME_RATE
@ YARP_FEATURE_WHITE_BALANCE
An interface to the operating system, including Port based communication.
constexpr char clipPlanes[]
constexpr char depthRes[]
constexpr char accuracy[]
std::string deviceDescription
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).