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
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
23
24#include <rclcpp/rclcpp.hpp>
25#include <sensor_msgs/msg/image.hpp>
26#include <sensor_msgs/msg/camera_info.hpp>
27
41{
42private:
43 // Publishers
44 typedef rclcpp::Publisher<sensor_msgs::msg::Image> ImageTopicType;
45 typedef rclcpp::Publisher<sensor_msgs::msg::CameraInfo> CameraInfoTopicType;
46
47 ImageTopicType::SharedPtr publisher_image;
48 CameraInfoTopicType::SharedPtr publisher_cameraInfo;
49 rclcpp::Node::SharedPtr m_node;
50
51 // Interfaces handled
52 yarp::dev::IRgbVisualParams* iRgbVisualParams {nullptr};
53 yarp::dev::IFrameGrabberImage* iFrameGrabberImage {nullptr};
54 yarp::dev::IPreciselyTimed* iPreciselyTimed {nullptr};
55
56 // Images
58
59 // Internal state
60 bool m_active {false};
61 yarp::os::Stamp m_stamp;
62
63 // Options
64 static constexpr double s_default_period = 0.03; // seconds
65 double m_period {s_default_period};
66
67 bool setCamInfo(sensor_msgs::msg::CameraInfo& cameraInfo);
68
69public:
75 ~FrameGrabber_nws_ros2() override;
76
77 // DeviceDriver
78 bool close() override;
79 bool open(yarp::os::Searchable& config) override;
80
81 // IWrapper interface
82 bool attach(yarp::dev::PolyDriver* poly) override;
83 bool detach() override;
84
85 //RateThread
86 bool threadInit() override;
87 void threadRelease() override;
88 void run() override;
89};
90
91#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:605