YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Ros2Test.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_ROS2_ROS2TEST_H
7#define YARP_ROS2_ROS2TEST_H
8
11
12#include <rclcpp/rclcpp.hpp>
13#include <std_msgs/msg/string.hpp>
14
15#include <mutex>
16
18{
19public:
20 Ros2Init();
21
22 std::shared_ptr<rclcpp::Node> node;
23
24 static Ros2Init& get();
25};
26
27
37{
38public:
39 MinimalPublisher(const std::string& topicname);
40};
41
42
43class Ros2Test :
46{
47public:
48 Ros2Test();
49 Ros2Test(const Ros2Test&) = delete;
50 Ros2Test(Ros2Test&&) noexcept = delete;
51 Ros2Test& operator=(const Ros2Test&) = delete;
52 Ros2Test& operator=(Ros2Test&&) noexcept = delete;
53 ~Ros2Test() override = default;
54
55 // DeviceDriver
56 bool open(yarp::os::Searchable& config) override;
57 bool close() override;
58
59 // PeriodicThread
60 void run() override;
61
62private:
63 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr m_publisher;
64 std::string m_topic;
65 size_t m_count {0};
66};
67
68#endif // YARP_ROS2_ROS2TEST_H
ros2test: A Network publisher test
Definition Ros2Test.h:37
MinimalPublisher(const std::string &topicname)
std::shared_ptr< rclcpp::Node > node
Definition Ros2Test.h:22
static Ros2Init & get()
Definition Ros2Test.cpp:27
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Definition Ros2Test.cpp:39
bool close() override
Close the DeviceDriver.
Definition Ros2Test.cpp:51
Ros2Test(Ros2Test &&) noexcept=delete
void run() override
Loop function.
Definition Ros2Test.cpp:58
Ros2Test(const Ros2Test &)=delete
Interface implemented by all device drivers.
An abstraction for a periodic thread.
STL namespace.
The main, catch-all namespace for YARP.
Definition dirs.h:16