YARP
Yet Another Robot Platform
Rangefinder2D_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: LGPL-2.1-or-later
4  */
5 
6 #ifndef YARP_DEV_RANGEFINDER2D_NWS_ROS_H
7 #define YARP_DEV_RANGEFINDER2D_NWS_ROS_H
8 
9  //#include <list>
10 #include <vector>
11 #include <iostream>
12 #include <string>
13 #include <sstream>
14 
15 #include <yarp/os/Network.h>
16 #include <yarp/os/Port.h>
17 #include <yarp/os/BufferedPort.h>
18 #include <yarp/os/Bottle.h>
19 #include <yarp/os/Time.h>
20 #include <yarp/os/Property.h>
21 
22 #include <yarp/os/PeriodicThread.h>
23 #include <yarp/os/BufferedPort.h>
24 #include <yarp/os/Stamp.h>
25 
26 #include <yarp/sig/Vector.h>
27 
28 #include <yarp/dev/LaserScan2D.h>
30 #include <yarp/dev/PolyDriver.h>
31 #include <yarp/dev/DeviceDriver.h>
32 #include <yarp/dev/WrapperSingle.h>
33 #include <yarp/dev/api.h>
35 
36 // ROS state publisher
37 #include <yarp/os/Node.h>
38 #include <yarp/os/Publisher.h>
41 
42 
43 #define DEFAULT_THREAD_PERIOD 0.02 //s
44 
45 
80 {
81 public:
84 
85  bool open(yarp::os::Searchable &params) override;
86  bool close() override;
87 
89  bool attach(yarp::dev::PolyDriver* driver) override;
90  bool detach() override;
91 
92  bool threadInit() override;
93  void threadRelease() override;
94  void run() override;
95 
96 private:
97  // ROS streaming data
98  std::string frame_id; // name of the frame measures are referred to
99  std::string nodeName; // name of the rosNode
100  std::string topicName; // name of the rosTopic
101  yarp::os::Node* node; // add a ROS node
102  yarp::os::NetUint32 msgCounter; // incremental counter in the ROS message
103  yarp::os::Publisher<yarp::rosmsg::sensor_msgs::LaserScan> publisherPort; // Dedicated ROS topic publisher
104 
105 private:
106  //interfaces
107  yarp::dev::PolyDriver m_driver;
110 
111 private:
112  //device data
113  yarp::os::Stamp lastStateStamp;
114  double _period;
115  double minAngle, maxAngle;
116  double minDistance, maxDistance;
117  double resolution;
118  bool isDeviceOwned;
119 
120 private:
121  //private methods
122  bool checkROSParams(yarp::os::Searchable &config);
123  bool initialize_ROS();
124 };
125 
126 #endif //YARP_DEV_RANGEFINDER2D_NWS_ROS_H
contains the definition of a Vector type
rangefinder2D_nws_ros: A Network grabber for 2D Rangefinder devices. This device will publish data on...
bool close() override
Close the DeviceDriver.
Rangefinder2D_nws_ros()
It reads the data from a rangefinder sensor and sends them on one port.
void threadRelease() override
Release method.
bool detach() override
Detach the object (you must have first called attach).
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
void attach(yarp::dev::IRangefinder2D *s)
bool threadInit() override
Initialization method.
void run() override
Loop function.
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
A generic interface for planar laser range finders.
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
std::uint32_t NetUint32
Definition of the NetUint32 type.
Definition: NetUint32.h:30