YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
FrameGrabber_nws_ros2.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_FRAMEGRABBER_NWS_ROS2_H
7#define YARP_FRAMEGRABBER_NWS_ROS2_H
8
10#include <yarp/os/RpcServer.h>
11#include <yarp/os/Stamp.h>
12
21
22#include <rclcpp/rclcpp.hpp>
23#include <sensor_msgs/msg/image.hpp>
24#include <sensor_msgs/msg/camera_info.hpp>
25
39{
40private:
41 // Publishers
42 typedef rclcpp::Publisher<sensor_msgs::msg::Image> ImageTopicType;
43 typedef rclcpp::Publisher<sensor_msgs::msg::CameraInfo> CameraInfoTopicType;
44
45 ImageTopicType::SharedPtr publisher_image;
46 CameraInfoTopicType::SharedPtr publisher_cameraInfo;
47 rclcpp::Node::SharedPtr m_node;
48
49 // Interfaces handled
50 yarp::dev::IRgbVisualParams* iRgbVisualParams {nullptr};
51 yarp::dev::IFrameGrabberImage* iFrameGrabberImage {nullptr};
52 yarp::dev::IPreciselyTimed* iPreciselyTimed {nullptr};
53
54 // Images
56
57 // Internal state
58 bool m_active {false};
59 yarp::os::Stamp m_stamp;
60
61 // Options
62 static constexpr double s_default_period = 0.03; // seconds
63 double m_period {s_default_period};
64
65 bool setCamInfo(sensor_msgs::msg::CameraInfo& cameraInfo);
66
67public:
73 ~FrameGrabber_nws_ros2() override;
74
75 // DeviceDriver
76 bool close() override;
77 bool open(yarp::os::Searchable& config) override;
78
79 // IWrapper interface
80 bool attach(yarp::dev::PolyDriver* poly) override;
81 bool detach() override;
82
83 //RateThread
84 bool threadInit() override;
85 void threadRelease() override;
86 void run() override;
87};
88
89#endif // YARP_FRAMEGRABBER_NWS_ROS2_H
This class is the parameters parser for class FrameGrabber_nws_ros2.
FrameGrabber_nws_ros2: A Network grabber for camera devices.
void run() override
Loop function.
FrameGrabber_nws_ros2(FrameGrabber_nws_ros2 &&)=delete
bool threadInit() override
Initialization method.
bool detach() override
Detach the object (you must have first called attach).
void threadRelease() override
Release method.
FrameGrabber_nws_ros2(const FrameGrabber_nws_ros2 &)=delete
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
FrameGrabber_nws_ros2 & operator=(const FrameGrabber_nws_ros2 &)=delete
FrameGrabber_nws_ros2 & operator=(FrameGrabber_nws_ros2 &&)=delete
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
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.
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:603