6#ifndef YARP_ROS2_RANGEFINDER2D_NWS_ROS2_H
7#define YARP_ROS2_RANGEFINDER2D_NWS_ROS2_H
14#include <rclcpp/rclcpp.hpp>
15#include <std_msgs/msg/string.hpp>
16#include <sensor_msgs/msg/laser_scan.hpp>
45 bool attach(
yarp::dev::PolyDriver* driver) override;
49 bool open(
yarp::os::Searchable& config) override;
50 bool close() override;
56 yarp::dev::PolyDriver m_driver;
57 yarp::dev::IRangefinder2D *m_iDevice =
nullptr;
58 rclcpp::Node::SharedPtr m_node;
59 rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr m_publisher;
60 bool m_isDeviceOwned = false;
62 double m_minAngle, m_maxAngle;
63 double m_minDistance, m_maxDistance;
This class is the parameters parser for class Rangefinder2D_nws_ros2.
Rangefinder2D_nws_ros2: A Network grabber for 2D Rangefinder devices
bool close() override
Close the DeviceDriver.
void run() override
Loop function.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
Rangefinder2D_nws_ros2(Rangefinder2D_nws_ros2 &&) noexcept=delete
Rangefinder2D_nws_ros2(const Rangefinder2D_nws_ros2 &)=delete
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
Interface implemented by all device drivers.
Helper interface for an object that can wrap/or "attach" to a single other device.
An abstraction for a periodic thread.
The main, catch-all namespace for YARP.