YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
FrameGrabber_nws_ros.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_FRAMEGRABBER_NWS_ROS_H
7#define YARP_FRAMEGRABBER_NWS_ROS_H
8
9#include <yarp/os/Node.h>
10#include <yarp/os/Publisher.h>
12#include <yarp/os/RpcServer.h>
13#include <yarp/os/Stamp.h>
14
22
23#include <yarp/rosmsg/sensor_msgs/CameraInfo.h>
24#include <yarp/rosmsg/sensor_msgs/Image.h>
25
46{
47private:
48 // Publishers
51
52 yarp::os::Node* node {nullptr};
53 ImageTopicType publisherPort_image;
54 CameraInfoTopicType publisherPort_cameraInfo;
55
56 // Interfaces handled
57 yarp::dev::IRgbVisualParams* iRgbVisualParams {nullptr};
58 yarp::dev::IFrameGrabberImage* iFrameGrabberImage {nullptr};
59 yarp::dev::IPreciselyTimed* iPreciselyTimed {nullptr};
60
61 // Images
63
64 // Internal state
65 bool m_active {false};
66 yarp::os::Stamp m_stamp;
67 std::string m_frameId;
68
69 // Options
70 static constexpr double s_default_period = 0.03; // seconds
71 double m_period {s_default_period};
72
73 bool setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo);
74
75public:
81 ~FrameGrabber_nws_ros() override;
82
83 // DeviceDriver
84 bool close() override;
85 bool open(yarp::os::Searchable& config) override;
86
87 // IWrapper interface
88 bool attach(yarp::dev::PolyDriver* poly) override;
89 bool detach() override;
90
91 //RateThread
92 bool threadInit() override;
93 void threadRelease() override;
94 void run() override;
95};
96
97#endif // YARP_FRAMEGRABBER_NWS_ROS_H
frameGrabber_nws_ros: A ROS NWS for camera devices. Parameters required by this device are:
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
void run() override
Loop function.
FrameGrabber_nws_ros & operator=(const FrameGrabber_nws_ros &)=delete
FrameGrabber_nws_ros(FrameGrabber_nws_ros &&)=delete
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 & operator=(FrameGrabber_nws_ros &&)=delete
bool threadInit() override
Initialization method.
void threadRelease() override
Release method.
FrameGrabber_nws_ros(const FrameGrabber_nws_ros &)=delete
Interface implemented by all device drivers.
An interface for retrieving intrinsic parameter from a rgb camera.
A container for a device driver.
Definition PolyDriver.h:23
Helper interface for an object that can wrap/or "attach" to a single other device.
A mini-server for performing network communication in the background.
The Node class.
Definition Node.h:23
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition Searchable.h:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
Typed image class.
Definition Image.h:605