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>
18#include <yarp/os/Bottle.h>
19#include <yarp/os/Time.h>
20#include <yarp/os/Property.h>
21
24#include <yarp/os/Stamp.h>
25
26#include <yarp/sig/Vector.h>
27
30#include <yarp/dev/PolyDriver.h>
33#include <yarp/dev/api.h>
34
35#define DEFAULT_THREAD_PERIOD 0.02 //s
36
68{
69public:
72
73 bool open(yarp::os::Searchable &params) override;
74 bool close() override;
75
77 bool attach(yarp::dev::PolyDriver* driver) override;
78 bool detach() override;
79
80 bool threadInit() override;
81 void threadRelease() override;
82 void run() override;
83 bool read(yarp::os::ConnectionReader& connection) override;
84
85private:
86 //yarp streaming data
87 std::string streamingPortName;
88 std::string rpcPortName;
89 std::string frame_id;
90 yarp::os::Port rpcPort;
92
93 //interfaces
94 yarp::dev::PolyDriver m_driver;
96
97 //device data
98 yarp::os::Stamp lastStateStamp;
99 double _period;
100 double minAngle, maxAngle;
101 double minDistance, maxDistance;
102 double resolution;
103 bool isDeviceOwned;
104
105 //private methods
106 bool initialize_YARP(yarp::os::Searchable &config);
107};
108
109#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:30
A generic interface for planar laser range finders.
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.
Definition: WrapperSingle.h:31
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:24
A mini-server for network communication.
Definition: Port.h:46
A base class for nested structures that can be searched.
Definition: Searchable.h:63
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:21