32 using namespace openni;
35 #ifndef RETURN_FALSE_STATUS_NOT_OK
36 #define RETURN_FALSE_STATUS_NOT_OK(s) if(s != STATUS_OK) { yCError(DEPTHCAMERA) << OpenNI::getExtendedError(); return false; }
41 constexpr
char accuracy [] =
"accuracy";
43 constexpr
char depth_Fov [] =
"depth_Fov";
44 constexpr
char depthRes [] =
"depthResolution";
45 constexpr
char rgb_Fov [] =
"rgb_Fov";
46 constexpr
char rgbRes [] =
"rgbResolution";
47 constexpr
char rgbMirroring [] =
"rgbMirroring";
48 constexpr
char depthMirroring [] =
"depthMirroring";
51 static std::map<std::string, RGBDSensorParamParser::RGBDParam>
params_map =
71 openni::PixelFormat pixF{openni::PixelFormat::PIXEL_FORMAT_DEPTH_1_MM};
79 bool isValid(){
return frameRef.isValid() & isReady;}
83 std::lock_guard<std::mutex> guard(mutex);
84 return inputImage.
copy(image);
89 std::lock_guard<std::mutex> guard(mutex);
94 void onNewFrame(openni::VideoStream& stream)
override;
95 openni::VideoFrameRef frameRef;
103 void streamFrameListener::onNewFrame(openni::VideoStream& stream)
105 std::lock_guard<std::mutex> guard(mutex);
106 stream.readFrame(&frameRef);
108 if (!frameRef.isValid() || !frameRef.getData())
110 yCInfo(DEPTHCAMERA) <<
"Frame lost";
116 pixF = stream.getVideoMode().getPixelFormat();
118 w = frameRef.getWidth();
119 h = frameRef.getHeight();
120 dataSize = frameRef.getDataSize();
122 if (isReady ==
false)
129 yCError(DEPTHCAMERA) <<
"Pixel Format not recognized";
133 image.setPixelCode(pixC);
136 if (image.getRawImageSize() != (
size_t) frameRef.getDataSize())
138 yCError(DEPTHCAMERA) <<
"Device and local copy data size doesn't match";
142 memcpy((
void*)image.getRawImage(), (
void*)frameRef.getData(), frameRef.getDataSize());
151 m_depthRegistration =
true;
171 delete m_paramParser;
174 bool depthCameraDriver::initializeOpeNIDevice()
178 rc = OpenNI::initialize();
181 yCError(DEPTHCAMERA) <<
"Initialize failed," << OpenNI::getExtendedError();
185 rc = m_device.open(ANY_DEVICE);
188 yCError(DEPTHCAMERA) <<
"Couldn't open device," << OpenNI::getExtendedError();
192 if (m_device.getSensorInfo(SENSOR_COLOR) !=
nullptr)
194 rc = m_imageStream.create(m_device, SENSOR_COLOR);
197 yCError(DEPTHCAMERA) <<
"Couldn't create color stream," << OpenNI::getExtendedError();
202 rc = m_imageStream.start();
205 yCError(DEPTHCAMERA) <<
"Couldn't start the color stream," << OpenNI::getExtendedError();
209 if (m_device.getSensorInfo(SENSOR_DEPTH) !=
nullptr)
211 rc = m_depthStream.create(m_device, SENSOR_DEPTH);
214 yCError(DEPTHCAMERA) <<
"Couldn't create depth stream," << OpenNI::getExtendedError();
219 if (m_depthRegistration)
221 if (m_device.isImageRegistrationModeSupported(IMAGE_REGISTRATION_DEPTH_TO_COLOR))
223 if (m_device.setImageRegistrationMode(IMAGE_REGISTRATION_DEPTH_TO_COLOR) == STATUS_OK)
225 yCInfo(DEPTHCAMERA) <<
"Depth successfully registered on rgb sensor";
229 yCWarning(DEPTHCAMERA) <<
"Depth registration failed.. sending unregistered images";
234 yCWarning(DEPTHCAMERA) <<
"Depth image registration not supported by this device";
238 rc = m_depthStream.start();
241 yCError(DEPTHCAMERA) <<
"Couldn't start the depth stream," << OpenNI::getExtendedError();
245 m_imageStream.addNewFrameListener(m_imageFrame);
246 m_depthStream.addNewFrameListener(m_depthFrame);
252 void depthCameraDriver::settingErrorMsg(
const string& error,
bool&
ret)
258 bool depthCameraDriver::setParams()
296 settingErrorMsg(
"Param " +
params_map[depth_Fov].name +
" is not a double as it should be.",
ret);
299 settingErrorMsg(
"Setting param " +
params_map[depth_Fov].name +
" failed... quitting.",
ret);
313 settingErrorMsg(
"Param " +
params_map[rgb_Fov].name +
" is not a double as it should be.",
ret);
318 settingErrorMsg(
"Setting param " +
params_map[rgb_Fov].name +
" failed... quitting.",
ret);
349 settingErrorMsg(
"Param " +
params_map[
rgbRes].name +
" is not a int as it should be.",
ret);
369 settingErrorMsg(
"Param " +
params_map[rgbMirroring].name +
" is not a bool as it should be.",
ret);
373 for (
int t = 0;
t < 5;
t++)
375 yCInfo(DEPTHCAMERA) <<
"Trying to set rgb mirroring parameter for the" <<
t+1 <<
"time/s";
379 yCInfo(DEPTHCAMERA) <<
"Rgb mirroring parameter set successfully";
386 settingErrorMsg(
"Setting param " +
params_map[rgbMirroring].name +
" failed... quitting.",
ret);
400 settingErrorMsg(
"Param " +
params_map[depthMirroring].name +
" is not a bool as it should be.",
ret);
403 for (
int t = 0;
t < 5;
t++)
405 yCInfo(DEPTHCAMERA) <<
"Trying to set depth mirroring parameter for the" <<
t+1 <<
"time/s";
409 yCInfo(DEPTHCAMERA) <<
"Depth mirroring parameter set successfully";
416 settingErrorMsg(
"Setting param " +
params_map[depthMirroring].name +
" failed... quitting.",
ret);
425 std::vector<RGBDSensorParamParser::RGBDParam*> params;
428 params.push_back(&(p.second));
431 if (!m_paramParser->
parseParam(config, params))
433 yCError(DEPTHCAMERA) <<
"Failed to parse the parameters";
438 m_depthRegistration = !(config.
check(
"registered") && config.
find(
"registered").
isBool() && config.
find(
"registered").
asBool() ==
false);
440 if (!initializeOpeNIDevice())
456 m_imageStream.stop();
457 m_imageStream.destroy();
458 m_depthStream.stop();
459 m_depthStream.destroy();
472 return m_imageStream.getVideoMode().getResolutionY();
482 return m_imageStream.getVideoMode().getResolutionX();
487 yCWarning(DEPTHCAMERA) <<
"getRgbSupportedConfigurations not implemented yet";
498 width = m_imageStream.getVideoMode().getResolutionX();
499 height = m_imageStream.getVideoMode().getResolutionY();
508 yCError(DEPTHCAMERA) <<
"Cannot set. Depth resolution is a description!";
512 return setResolution(width, height, m_depthStream);
515 bool depthCameraDriver::setResolution(
int width,
int height, VideoStream& stream)
520 vm = stream.getVideoMode();
521 vm.setResolution(width, height);
523 bRet = (stream.setVideoMode(vm) == STATUS_OK);
528 yCError(DEPTHCAMERA) << OpenNI::getExtendedError();
541 return setResolution(width, height, m_imageStream);
544 bool depthCameraDriver::setFOV(
double horizontalFov,
double verticalFov, VideoStream& stream)
557 return setFOV(horizontalFov, verticalFov, m_depthStream);
566 return setFOV(horizontalFov, verticalFov, m_depthStream);
576 a1 = fabs(_accuracy - 0.001) < 0.00001;
577 a2 = fabs(_accuracy - 0.0001) < 0.00001;
580 yCError(DEPTHCAMERA) <<
"Supporting accuracy of 1mm (0.001) or 100um (0.0001) only at the moment";
588 vm = m_imageStream.getVideoMode();
589 pf = fabs(_accuracy - 0.001) < 0.00001 ? PIXEL_FORMAT_DEPTH_1_MM : PIXEL_FORMAT_DEPTH_100_UM;
591 vm.setPixelFormat(pf);
592 m_depthStream.stop();
593 ret = m_depthStream.setVideoMode(vm) == STATUS_OK;
598 yCError(DEPTHCAMERA) << OpenNI::getExtendedError();
607 horizontalFov =
params_map[rgb_Fov].val[0].asFloat64();
608 verticalFov =
params_map[rgb_Fov].val[1].asFloat64();
611 horizontalFov = m_imageStream.getHorizontalFieldOfView() *
RAD2DEG;
612 verticalFov = m_imageStream.getVerticalFieldOfView() *
RAD2DEG;
620 mirror =
params_map[rgbMirroring].val[0].asBool();
624 mirror = m_imageStream.getMirroringEnabled();
635 if (m_imageStream.setMirroringEnabled(mirror) != STATUS_OK)
642 return (
ret == mirror);
653 return setIntrinsic(intrinsic, m_paramParser->
rgbIntrinsic);
662 return m_depthStream.getVideoMode().getResolutionY();
671 return m_depthStream.getVideoMode().getResolutionX();
678 horizontalFov =
params_map[depth_Fov].val[0].asFloat64();
679 verticalFov =
params_map[depth_Fov].val[1].asFloat64();
682 horizontalFov = m_depthStream.getHorizontalFieldOfView() *
RAD2DEG;
683 verticalFov = m_depthStream.getVerticalFieldOfView() *
RAD2DEG;
689 return setIntrinsic(intrinsic, m_paramParser->
rgbIntrinsic);
698 return m_depthStream.getVideoMode().getPixelFormat() == PIXEL_FORMAT_DEPTH_1_MM ? 0.001 : 0.0001;
711 nearPlane = m_depthStream.getMinPixelValue() * factor;
712 farPlane = m_depthStream.getMaxPixelValue() * factor;
733 return params_map[depthMirroring].val[0].asBool();
735 mirror = m_depthStream.getMirroringEnabled();
749 return (
ret == mirror);
760 return getImage(rgbImage, timeStamp, m_imageFrame);
765 return getImage(
depthImage, timeStamp, m_depthFrame);
792 case (PIXEL_FORMAT_RGB888):
795 case (PIXEL_FORMAT_DEPTH_1_MM):
798 case (PIXEL_FORMAT_DEPTH_100_UM):
801 case (PIXEL_FORMAT_SHIFT_9_2):
804 case (PIXEL_FORMAT_SHIFT_9_3):
807 case (PIXEL_FORMAT_GRAY8):
810 case (PIXEL_FORMAT_GRAY16):
828 std::lock_guard<std::mutex> guard(sourceFrame->
mutex);
831 yCError(DEPTHCAMERA) <<
"Device not ready";
838 if (sourceFrame->
dataSize !=
size_t(h * w *
sizeof(
short)) ||
839 (sourceFrame->
pixF != PIXEL_FORMAT_DEPTH_100_UM && sourceFrame->
pixF != PIXEL_FORMAT_DEPTH_1_MM))
841 yCError(DEPTHCAMERA) <<
"getImage: image format error";
850 factor = sourceFrame->
pixF == PIXEL_FORMAT_DEPTH_1_MM ? 0.001 : 0.0001;
853 rawImage =
reinterpret_cast<float*
> (Frame.
getRawImage());
856 for(i = 0; i < w * h; i++)
858 rawImage[i] = srcRawImage[i] * factor;
866 return getImage(colorFrame, colorStamp, m_imageFrame) & getImage(depthFrame, depthStamp, m_depthFrame);
871 openni::DeviceState status;
872 status = DEVICE_STATE_NOT_READY;
873 if (m_device.isValid() &&
874 m_imageStream.isValid() &&
875 m_depthStream.isValid() &&
879 status = DEVICE_STATE_OK;
883 case DEVICE_STATE_OK:
886 case DEVICE_STATE_NOT_READY:
898 return OpenNI::getExtendedError();
917 if (std::find(m_supportedFeatures.begin(), m_supportedFeatures.end(), f) != m_supportedFeatures.end())
934 yCError(DEPTHCAMERA) <<
"Feature not supported!";
951 vm = m_imageStream.getVideoMode();
952 vm.setFps(
int(value));
955 m_depthStream.getVideoMode();
956 vm.setFps(
int(value));
961 yCError(DEPTHCAMERA) <<
"No manual mode for white_balance. call hasManual() to know if a specific feature support Manual mode instead of wasting my time";
964 yCError(DEPTHCAMERA) <<
"Feature not supported!";
975 yCError(DEPTHCAMERA) <<
"Feature not supported!";
983 *value = m_imageStream.getCameraSettings()->getExposure();
986 *value = m_imageStream.getCameraSettings()->getGain();
989 *value = (m_imageStream.getVideoMode().getFps());
992 yCError(DEPTHCAMERA) <<
"No manual mode for white_balance. call hasManual() to know if a specific feature support Manual mode";
1002 yCError(DEPTHCAMERA) <<
"No 2-valued feature are supported";
1008 yCError(DEPTHCAMERA) <<
"No 2-valued feature are supported";
1017 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1036 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1042 yCError(DEPTHCAMERA) <<
"Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1068 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1074 yCError(DEPTHCAMERA) <<
"Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1078 *isActive = m_imageStream.getCameraSettings()->getAutoWhiteBalanceEnabled();
1087 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1106 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1125 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1137 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1160 yCError(DEPTHCAMERA) <<
"Feature does not have both auto and manual mode";
1169 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1180 yCError(DEPTHCAMERA) <<
"Feature does not have both auto and manual mode";
1189 yCError(DEPTHCAMERA) <<
"Feature not supported!";
1195 yCError(DEPTHCAMERA) <<
"Feature doesn't have OnePush";
@ YARP_FEATURE_FRAME_RATE
@ YARP_FEATURE_WHITE_BALANCE
bool setActive(int feature, bool onoff) override
Set the requested feature on or off.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getCameraDescription(CameraDescriptor *camera) override
Get a basic description of the camera hw.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool hasManual(int feature, bool *hasManual) override
Check if the requested feature has the 'manual' mode.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
int getDepthHeight() override
Return the height of each frame.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
int getRgbHeight() override
Return the height of each frame.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool close() override
Close the DeviceDriver.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
bool hasFeature(int feature, bool *hasFeature) override
Check if camera has the requested feature (saturation, brightness ...
bool hasOnOff(int feature, bool *HasOnOff) override
Check if the camera has the ability to turn on/off the requested feature.
bool getActive(int feature, bool *isActive) override
Get the current status of the feature, on or off.
bool setMode(int feature, FeatureMode mode) override
Set the requested mode for the feature.
int getRgbWidth() override
Return the width of each frame.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
int getDepthWidth() override
Return the height of each frame.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool getFeature(int feature, double *value) override
Get the current value for the requested feature.
bool setFeature(int feature, double value) override
Set the requested feature to a value (saturation, brightness ...
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool hasAuto(int feature, bool *hasAuto) override
Check if the requested feature has the 'auto' mode.
bool hasOnePush(int feature, bool *hasOnePush) override
Check if the requested feature has the 'onePush' mode.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
static int pixFormatToCode(openni::PixelFormat p)
bool setOnePush(int feature) override
Set the requested feature to a value (saturation, brightness ...
bool getMode(int feature, FeatureMode *mode) override
Get the current mode for the feature.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
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 class for storing options and configuration information.
A base class for nested structures that can be searched.
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.
An abstraction for a time stamp and/or sequence number.
static void delaySystem(double seconds)
A single value (typically within a Bottle).
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool isBool() const
Checks if value is a boolean.
virtual bool asBool() const
Get boolean value.
virtual std::int32_t asInt32() const
Get 32-bit integer value.
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
virtual bool isInt32() const
Checks if value is a 32-bit integer.
Image class with user control of representation details.
unsigned char * getRawImage() const
Access to the internal image buffer.
bool copy(const Image &alt)
Copy operator.
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,...)
An interface for the device drivers.
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).
void toProperty(yarp::os::Property &intrinsic) const
toProperty, convert the struct to a Property.