23 #define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR 1
24 #define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR 0
37 iRGBDSensor = interface;
38 ret = rgbParser.configure(interface);
39 ret &= depthParser.configure(interface);
45 bool ret = rgbParser.configure(rgbInterface);
46 ret &= depthParser.configure(depthInterface);
52 return fgCtrlParsers.configure(_fgCtrl);
66 ret = rgbParser.respond(cmd, response);
73 ret = depthParser.respond(cmd, response);
80 ret = fgCtrlParsers.respond(cmd, response);
95 ret = iRGBDSensor->getExtrinsicParam(params);
102 ret &= Property::copyPortable(params, params_b);
103 response.
append(params_b);
115 response.
addString(iRGBDSensor->getLastErrorMsg());
135 response.
addInt32(iRGBDSensor->getSensorStatus());
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.6 and removed in YARP 4.";
217 setId(
"RGBDSensorWrapper for " + depthFrame_StreamingPort_Name);
219 if(use_YARP && !initialize_YARP(config))
225 if(use_ROS && !initialize_ROS(config))
235 if(! openAndAttachSubDevice(config))
243 if (!openDeferredAttach(config)) {
253 if (!config.
check(
"period",
"refresh period of the broadcasted values in ms"))
276 std::string confUseRos;
278 if (!rosGroup.
check(
"use_ROS"))
286 if (confUseRos ==
"true" || confUseRos ==
"only")
289 use_YARP = confUseRos ==
"true" ? true :
false;
294 if (verbose >= 3 && confUseRos !=
"false")
305 std::vector<param<std::string> > rosStringParam;
306 param<std::string>* prm;
315 for (i = 0; i < rosStringParam.size(); i++)
317 prm = &rosStringParam[i];
318 if (!rosGroup.
check(prm->parname))
330 if (rosGroup.
check(
"forceInfoSync"))
332 forceInfoSync = rosGroup.
find(
"forceInfoSync").
asBool();
338 std::string rootName;
339 rootName = config.
check(
"name",
Value(
"/"),
"starting '/' if needed.").asString();
341 if (!config.
check(
"name",
"Prefix name of the ports opened by the RGBD wrapper.")) {
348 rpcPort_Name = rootName +
"/rpc:i";
349 colorFrame_StreamingPort_Name = rootName +
"/rgbImage:o";
350 depthFrame_StreamingPort_Name = rootName +
"/depthImage:o";
353 if(config.
check(
"subdevice")) {
354 isSubdeviceOwned=
true;
356 isSubdeviceOwned=
false;
362 bool RGBDSensorWrapper::openDeferredAttach(
Searchable& prop)
365 isSubdeviceOwned =
false;
369 bool RGBDSensorWrapper::openAndAttachSubDevice(
Searchable& prop)
375 p.setMonitor(prop.getMonitor(),
"subdevice");
381 subDeviceOwned->
open(p);
383 if (!subDeviceOwned->
isValid())
388 isSubdeviceOwned =
true;
389 if(!
attach(subDeviceOwned)) {
406 delete subDeviceOwned;
407 subDeviceOwned=
nullptr;
411 isSubdeviceOwned =
false;
422 colorFrame_StreamingPort.
close();
423 depthFrame_StreamingPort.
close();
449 if(!rpcPort.
open(rpcPort_Name))
456 if(!colorFrame_StreamingPort.
open(colorFrame_StreamingPort_Name))
461 if(!depthFrame_StreamingPort.
open(depthFrame_StreamingPort_Name))
475 if (!rosPublisherPort_color.
topic(colorTopicName))
477 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << colorTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
480 if (!rosPublisherPort_depth.
topic(depthTopicName))
482 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << depthTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
485 if (!rosPublisherPort_colorCaminfo.
topic(cInfoTopicName))
487 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << cInfoTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
490 if (!rosPublisherPort_depthCaminfo.
topic(dInfoTopicName))
492 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << dInfoTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
517 if (device2attach.
size() != 1)
524 if(device2attach[0]->key ==
"IRGBDSensor")
533 if (!Idevice2attach->
isValid())
535 yCError(
RGBDSENSORWRAPPER) <<
"Device " << device2attach[0]->key <<
" to attach to is not valid ... cannot proceed";
539 Idevice2attach->
view(sensor_p);
540 Idevice2attach->
view(fgCtrl);
545 PeriodicThread::setPeriod(period);
546 return PeriodicThread::start();
556 if (isSubdeviceOwned) {
586 PeriodicThread::setPeriod(period);
587 return PeriodicThread::start();
594 poly->
view(sensor_p);
598 if(sensor_p ==
nullptr)
615 PeriodicThread::setPeriod(period);
616 return PeriodicThread::start();
652 std::string distModel;
653 std::string currentSensor;
656 std::vector<param<double> > parVector;
660 currentSensor = sensorType == COLOR_SENSOR ?
"Rgb" :
"Depth";
669 if(!camData.
check(
"distortionModel"))
676 if (distModel !=
"plumb_bob")
685 parVector.emplace_back(phyF,
"physFocalLength");
686 parVector.emplace_back(fx,
"focalLengthX");
687 parVector.emplace_back(fy,
"focalLengthY");
688 parVector.emplace_back(cx,
"principalPointX");
689 parVector.emplace_back(cy,
"principalPointY");
690 parVector.emplace_back(k1,
"k1");
691 parVector.emplace_back(k2,
"k2");
692 parVector.emplace_back(t1,
"t1");
693 parVector.emplace_back(t2,
"t2");
694 parVector.emplace_back(k3,
"k3");
695 parVector.emplace_back(stamp,
"stamp");
696 for(i = 0; i < parVector.size(); i++)
700 if(!camData.
check(par->parname))
715 cameraInfo.
D.resize(5);
716 cameraInfo.
D[0] = k1;
717 cameraInfo.
D[1] = k2;
718 cameraInfo.
D[2] = t1;
719 cameraInfo.
D[3] = t2;
720 cameraInfo.
D[4] = k3;
722 cameraInfo.
K.resize(9);
723 cameraInfo.
K[0] = fx; cameraInfo.
K[1] = 0; cameraInfo.
K[2] = cx;
724 cameraInfo.
K[3] = 0; cameraInfo.
K[4] = fy; cameraInfo.
K[5] = cy;
725 cameraInfo.
K[6] = 0; cameraInfo.
K[7] = 0; cameraInfo.
K[8] = 1;
736 cameraInfo.
R.assign(9, 0);
737 cameraInfo.
R.at(0) = cameraInfo.
R.at(4) = cameraInfo.
R.at(8) = 1;
739 cameraInfo.
P.resize(12);
740 cameraInfo.
P[0] = fx; cameraInfo.
P[1] = 0; cameraInfo.
P[2] = cx; cameraInfo.
P[3] = 0;
741 cameraInfo.
P[4] = 0; cameraInfo.
P[5] = fy; cameraInfo.
P[6] = cy; cameraInfo.
P[7] = 0;
742 cameraInfo.
P[8] = 0; cameraInfo.
P[9] = 0; cameraInfo.
P[10] = 1; cameraInfo.
P[11] = 0;
750 bool RGBDSensorWrapper::writeData()
764 bool rgb_data_ok =
true;
765 bool depth_data_ok =
true;
767 if (((colorStamp.
getTime() - oldColorStamp.
getTime()) > 0) ==
false)
772 else { oldColorStamp = colorStamp; }
774 if (((depthStamp.
getTime() - oldDepthStamp.
getTime()) > 0) ==
false)
779 else { oldDepthStamp = depthStamp; }
790 colorFrame_StreamingPort.
write();
797 depthFrame_StreamingPort.
write();
810 rosPublisherPort_color.
write();
811 if (setCamInfo(camInfoC, rosFrameId, nodeSeq, COLOR_SENSOR))
815 rosPublisherPort_colorCaminfo.
setEnvelope(colorStamp);
816 rosPublisherPort_colorCaminfo.
write();
830 rosPublisherPort_depth.
write();
831 if (setCamInfo(camInfoD, rosFrameId, nodeSeq, DEPTH_SENSOR))
835 rosPublisherPort_depthCaminfo.
setEnvelope(depthStamp);
836 rosPublisherPort_depthCaminfo.
write();
851 if (sensor_p!=
nullptr)
855 switch (sensorStatus)
857 case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
865 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 setId(const std::string &id)
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,...
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.
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.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
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.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
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.
std::string distortion_model
std::vector< yarp::conf::float64_t > R
std::vector< yarp::conf::float64_t > K
yarp::rosmsg::sensor_msgs::RegionOfInterest roi
std::vector< yarp::conf::float64_t > P
yarp::rosmsg::std_msgs::Header header
std::vector< yarp::conf::float64_t > D
yarp::rosmsg::std_msgs::Header header
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
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)
An interface for the device drivers.
std::string decode(NetInt32 code)
Convert a vocabulary identifier into a string.
An interface to the operating system, including Port based communication.