|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
27 #define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR 1
28 #define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR 0
41 iRGBDSensor = interface;
42 ret = rgbParser.configure(interface);
43 ret &= depthParser.configure(interface);
49 bool ret = rgbParser.configure(rgbInterface);
50 ret &= depthParser.configure(depthInterface);
56 return fgCtrlParsers.configure(_fgCtrl);
70 ret = rgbParser.respond(cmd, response);
77 ret = depthParser.respond(cmd, response);
84 ret = fgCtrlParsers.respond(cmd, response);
99 ret = iRGBDSensor->getExtrinsicParam(params);
106 ret &= Property::copyPortable(params, params_b);
107 response.
append(params_b);
119 response.
addString(iRGBDSensor->getLastErrorMsg());
139 response.
addInt32(iRGBDSensor->getSensorStatus());
166 return DeviceResponder::respond(cmd,response);
186 isSubdeviceOwned(false),
187 subDeviceOwned(nullptr)
215 setId(
"RGBDSensorWrapper for " + depthFrame_StreamingPort_Name);
217 if(use_YARP && !initialize_YARP(config))
223 if(use_ROS && !initialize_ROS(config))
233 if(! openAndAttachSubDevice(config))
241 if(!openDeferredAttach(config))
250 if (!config.
check(
"period",
"refresh period of the broadcasted values in ms"))
273 if (!rosGroup.
check(
"use_ROS"))
281 if (confUseRos ==
"true" || confUseRos ==
"only")
284 use_YARP = confUseRos ==
"true" ? true :
false;
289 if (verbose >= 3 && confUseRos !=
"false")
300 std::vector<param<string> > rosStringParam;
310 for (i = 0; i < rosStringParam.size(); i++)
312 prm = &rosStringParam[i];
313 if (!rosGroup.
check(prm->parname))
325 if (rosGroup.
check(
"forceInfoSync"))
327 forceInfoSync = rosGroup.
find(
"forceInfoSync").
asBool();
333 std::string rootName;
334 rootName = config.
check(
"name",
Value(
"/"),
"starting '/' if needed.").asString();
336 if (!config.
check(
"name",
"Prefix name of the ports opened by the RGBD wrapper.")) {
343 rpcPort_Name = rootName +
"/rpc:i";
344 colorFrame_StreamingPort_Name = rootName +
"/rgbImage:o";
345 depthFrame_StreamingPort_Name = rootName +
"/depthImage:o";
348 if(config.
check(
"subdevice")) {
349 isSubdeviceOwned=
true;
351 isSubdeviceOwned=
false;
357 bool RGBDSensorWrapper::openDeferredAttach(
Searchable& prop)
360 isSubdeviceOwned =
false;
364 bool RGBDSensorWrapper::openAndAttachSubDevice(
Searchable& prop)
370 p.setMonitor(prop.getMonitor(),
"subdevice");
376 subDeviceOwned->
open(p);
378 if (!subDeviceOwned->
isValid())
383 isSubdeviceOwned =
true;
384 if(!
attach(subDeviceOwned)) {
401 delete subDeviceOwned;
402 subDeviceOwned=
nullptr;
406 isSubdeviceOwned =
false;
417 colorFrame_StreamingPort.
close();
418 depthFrame_StreamingPort.
close();
444 if(!rpcPort.
open(rpcPort_Name))
451 if(!colorFrame_StreamingPort.
open(colorFrame_StreamingPort_Name))
456 if(!depthFrame_StreamingPort.
open(depthFrame_StreamingPort_Name))
470 if (!rosPublisherPort_color.
topic(colorTopicName))
472 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << colorTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
475 if (!rosPublisherPort_depth.
topic(depthTopicName))
477 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << depthTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
480 if (!rosPublisherPort_colorCaminfo.
topic(cInfoTopicName))
482 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << cInfoTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
485 if (!rosPublisherPort_depthCaminfo.
topic(dInfoTopicName))
487 yCError(
RGBDSENSORWRAPPER) <<
"Unable to publish data on " << dInfoTopicName.c_str() <<
" topic, check your yarp-ROS network configuration";
512 if (device2attach.
size() != 1)
519 if(device2attach[0]->key ==
"IRGBDSensor")
528 if (!Idevice2attach->
isValid())
530 yCError(
RGBDSENSORWRAPPER) <<
"Device " << device2attach[0]->key <<
" to attach to is not valid ... cannot proceed";
534 Idevice2attach->
view(sensor_p);
535 Idevice2attach->
view(fgCtrl);
539 PeriodicThread::setPeriod(period);
540 return PeriodicThread::start();
549 if (isSubdeviceOwned)
578 PeriodicThread::setPeriod(period);
579 return PeriodicThread::start();
586 poly->
view(sensor_p);
590 if(sensor_p ==
nullptr)
607 PeriodicThread::setPeriod(period);
608 return PeriodicThread::start();
644 string distModel, currentSensor;
647 vector<param<double> > parVector;
651 currentSensor = sensorType == COLOR_SENSOR ?
"Rgb" :
"Depth";
660 if(!camData.
check(
"distortionModel"))
667 if (distModel !=
"plumb_bob")
676 parVector.emplace_back(phyF,
"physFocalLength");
677 parVector.emplace_back(fx,
"focalLengthX");
678 parVector.emplace_back(fy,
"focalLengthY");
679 parVector.emplace_back(cx,
"principalPointX");
680 parVector.emplace_back(cy,
"principalPointY");
681 parVector.emplace_back(k1,
"k1");
682 parVector.emplace_back(k2,
"k2");
683 parVector.emplace_back(t1,
"t1");
684 parVector.emplace_back(t2,
"t2");
685 parVector.emplace_back(k3,
"k3");
686 parVector.emplace_back(stamp,
"stamp");
687 for(i = 0; i < parVector.size(); i++)
691 if(!camData.
check(par->parname))
706 cameraInfo.
D.resize(5);
707 cameraInfo.
D[0] = k1;
708 cameraInfo.
D[1] = k2;
709 cameraInfo.
D[2] = t1;
710 cameraInfo.
D[3] = t2;
711 cameraInfo.
D[4] = k3;
713 cameraInfo.
K.resize(9);
714 cameraInfo.
K[0] = fx; cameraInfo.
K[1] = 0; cameraInfo.
K[2] = cx;
715 cameraInfo.
K[3] = 0; cameraInfo.
K[4] = fy; cameraInfo.
K[5] = cy;
716 cameraInfo.
K[6] = 0; cameraInfo.
K[7] = 0; cameraInfo.
K[8] = 1;
727 cameraInfo.
R.assign(9, 0);
728 cameraInfo.
R.at(0) = cameraInfo.
R.at(4) = cameraInfo.
R.at(8) = 1;
730 cameraInfo.
P.resize(12);
731 cameraInfo.
P[0] = fx; cameraInfo.
P[1] = 0; cameraInfo.
P[2] = cx; cameraInfo.
P[3] = 0;
732 cameraInfo.
P[4] = 0; cameraInfo.
P[5] = fy; cameraInfo.
P[6] = cy; cameraInfo.
P[7] = 0;
733 cameraInfo.
P[8] = 0; cameraInfo.
P[9] = 0; cameraInfo.
P[10] = 1; cameraInfo.
P[11] = 0;
741 bool RGBDSensorWrapper::writeData()
755 bool rgb_data_ok =
true;
756 bool depth_data_ok =
true;
758 if (((colorStamp.
getTime() - oldColorStamp.
getTime()) > 0) ==
false)
763 else { oldColorStamp = colorStamp; }
765 if (((depthStamp.
getTime() - oldDepthStamp.
getTime()) > 0) ==
false)
770 else { oldDepthStamp = depthStamp; }
781 colorFrame_StreamingPort.
write();
788 depthFrame_StreamingPort.
write();
801 rosPublisherPort_color.
write();
802 if (setCamInfo(camInfoC, rosFrameId, nodeSeq, COLOR_SENSOR))
806 rosPublisherPort_colorCaminfo.
setEnvelope(colorStamp);
807 rosPublisherPort_colorCaminfo.
write();
821 rosPublisherPort_depth.
write();
822 if (setCamInfo(camInfoD, rosFrameId, nodeSeq, DEPTH_SENSOR))
826 rosPublisherPort_depthCaminfo.
setEnvelope(depthStamp);
827 rosPublisherPort_depthCaminfo.
write();
842 if (sensor_p!=
nullptr)
846 switch (sensorStatus)
848 case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
856 case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
void close() override
Stop port activity.
A simple collection of objects that can be described and transmitted in a portable way.
int getRgbHeight() override=0
Return the height of each frame.
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
void setId(const std::string &id)
std::string toString() const override
Gives a human-readable textual representation of the bottle.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
void clear()
Empties the bottle of any objects it contains.
A base class for nested structures that can be searched.
const std::string depthInfoTopicName_param
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
constexpr yarp::conf::vocab32_t VOCAB_RGBD_PROTOCOL_VERSION
bool threadInit() override
Initialization method.
const std::string colorInfoTopicName_param
#define yCWarning(component,...)
const std::string frameId_param
#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR
constexpr yarp::conf::vocab32_t VOCAB_DEPTH_VISUAL_PARAMS
constexpr yarp::conf::vocab32_t VOCAB_FRAMEGRABBER_CONTROL
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.
bool isValid() const
Check if device is valid.
bool close() override
Close the DeviceDriver.
#define YARP_LOG_COMPONENT(name,...)
constexpr yarp::conf::vocab32_t VOCAB_STATUS
const std::string depthTopicName_param
constexpr yarp::conf::vocab32_t VOCAB_GET
constexpr yarp::conf::vocab32_t VOCAB_RGBD_SENSOR
bool attachAll(const yarp::dev::PolyDriverList &p) override
Specify which sensor this thread has to read from.
void interrupt() override
Interrupt any current reads or writes attached to the port.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool view(T *&x)
Get an interface to the device driver.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
~RGBDSensorWrapper() override
bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the depth camera.
bool open(const std::string &txt)
Construct and configure a device by its common name.
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool isRunning() const
Returns true when the thread is started, false otherwise.
bool configure(yarp::dev::IRGBDSensor *interface)
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
An interface for the device drivers.
yarp::rosmsg::std_msgs::Header header
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
std::string decode(NetInt32 code)
Convert a vocabulary identifier into a string.
constexpr yarp::conf::vocab32_t VOCAB_ERROR_MSG
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
yarp::rosmsg::sensor_msgs::RegionOfInterest roi
constexpr yarp::conf::vocab32_t VOCAB_SET
bool topic(const std::string &name)
Set topic to publish to.
const std::string nodeName_param
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Image class with user control of representation details.
const yarp::os::LogComponent & RGBDSENSORWRAPPER()
int getDepthHeight() override=0
Return the height of each frame.
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)
double getTime() const
Get the time stamp.
bool detachAll() override
Detach the object (you must have first called attach).
virtual bool asBool() const
Get boolean value.
virtual std::string asString() const
Get string value.
A container for a device driver.
constexpr yarp::conf::vocab32_t VOCAB_FAILED
yarp::rosmsg::std_msgs::Header header
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
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.
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
bool open(yarp::os::Searchable ¶ms) override
Device driver interface.
void threadRelease() override
Release method.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the rgb camera.
#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR
Control interface for frame grabber devices.
void addString(const char *str)
Places a string in the bottle, at the end of the list.
void setReader(PortReader &reader) override
Set an external reader for port data.
An abstraction for a periodic thread.
std::vector< yarp::conf::float64_t > P
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
std::vector< yarp::conf::float64_t > D
bool isNull() const override
Checks if the object is invalid.
virtual bool getImages(yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=NULL, yarp::os::Stamp *depthStamp=NULL)=0
Get the both the color and depth frame in a single call.
An abstraction for a time stamp and/or sequence number.
#define yCError(component,...)
constexpr yarp::conf::vocab32_t VOCAB_RGB_VISUAL_PARAMS
virtual std::int32_t asInt32() const
Get 32-bit integer value.
int getDepthWidth() override=0
Return the height of each frame.
An interface for retrieving intrinsic parameter from a rgb camera.
bool detach() override
Detach the object (you must have first called attach).
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
void run() override
Loop function.
std::vector< yarp::conf::float64_t > R
#define yCInfo(component,...)
An interface to the operating system, including Port based communication.
#define yCDebug(component,...)
#define DEFAULT_THREAD_PERIOD
void close() override
Stop port activity.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void interrupt()
interrupt delegates the call to the Node port interrupt.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
const std::string colorTopicName_param
#define yCTrace(component,...)
constexpr yarp::conf::vocab32_t VOCAB_IS
std::string distortion_model
int getRgbWidth() override=0
Return the width of each frame.
virtual RGBDSensor_status getSensorStatus()=0
Get the surrent status of the sensor, using enum type.
A single value (typically within a Bottle).
An interface for retrieving intrinsic parameter from a depth camera.
bool fromConfig(yarp::os::Searchable ¶ms)
constexpr yarp::conf::vocab32_t VOCAB_EXTRINSIC_PARAM
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.
void shallowCopyImages(const yarp::sig::FlexImage &src, yarp::sig::FlexImage &dest)
A class for storing options and configuration information.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
void append(const Bottle &alt)
Append the content of the given bottle to the current list.
std::vector< yarp::conf::float64_t > K