23#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR 1
24#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR 0
34bool RGBDSensorParser::configure(
IRGBDSensor *interface)
37 iRGBDSensor = interface;
102 ret &= Property::copyPortable(params, params_b);
103 response.
append(params_b);
162 return DeviceResponder::respond(cmd,response);
182 isSubdeviceOwned(false),
183 subDeviceOwned(nullptr)
198 yCWarning(
RGBDSENSORWRAPPER) <<
"The old device is no longer supported, and it will be deprecated in YARP 3.7 and removed in YARP 4.";
217 if(use_YARP && !initialize_YARP(config))
223 if(use_ROS && !initialize_ROS(config))
233 if(! openAndAttachSubDevice(config))
241 if (!openDeferredAttach(config)) {
251 if (!config.
check(
"period",
"refresh period of the broadcasted values in ms"))
274 std::string confUseRos;
276 if (!rosGroup.
check(
"use_ROS"))
284 if (confUseRos ==
"true" || confUseRos ==
"only")
287 use_YARP = confUseRos ==
"true" ? true :
false;
292 if (verbose >= 3 && confUseRos !=
"false")
303 std::vector<param<std::string> > rosStringParam;
304 param<std::string>* prm;
313 for (i = 0; i < rosStringParam.size(); i++)
315 prm = &rosStringParam[i];
316 if (!rosGroup.
check(prm->parname))
328 if (rosGroup.
check(
"forceInfoSync"))
330 forceInfoSync = rosGroup.
find(
"forceInfoSync").
asBool();
336 std::string rootName;
337 rootName = config.
check(
"name",
Value(
"/"),
"starting '/' if needed.").asString();
339 if (!config.
check(
"name",
"Prefix name of the ports opened by the RGBD wrapper.")) {
346 rpcPort_Name = rootName +
"/rpc:i";
347 colorFrame_StreamingPort_Name = rootName +
"/rgbImage:o";
348 depthFrame_StreamingPort_Name = rootName +
"/depthImage:o";
351 if(config.
check(
"subdevice")) {
352 isSubdeviceOwned=
true;
354 isSubdeviceOwned=
false;
360bool RGBDSensorWrapper::openDeferredAttach(
Searchable& prop)
363 isSubdeviceOwned =
false;
367bool RGBDSensorWrapper::openAndAttachSubDevice(
Searchable& prop)
373 p.setMonitor(prop.getMonitor(),
"subdevice");
379 subDeviceOwned->
open(p);
381 if (!subDeviceOwned->
isValid())
386 isSubdeviceOwned =
true;
387 if(!
attach(subDeviceOwned)) {
404 delete subDeviceOwned;
405 subDeviceOwned=
nullptr;
409 isSubdeviceOwned =
false;
420 colorFrame_StreamingPort.
close();
421 depthFrame_StreamingPort.
close();
447 if(!rpcPort.
open(rpcPort_Name))
454 if(!colorFrame_StreamingPort.
open(colorFrame_StreamingPort_Name))
459 if(!depthFrame_StreamingPort.
open(depthFrame_StreamingPort_Name))
473 if (!rosPublisherPort_color.
topic(colorTopicName))
475 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << colorTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
478 if (!rosPublisherPort_depth.
topic(depthTopicName))
480 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << depthTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
483 if (!rosPublisherPort_colorCaminfo.
topic(cInfoTopicName))
485 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << cInfoTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
488 if (!rosPublisherPort_depthCaminfo.
topic(dInfoTopicName))
490 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << dInfoTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
505 if (device2attach.
size() != 1)
512 if(device2attach[0]->key ==
"IRGBDSensor")
521 if (!Idevice2attach->
isValid())
523 yCError(
RGBDSENSORWRAPPER) <<
"Device " << device2attach[0]->key <<
" to attach to is not valid ... cannot proceed";
527 Idevice2attach->
view(sensor_p);
528 Idevice2attach->
view(fgCtrl);
533 PeriodicThread::setPeriod(period);
534 return PeriodicThread::start();
544 if (isSubdeviceOwned) {
574 PeriodicThread::setPeriod(period);
575 return PeriodicThread::start();
582 poly->
view(sensor_p);
586 if(sensor_p ==
nullptr)
603 PeriodicThread::setPeriod(period);
604 return PeriodicThread::start();
640 std::string distModel;
641 std::string currentSensor;
644 std::vector<param<double> > parVector;
648 currentSensor = sensorType == COLOR_SENSOR ?
"Rgb" :
"Depth";
657 if(!camData.
check(
"distortionModel"))
664 if (distModel !=
"plumb_bob")
673 parVector.emplace_back(phyF,
"physFocalLength");
674 parVector.emplace_back(fx,
"focalLengthX");
675 parVector.emplace_back(fy,
"focalLengthY");
676 parVector.emplace_back(cx,
"principalPointX");
677 parVector.emplace_back(cy,
"principalPointY");
678 parVector.emplace_back(k1,
"k1");
679 parVector.emplace_back(k2,
"k2");
680 parVector.emplace_back(t1,
"t1");
681 parVector.emplace_back(t2,
"t2");
682 parVector.emplace_back(k3,
"k3");
683 parVector.emplace_back(stamp,
"stamp");
684 for(i = 0; i < parVector.size(); i++)
688 if(!camData.
check(par->parname))
696 cameraInfo.header.frame_id = frame_id;
697 cameraInfo.header.seq = seq;
698 cameraInfo.header.stamp = stamp;
701 cameraInfo.distortion_model = distModel;
703 cameraInfo.D.resize(5);
704 cameraInfo.D[0] = k1;
705 cameraInfo.D[1] = k2;
706 cameraInfo.D[2] = t1;
707 cameraInfo.D[3] = t2;
708 cameraInfo.D[4] = k3;
710 cameraInfo.K.resize(9);
711 cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx;
712 cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy;
713 cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1;
724 cameraInfo.R.assign(9, 0);
725 cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1;
727 cameraInfo.P.resize(12);
728 cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0;
729 cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0;
730 cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0;
732 cameraInfo.binning_x = cameraInfo.binning_y = 0;
733 cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0;
734 cameraInfo.roi.do_rectify =
false;
738bool RGBDSensorWrapper::writeData()
752 bool rgb_data_ok =
true;
753 bool depth_data_ok =
true;
755 if (((colorStamp.
getTime() - oldColorStamp.
getTime()) > 0) ==
false)
760 else { oldColorStamp = colorStamp; }
762 if (((depthStamp.
getTime() - oldDepthStamp.
getTime()) > 0) ==
false)
767 else { oldDepthStamp = depthStamp; }
778 colorFrame_StreamingPort.
write();
785 depthFrame_StreamingPort.
write();
798 rosPublisherPort_color.
write();
799 if (setCamInfo(camInfoC, rosFrameId, nodeSeq, COLOR_SENSOR))
802 {camInfoC.header.stamp = rColorImage.header.stamp;}
803 rosPublisherPort_colorCaminfo.
setEnvelope(colorStamp);
804 rosPublisherPort_colorCaminfo.
write();
818 rosPublisherPort_depth.
write();
819 if (setCamInfo(camInfoD, rosFrameId, nodeSeq, DEPTH_SENSOR))
822 {camInfoD.header.stamp = rDepthImage.header.stamp;}
823 rosPublisherPort_depthCaminfo.
setEnvelope(depthStamp);
824 rosPublisherPort_depthCaminfo.
write();
839 if (sensor_p!=
nullptr)
843 switch (sensorStatus)
845 case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
853 case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
constexpr yarp::conf::vocab32_t VOCAB_DEPTH_VISUAL_PARAMS
constexpr yarp::conf::vocab32_t VOCAB_RGBD_SENSOR
constexpr yarp::conf::vocab32_t VOCAB_RGB_VISUAL_PARAMS
constexpr yarp::conf::vocab32_t VOCAB_EXTRINSIC_PARAM
constexpr yarp::conf::vocab32_t VOCAB_RGBD_PROTOCOL_VERSION
constexpr yarp::conf::vocab32_t VOCAB_STATUS
constexpr yarp::conf::vocab32_t VOCAB_FRAMEGRABBER_CONTROL
constexpr yarp::conf::vocab32_t VOCAB_ERROR_MSG
constexpr yarp::conf::vocab32_t VOCAB_IS
constexpr yarp::conf::vocab32_t VOCAB_GET
constexpr yarp::conf::vocab32_t VOCAB_FAILED
constexpr yarp::conf::vocab32_t VOCAB_SET
const yarp::os::LogComponent & RGBDSENSORWRAPPER()
#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR
#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR
constexpr double DEFAULT_THREAD_PERIOD
bool configure(yarp::dev::IRGBDSensor *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool detach() override
Detach the object (you must have first called attach).
bool attachAll(const yarp::dev::PolyDriverList &p) override
Specify which sensor this thread has to read from.
~RGBDSensorWrapper() override
bool close() override
Close the DeviceDriver.
bool fromConfig(yarp::os::Searchable ¶ms)
void run() override
Loop function.
bool threadInit() override
Initialization method.
bool open(yarp::os::Searchable ¶ms) override
Device driver interface.
void threadRelease() override
Release method.
bool detachAll() override
Detach the object (you must have first called attach).
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
bool view(T *&x)
Get an interface to the device driver.
An interface for retrieving intrinsic parameter from a depth camera.
Control interface for frame grabber devices.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
virtual std::string getLastErrorMsg(yarp::os::Stamp *timeStamp=nullptr)=0
Return an error message in case of error.
int getRgbWidth() override=0
Return the width of each frame.
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the rgb camera.
int getDepthWidth() override=0
Return the height of each frame.
virtual bool getExtrinsicParam(yarp::sig::Matrix &extrinsic)=0
Get the extrinsic parameters from the device.
int getRgbHeight() override=0
Return the height of each frame.
virtual bool getImages(yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=nullptr, yarp::os::Stamp *depthStamp=nullptr)=0
Get the both the color and depth frame in a single call.
virtual RGBDSensor_status getSensorStatus()=0
Get the surrent status of the sensor, using enum type.
int getDepthHeight() override=0
Return the height of each frame.
bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the depth camera.
An interface for retrieving intrinsic parameter from a rgb camera.
A container for a device driver.
bool isValid() const
Check if device is valid.
bool open(const std::string &txt)
Construct and configure a device by its common name.
A simple collection of objects that can be described and transmitted in a portable way.
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
void append(const Bottle &alt)
Append the content of the given bottle to the current list.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
void clear()
Empties the bottle of any objects it contains.
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
bool isNull() const override
Checks if the object is invalid.
void addString(const char *str)
Places a string in the bottle, at the end of the list.
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
void close() override
Stop port activity.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
void interrupt()
interrupt delegates the call to the Node port interrupt.
An abstraction for a periodic thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
void setReader(PortReader &reader) override
Set an external reader for port data.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void close() override
Stop port activity.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
A class for storing options and configuration information.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
bool topic(const std::string &name)
Set topic to publish to.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
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 std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
An abstraction for a time stamp and/or sequence number.
double getTime() const
Get the time stamp.
A single value (typically within a Bottle).
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
virtual bool asBool() const
Get boolean value.
virtual std::int32_t asInt32() const
Get 32-bit integer value.
virtual std::string asString() const
Get string value.
bool configure(yarp::dev::IDepthVisualParams *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool configure(yarp::dev::IFrameGrabberControls *interface)
bool configure(yarp::dev::IRgbVisualParams *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
Image class with user control of representation details.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
const std::string depthInfoTopicName_param
const std::string depthTopicName_param
const std::string colorTopicName_param
const std::string nodeName_param
const std::string frameId_param
const std::string colorInfoTopicName_param
yarp::rosmsg::sensor_msgs::Image Image
yarp::rosmsg::sensor_msgs::CameraInfo CameraInfo
void shallowCopyImages(const yarp::sig::FlexImage &src, yarp::sig::FlexImage &dest)
void deepCopyImages(const yarp::sig::FlexImage &src, yarp::rosmsg::sensor_msgs::Image &dest, const std::string &frame_id, const yarp::rosmsg::TickTime &timeStamp, const unsigned int &seq)
For streams capable of holding different kinds of content, check what they actually have.
std::string decode(NetInt32 code)
Convert a vocabulary identifier into a string.
An interface to the operating system, including Port based communication.