#include <vector>
#include <iostream>
#include <string>
#include <sstream>
#include <yarp/os/Network.h>
#include <yarp/os/Port.h>
#include <yarp/os/BufferedPort.h>
#include <yarp/os/Bottle.h>
#include <yarp/os/Time.h>
#include <yarp/os/Property.h>
#include <yarp/os/PeriodicThread.h>
#include <yarp/os/Stamp.h>
#include <yarp/sig/Vector.h>
#include <yarp/dev/LaserScan2D.h>
#include <yarp/dev/IRangefinder2D.h>
#include <yarp/dev/PolyDriver.h>
#include <yarp/dev/DeviceDriver.h>
#include <yarp/dev/WrapperSingle.h>
#include <yarp/dev/api.h>
#include <yarp/os/Node.h>
#include <yarp/os/Publisher.h>
#include <yarp/rosmsg/sensor_msgs/LaserScan.h>
#include <yarp/rosmsg/impl/yarpRosHelper.h>
Go to the source code of this file.
|
class | Rangefinder2D_nws_ros |
| rangefinder2D_nws_ros : A Network grabber for 2D Rangefinder devices. This device will publish data on the specified ROS topic. More...
|
|
◆ DEFAULT_THREAD_PERIOD
#define DEFAULT_THREAD_PERIOD 0.02 |