YARP
Yet Another Robot Platform
Rangefinder2D_nws_yarp.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_YARP_H
7 #define YARP_DEV_RANGEFINDER2D_NWS_YARP_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 #define DEFAULT_THREAD_PERIOD 0.02 //s
37 
69 {
70 public:
73 
74  bool open(yarp::os::Searchable &params) override;
75  bool close() override;
76 
78  bool attach(yarp::dev::PolyDriver* driver) override;
79  bool detach() override;
80 
81  bool threadInit() override;
82  void threadRelease() override;
83  void run() override;
84  bool read(yarp::os::ConnectionReader& connection) override;
85 
86 private:
87  //yarp streaming data
88  std::string streamingPortName;
89  std::string rpcPortName;
90  std::string frame_id;
91  yarp::os::Port rpcPort;
93 
94  //interfaces
95  yarp::dev::PolyDriver m_driver;
98 
99  //device data
100  yarp::os::Stamp lastStateStamp;
101  double _period;
102  double minAngle, maxAngle;
103  double minDistance, maxDistance;
104  double resolution;
105  bool isDeviceOwned;
106 
107  //private methods
108  bool initialize_YARP(yarp::os::Searchable &config);
109 };
110 
111 #endif //YARP_DEV_RANGEFINDER2D_NWS_YARP_H
contains the definition of a Vector type
rangefinder2D_nws_yarp: A Network grabber for 2D Rangefinder devices. This device will stream data on...
void run() override
Loop function.
void threadRelease() override
Release method.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
Rangefinder2D_nws_yarp()
It reads the data from a rangefinder sensor and sends them on one port.
bool detach() override
Detach the object (you must have first called attach).
void attach(yarp::dev::IRangefinder2D *s)
bool threadInit() override
Initialization method.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool close() override
Close the DeviceDriver.
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
An interface for reading from a network connection.
An abstraction for a periodic thread.
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
Definition: PortReader.h:25
A mini-server for network communication.
Definition: Port.h:47
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