YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Rangefinder2D_nws_ros.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 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>
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// ROS state publisher
36#include <yarp/os/Node.h>
37#include <yarp/os/Publisher.h>
40
41
42#define DEFAULT_THREAD_PERIOD 0.02 //s
43
44
78{
79public:
82
83 bool open(yarp::os::Searchable &params) override;
84 bool close() override;
85
87 bool attach(yarp::dev::PolyDriver* driver) override;
88 bool detach() override;
89
90 bool threadInit() override;
91 void threadRelease() override;
92 void run() override;
93
94private:
95 // ROS streaming data
96 std::string frame_id; // name of the frame measures are referred to
97 std::string nodeName; // name of the rosNode
98 std::string topicName; // name of the rosTopic
99 yarp::os::Node* node; // add a ROS node
100 yarp::os::NetUint32 msgCounter; // incremental counter in the ROS message
101 yarp::os::Publisher<yarp::rosmsg::sensor_msgs::LaserScan> publisherPort; // Dedicated ROS topic publisher
102
103private:
104 //interfaces
105 yarp::dev::PolyDriver m_driver;
107
108private:
109 //device data
110 yarp::os::Stamp lastStateStamp;
111 double _period;
112 double minAngle, maxAngle;
113 double minDistance, maxDistance;
114 double resolution;
115
116private:
117 //private methods
118 bool checkROSParams(yarp::os::Searchable &config);
119 bool initialize_ROS();
120};
121
122#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.
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.
A mini-server for performing network communication in the background.
The Node class.
Definition Node.h:23
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition Searchable.h:56
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
std::uint32_t NetUint32
Definition of the NetUint32 type.
Definition NetUint32.h:29