37 isSubdeviceOwned(false),
38 subDeviceOwned(
nullptr)
56 if (!config.
check(
"period",
"refresh period of the broadcasted values in s"))
69 if (config.
check(
"forceInfoSync"))
71 forceInfoSync = config.
find(
"forceInfoSync").
asBool();
74 if(config.
check(
"subdevice")) {
75 isSubdeviceOwned=
true;
77 isSubdeviceOwned=
false;
80 if(!initialize_ROS(config))
89 if(! openAndAttachSubDevice(config))
97 if (!openDeferredAttach(config)) {
105bool RgbdSensor_nws_ros::openDeferredAttach(
Searchable& prop)
108 isSubdeviceOwned =
false;
112bool RgbdSensor_nws_ros::openAndAttachSubDevice(
Searchable& prop)
118 p.setMonitor(prop.getMonitor(),
"subdevice");
124 subDeviceOwned->
open(p);
126 if (!subDeviceOwned->
isValid())
131 isSubdeviceOwned =
true;
132 if(!
attach(subDeviceOwned)) {
149 delete subDeviceOwned;
150 subDeviceOwned=
nullptr;
154 isSubdeviceOwned =
false;
172 if (!params.
check(
"depth_topic_name")) {
176 std::string depth_topic_name = params.
find(
"depth_topic_name").
asString();
177 if(depth_topic_name[0] !=
'/'){
183 if (!params.
check(
"color_topic_name")) {
187 std::string color_topic_name = params.
find(
"color_topic_name").
asString();
188 if(color_topic_name[0] !=
'/'){
194 if (!params.
check(
"node_name")) {
198 std::string node_name = params.
find(
"node_name").
asString();
199 if(node_name[0] !=
'/'){
205 if (!params.
check(
"depth_frame_id")) {
209 m_depth_frame_id = params.
find(
"depth_frame_id").
asString();
212 if (!params.
check(
"color_frame_id")) {
216 m_color_frame_id = params.
find(
"color_frame_id").
asString();
222 if (!publisherPort_color.
topic(color_topic_name))
224 yCError(
RGBDSENSORNWSROS) <<
"Unable to publish data on " << color_topic_name.c_str() <<
" topic, check your yarp-ROS network configuration";
228 if (!publisherPort_depth.
topic(depth_topic_name))
230 yCError(
RGBDSENSORNWSROS) <<
"Unable to publish data on " << depth_topic_name.c_str() <<
" topic, check your yarp-ROS network configuration";
233 std::string rgb_info_topic_name = color_topic_name.substr(0,color_topic_name.rfind(
'/')) +
"/camera_info";
234 if (!publisherPort_colorCaminfo.
topic(rgb_info_topic_name))
236 yCError(
RGBDSENSORNWSROS) <<
"Unable to publish data on " << rgb_info_topic_name.c_str() <<
" topic, check your yarp-ROS network configuration";
240 std::string depth_info_topic_name = depth_topic_name.substr(0,depth_topic_name.rfind(
'/')) +
"/camera_info";
241 if (!publisherPort_depthCaminfo.
topic(depth_info_topic_name))
243 yCError(
RGBDSENSORNWSROS) <<
"Unable to publish data on " << depth_info_topic_name.c_str() <<
" topic, check your yarp-ROS network configuration";
260 if (isSubdeviceOwned) {
272 poly->
view(sensor_p);
276 if(sensor_p ==
nullptr)
282 if(fgCtrl ==
nullptr)
287 PeriodicThread::setPeriod(period);
288 return PeriodicThread::start();
318 std::string distModel;
319 std::string currentSensor;
322 std::vector<param<double> > parVector;
326 currentSensor = sensorType == COLOR_SENSOR ?
"Rgb" :
"Depth";
335 if(!camData.
check(
"distortionModel"))
342 if (distModel !=
"plumb_bob")
351 parVector.emplace_back(phyF,
"physFocalLength");
352 parVector.emplace_back(fx,
"focalLengthX");
353 parVector.emplace_back(fy,
"focalLengthY");
354 parVector.emplace_back(cx,
"principalPointX");
355 parVector.emplace_back(cy,
"principalPointY");
356 parVector.emplace_back(k1,
"k1");
357 parVector.emplace_back(k2,
"k2");
358 parVector.emplace_back(t1,
"t1");
359 parVector.emplace_back(t2,
"t2");
360 parVector.emplace_back(k3,
"k3");
361 parVector.emplace_back(stamp,
"stamp");
362 for(i = 0; i < parVector.size(); i++)
366 if(!camData.
check(par->parname))
374 cameraInfo.header.frame_id = frame_id;
375 cameraInfo.header.seq = seq;
376 cameraInfo.header.stamp = stamp;
379 cameraInfo.distortion_model = distModel;
381 cameraInfo.D.resize(5);
382 cameraInfo.D[0] = k1;
383 cameraInfo.D[1] = k2;
384 cameraInfo.D[2] = t1;
385 cameraInfo.D[3] = t2;
386 cameraInfo.D[4] = k3;
388 cameraInfo.K.resize(9);
389 cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx;
390 cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy;
391 cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1;
402 cameraInfo.R.assign(9, 0);
403 cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1;
405 cameraInfo.P.resize(12);
406 cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0;
407 cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0;
408 cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0;
410 cameraInfo.binning_x = cameraInfo.binning_y = 0;
411 cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0;
412 cameraInfo.roi.do_rectify =
false;
416bool RgbdSensor_nws_ros::writeData()
430 bool rgb_data_ok =
true;
431 bool depth_data_ok =
true;
433 if (((colorStamp.
getTime() - oldColorStamp.
getTime()) > 0) ==
false)
438 else { oldColorStamp = colorStamp; }
440 if (((depthStamp.
getTime() - oldDepthStamp.
getTime()) > 0) ==
false)
445 else { oldDepthStamp = depthStamp; }
455 publisherPort_color.
write();
456 if (setCamInfo(camInfoC, m_color_frame_id, nodeSeq, COLOR_SENSOR))
459 {camInfoC.header.stamp = rColorImage.header.stamp;}
460 publisherPort_colorCaminfo.
setEnvelope(colorStamp);
461 publisherPort_colorCaminfo.
write();
475 publisherPort_depth.
write();
476 if (setCamInfo(camInfoD, m_depth_frame_id, nodeSeq, DEPTH_SENSOR))
479 {camInfoD.header.stamp = rDepthImage.header.stamp;}
480 publisherPort_depthCaminfo.
setEnvelope(depthStamp);
481 publisherPort_depthCaminfo.
write();
496 if (sensor_p!=
nullptr)
500 switch (sensorStatus)
502 case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
510 case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
constexpr double DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & RGBDSENSORNWSROS()
rgbdSensor_nws_ros: A Network grabber for kinect-like devices. This device will produce two streams o...
~RgbdSensor_nws_ros() override
bool close() override
Close the DeviceDriver.
void threadRelease() override
Release method.
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
bool open(yarp::os::Searchable ¶ms) override
Device driver interface.
bool threadInit() override
Initialization method.
void run() override
Loop function.
bool detach() override
WrapperSingle interface.
bool view(T *&x)
Get an interface to the device driver.
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.
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.
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...
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.
An abstraction for a time stamp and/or sequence number.
double getTime() const
Get the time stamp.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool asBool() const
Get boolean value.
virtual std::string asString() const
Get string value.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
yarp::rosmsg::sensor_msgs::Image Image
yarp::rosmsg::sensor_msgs::CameraInfo CameraInfo
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.
An interface to the operating system, including Port based communication.