22 PeriodicThread(s_default_period)
43 publisherPort_image.
close();
46 publisherPort_cameraInfo.
close();
48 if (node !=
nullptr) {
60 isSubdeviceOwned =
false;
69 yCError(FRAMEGRABBER_NWS_ROS,
"Device is already opened");
74 if (config.
check(
"period",
"refresh period(in s) of the broadcasted values through yarp ports") && config.
find(
"period").
isFloat64()) {
77 yCInfo(FRAMEGRABBER_NWS_ROS)
78 <<
"Period parameter not found, using default of"
82 PeriodicThread::setPeriod(m_period);
85 if (!config.
check(
"node_name"))
87 yCError(FRAMEGRABBER_NWS_ROS) <<
"Missing node_name parameter";
90 std::string nodeName = config.
find(
"node_name").
asString();
91 if (nodeName.c_str()[0] !=
'/') {
92 yCError(FRAMEGRABBER_NWS_ROS) <<
"Missing '/' in node_name parameter";
99 if (!config.
check(
"topic_name"))
101 yCError(FRAMEGRABBER_NWS_ROS) <<
"Missing topic_name parameter";
104 std::string topicName = config.
find(
"topic_name").
asString();
105 if (topicName.c_str()[0] !=
'/') {
106 yCError(FRAMEGRABBER_NWS_ROS) <<
"Missing '/' in topic_name parameter";
111 if (!publisherPort_image.
topic(topicName)) {
112 yCError(FRAMEGRABBER_NWS_ROS) <<
"Unable to publish data on " << topicName <<
" topic, check your yarp-ROS network configuration";
119 std::string cameraInfoTopicName = topicName.substr(0,topicName.rfind(
'/')) +
"/camera_info";
120 if (!publisherPort_cameraInfo.
topic(cameraInfoTopicName)) {
121 yCError(FRAMEGRABBER_NWS_ROS) <<
"Unable to publish data on" << cameraInfoTopicName <<
"topic, check your yarp-ROS network configuration";
126 if (!config.
check(
"frame_id"))
128 yCError(FRAMEGRABBER_NWS_ROS) <<
"Missing frame_id parameter";
134 isSubdeviceOwned = config.
check(
"subdevice");
135 if (isSubdeviceOwned) {
140 p.setMonitor(config.getMonitor(),
"subdevice");
148 yCError(FRAMEGRABBER_NWS_ROS,
"Unable to open subdevice");
152 yCError(FRAMEGRABBER_NWS_ROS,
"Unable to attach subdevice");
156 yCInfo(FRAMEGRABBER_NWS_ROS) <<
"Running, waiting for attach...";
167 yCError(FRAMEGRABBER_NWS_ROS) <<
"Device " << poly <<
" to attach to is not valid ... cannot proceed";
171 poly->
view(iRgbVisualParams);
172 poly->
view(iFrameGrabberImage);
173 poly->
view(iPreciselyTimed);
175 if (iFrameGrabberImage ==
nullptr) {
176 yCError(FRAMEGRABBER_NWS_ROS) <<
"IFrameGrabberImage interface is not available on the device";
180 if (iRgbVisualParams ==
nullptr) {
181 yCWarning(FRAMEGRABBER_NWS_ROS) <<
"IRgbVisualParams interface is not available on the device";
184 return PeriodicThread::start();
194 iRgbVisualParams =
nullptr;
195 iFrameGrabberImage =
nullptr;
196 iPreciselyTimed =
nullptr;
222 if (iPreciselyTimed) {
228 if (iFrameGrabberImage && publisherPort_image.
getOutputCount() > 0) {
230 auto& image = publisherPort_image.
prepare();
233 image.width = img->
width();
234 image.height = img->
height();
237 image.header.frame_id = m_frameId;
238 image.header.stamp = m_stamp.
getTime();
239 image.header.seq = m_stamp.
getCount();
240 image.is_bigendian = 0;
245 publisherPort_image.
write();
248 if (iRgbVisualParams && publisherPort_cameraInfo.
getOutputCount() > 0) {
249 auto& cameraInfo = publisherPort_cameraInfo.
prepare();
251 if (setCamInfo(cameraInfo)) {
253 publisherPort_cameraInfo.
write();
264 param(T& inVar, std::string inName) :
266 parname(std::move(inName))
276 yCAssert(FRAMEGRABBER_NWS_ROS, iRgbVisualParams);
280 yCErrorThreadOnce(FRAMEGRABBER_NWS_ROS) <<
"Unable to get intrinsic param from rgb sensor!";
284 if (!camData.
check(
"distortionModel")) {
285 yCWarning(FRAMEGRABBER_NWS_ROS) <<
"Missing distortion model";
289 std::string distModel = camData.
find(
"distortionModel").
asString();
290 if (distModel !=
"plumb_bob") {
291 yCError(FRAMEGRABBER_NWS_ROS) <<
"Distortion model not supported";
306 std::vector<param<double>> parVector;
307 parVector.emplace_back(phyF,
"physFocalLength");
308 parVector.emplace_back(fx,
"focalLengthX");
309 parVector.emplace_back(fy,
"focalLengthY");
310 parVector.emplace_back(cx,
"principalPointX");
311 parVector.emplace_back(cy,
"principalPointY");
312 parVector.emplace_back(k1,
"k1");
313 parVector.emplace_back(k2,
"k2");
314 parVector.emplace_back(t1,
"t1");
315 parVector.emplace_back(t2,
"t2");
316 parVector.emplace_back(k3,
"k3");
318 for(
auto& par : parVector) {
319 if(!camData.
check(par.parname)) {
320 yCWarning(FRAMEGRABBER_NWS_ROS) <<
"Driver has not the param:" << par.parname;
333 cameraInfo.
D.resize(5);
334 cameraInfo.
D[0] = k1;
335 cameraInfo.
D[1] = k2;
336 cameraInfo.
D[2] = t1;
337 cameraInfo.
D[3] = t2;
338 cameraInfo.
D[4] = k3;
340 cameraInfo.
K.resize(9);
341 cameraInfo.
K[0] = fx; cameraInfo.
K[1] = 0; cameraInfo.
K[2] = cx;
342 cameraInfo.
K[3] = 0; cameraInfo.
K[4] = fy; cameraInfo.
K[5] = cy;
343 cameraInfo.
K[6] = 0; cameraInfo.
K[7] = 0; cameraInfo.
K[8] = 1;
354 cameraInfo.
R.assign(9, 0);
355 cameraInfo.
R.at(0) = cameraInfo.
R.at(4) = cameraInfo.
R.at(8) = 1;
357 cameraInfo.
P.resize(12);
358 cameraInfo.
P[0] = fx; cameraInfo.
P[1] = 0; cameraInfo.
P[2] = cx; cameraInfo.
P[3] = 0;
359 cameraInfo.
P[4] = 0; cameraInfo.
P[5] = fy; cameraInfo.
P[6] = cy; cameraInfo.
P[7] = 0;
360 cameraInfo.
P[8] = 0; cameraInfo.
P[9] = 0; cameraInfo.
P[10] = 1; cameraInfo.
P[11] = 0;
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
void run() override
Loop function.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
bool close() override
Close the DeviceDriver.
~FrameGrabber_nws_ros() override
bool threadInit() override
Initialization method.
void threadRelease() override
Release method.
bool view(T *&x)
Get an interface to the device driver.
virtual bool getImage(ImageType &image)=0
Get an image from the frame grabber.
virtual yarp::os::Stamp getLastInputStamp()=0
Return the time stamp relative to the last acquisition.
virtual bool getRgbIntrinsicParam(yarp::os::Property &intrinsic)=0
Get the intrinsic parameters of the rgb camera.
virtual int getRgbHeight()=0
Return the height of each frame.
virtual int getRgbWidth()=0
Return the width of each frame.
A container for a device driver.
bool close() override
Close the DeviceDriver.
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.
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.
void close() override
Stop port activity.
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.
bool unprepare()
Give the last prepared object back to YARP without writing it.
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 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.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
double getTime() const
Get the time stamp.
int getCount() const
Get the sequence number.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
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
std::vector< std::uint8_t > data
int getPixelCode() const override
Gets pixel type identifier.
size_t width() const
Gets width of image in pixels.
size_t getRowSize() const
Size of the underlying image buffer rows.
unsigned char * getRawImage() const
Access to the internal image buffer.
size_t getRawImageSize() const
Access to the internal buffer size information (this is how much memory has been allocated for the im...
size_t height() const
Gets height of image in pixels.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCAssert(component, x)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
#define yCErrorThreadOnce(component,...)
std::string yarp2RosPixelCode(int code)
double now()
Return the current time in seconds, relative to an arbitrary starting point.