6#ifndef YARP_DEV_RGBDTOPOINTCLOUDSENSOR_NWS_ROS_H
7#define YARP_DEV_RGBDTOPOINTCLOUDSENSOR_NWS_ROS_H
32#include <yarp/rosmsg/TickTime.h>
33#include <yarp/rosmsg/sensor_msgs/PointCloud2.h>
84 typedef yarp::rosmsg::sensor_msgs::PointCloud2 PointCloud2Type;
85 typedef unsigned int UInt;
87 enum SensorType{COLOR_SENSOR, DEPTH_SENSOR};
92 param(T& inVar, std::string inName)
103 std::string nodeName;
104 std::string pointCloudTopicName;
116 std::string sensorId;
122 bool forceInfoSync =
true;
146 bool close()
override;
constexpr double DEFAULT_THREAD_PERIOD
contains the definition of a Vector type
RGBDToPointCloudSensor_nws_ros: A Network grabber for kinect-like devices. This device will produce o...
RGBDToPointCloudSensor_nws_ros(RGBDToPointCloudSensor_nws_ros &&)=delete
bool open(yarp::os::Searchable ¶ms) override
Device driver interface.
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
void threadRelease() override
Release method.
bool threadInit() override
Initialization method.
bool close() override
Close the DeviceDriver.
bool detach() override
WrapperSingle interface.
RGBDToPointCloudSensor_nws_ros & operator=(RGBDToPointCloudSensor_nws_ros &&)=delete
~RGBDToPointCloudSensor_nws_ros() override
RGBDToPointCloudSensor_nws_ros & operator=(const RGBDToPointCloudSensor_nws_ros &)=delete
RGBDToPointCloudSensor_nws_ros()
RGBDToPointCloudSensor_nws_ros(const RGBDToPointCloudSensor_nws_ros &)=delete
bool fromConfig(yarp::os::Searchable ¶ms)
void run() override
Loop function.
Interface implemented by all device drivers.
Control interface for frame grabber devices.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
A container for a device driver.
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.
An abstraction for a periodic thread.
A class for storing options and configuration information.
A base class for nested structures that can be searched.
An abstraction for a time stamp and/or sequence number.
Image class with user control of representation details.
const std::string frameId_param
const std::string pointCloudTopicName_param
const std::string nodeName_param