YARP
Yet Another Robot Platform
FrameGrabber_nws_ros.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 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>
11 #include <yarp/os/PeriodicThread.h>
12 #include <yarp/os/RpcServer.h>
13 #include <yarp/os/Stamp.h>
14 
15 #include <yarp/dev/DeviceDriver.h>
21 #include <yarp/dev/WrapperSingle.h>
22 
25 
47 {
48 private:
49  // Publishers
52 
53  yarp::os::Node* node {nullptr};
54  ImageTopicType publisherPort_image;
55  CameraInfoTopicType publisherPort_cameraInfo;
56 
57  // Subdevice
58  yarp::dev::PolyDriver* subdevice {nullptr};
59  bool isSubdeviceOwned {false};
60 
61  // Interfaces handled
62  yarp::dev::IRgbVisualParams* iRgbVisualParams {nullptr};
63  yarp::dev::IFrameGrabberImage* iFrameGrabberImage {nullptr};
64  yarp::dev::IPreciselyTimed* iPreciselyTimed {nullptr};
65 
66  // Images
68 
69  // Internal state
70  bool m_active {false};
71  yarp::os::Stamp m_stamp;
72  std::string m_frameId;
73 
74  // Options
75  static constexpr double s_default_period = 0.03; // seconds
76  double m_period {s_default_period};
77 
78  bool setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo);
79 
80 public:
86  ~FrameGrabber_nws_ros() override;
87 
88  // DeviceDriver
89  bool close() override;
90  bool open(yarp::os::Searchable& config) override;
91 
92  // IWrapper interface
93  bool attach(yarp::dev::PolyDriver* poly) override;
94  bool detach() override;
95 
96  //RateThread
97  bool threadInit() override;
98  void threadRelease() override;
99  void run() override;
100 };
101 
102 #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(FrameGrabber_nws_ros &&)=delete
FrameGrabber_nws_ros & operator=(const 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.
Definition: DeviceDriver.h:35
An interface for retrieving intrinsic parameter from a rgb camera.
A container for a device driver.
Definition: PolyDriver.h:24
Helper interface for an object that can wrap/or "attach" to a single other device.
Definition: WrapperSingle.h:32
The Node class.
Definition: Node.h:24
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition: Searchable.h:66
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22