YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RGBDToPointCloudSensor_nws_ros Class Reference

RGBDToPointCloudSensor_nws_ros: A Network grabber for kinect-like devices. This device will produce one stream of data for the point cloud derived fron the combination of the data derived from Framegrabber and IDepthSensor interfaces. See they documentation for more details about each interface. More...

#include </home/runner/work/yarp-documentation/yarp-documentation/yarp/opt-modules/yarp-devices-ros/src/devices/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.h>

+ Inheritance diagram for RGBDToPointCloudSensor_nws_ros:

Public Member Functions

 RGBDToPointCloudSensor_nws_ros ()
 
 RGBDToPointCloudSensor_nws_ros (const RGBDToPointCloudSensor_nws_ros &)=delete
 
 RGBDToPointCloudSensor_nws_ros (RGBDToPointCloudSensor_nws_ros &&)=delete
 
RGBDToPointCloudSensor_nws_rosoperator= (const RGBDToPointCloudSensor_nws_ros &)=delete
 
RGBDToPointCloudSensor_nws_rosoperator= (RGBDToPointCloudSensor_nws_ros &&)=delete
 
 ~RGBDToPointCloudSensor_nws_ros () override
 
bool open (yarp::os::Searchable &params) override
 Device driver interface.
 
bool fromConfig (yarp::os::Searchable &params)
 
bool close () override
 Close the DeviceDriver.
 
bool attach (yarp::dev::PolyDriver *poly) override
 Specify which sensor this thread has to read from.
 
bool detach () override
 WrapperSingle interface.
 
bool threadInit () override
 Initialization method.
 
void threadRelease () override
 Release method.
 
void run () override
 Loop function.
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
 DeviceDriver ()
 
 DeviceDriver (const DeviceDriver &other)=delete
 
 DeviceDriver (DeviceDriver &&other) noexcept=delete
 
DeviceDriveroperator= (const DeviceDriver &other)=delete
 
DeviceDriveroperator= (DeviceDriver &&other) noexcept=delete
 
virtual ~DeviceDriver ()
 
virtual std::string id () const
 Return the id assigned to the PolyDriver.
 
virtual void setId (const std::string &id)
 Set the id for this device.
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver.
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others.
 
- Public Member Functions inherited from yarp::dev::WrapperSingle
 ~WrapperSingle () override
 Destructor.
 
bool attachAll (const yarp::dev::PolyDriverList &drivers) final
 Attach to a list of objects.
 
bool detachAll () final
 Detach the object (you must have first called attach).
 
- Public Member Functions inherited from yarp::dev::IWrapper
virtual ~IWrapper ()
 Destructor.
 
- Public Member Functions inherited from yarp::dev::IMultipleWrapper
virtual ~IMultipleWrapper ()
 Destructor.
 
- Public Member Functions inherited from yarp::os::PeriodicThread
 PeriodicThread (double period, ShouldUseSystemClock useSystemClock=ShouldUseSystemClock::No, PeriodicThreadClock clockAccuracy=PeriodicThreadClock::Relative)
 Constructor.
 
 PeriodicThread (double period, PeriodicThreadClock clockAccuracy)
 Constructor.
 
virtual ~PeriodicThread ()
 
bool start ()
 Call this to start the thread.
 
void step ()
 Call this to "step" the thread rather than starting it.
 
void stop ()
 Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() called).
 
void askToStop ()
 Stop the thread.
 
bool isRunning () const
 Returns true when the thread is started, false otherwise.
 
bool isSuspended () const
 Returns true when the thread is suspended, false otherwise.
 
bool setPeriod (double period)
 Set the (new) period of the thread.
 
double getPeriod () const
 Return the current period of the thread.
 
void suspend ()
 Suspend the thread, the thread keeps running by doLoop is never executed.
 
void resume ()
 Resume the thread if previously suspended.
 
void resetStat ()
 Reset thread statistics.
 
double getEstimatedPeriod () const
 Return estimated period since last reset.
 
void getEstimatedPeriod (double &av, double &std) const
 Return estimated period since last reset.
 
unsigned int getIterations () const
 Return the number of iterations performed since last reset.
 
double getEstimatedUsed () const
 Return the estimated duration of the run() function since last reset.
 
void getEstimatedUsed (double &av, double &std) const
 Return estimated duration of the run() function since last reset.
 
int setPriority (int priority, int policy=-1)
 Set the priority and scheduling policy of the thread, if the OS supports that.
 
int getPriority () const
 Query the current priority of the thread, if the OS supports that.
 
int getPolicy () const
 Query the current scheduling policy of the thread, if the OS supports that.
 

Additional Inherited Members

- Protected Member Functions inherited from yarp::os::PeriodicThread
virtual void beforeStart ()
 Called just before a new thread starts.
 
virtual void afterStart (bool success)
 Called just after a new thread starts (or fails to start), this is executed by the same thread that calls start().
 

Detailed Description

RGBDToPointCloudSensor_nws_ros: A Network grabber for kinect-like devices. This device will produce one stream of data for the point cloud derived fron the combination of the data derived from Framegrabber and IDepthSensor interfaces. See they documentation for more details about each interface.

Description of input parameters

Parameters required by this device are:

Parameter name SubParameter Type Units Default Value Required Description Notes
period - double s 0.033 No refresh period of the broadcasted values in s default 0.033 s
topic_name - string - Yes set the name for ROS point cloud topic must start with a leading '/'
frame_id - string - Yes set the name of the reference frame
node_name - string - - Yes set the name for ROS node must start with a leading '/'

ROS message type used is sensor_msgs/Image.msg ( http://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) Some example of configuration files:

Example of configuration file using .ini format.

device RGBDToPointCloudSensor_nws_ros
subdevice <RGBDsensor>
period 30
topic_name /camera/points
frame_id depth_center
node_name /<robotName>/RGBDToPointCloudSensorNode

Definition at line 75 of file RGBDToPointCloudSensor_nws_ros.h.

Constructor & Destructor Documentation

◆ RGBDToPointCloudSensor_nws_ros() [1/3]

RGBDToPointCloudSensor_nws_ros::RGBDToPointCloudSensor_nws_ros ( )

Definition at line 22 of file RGBDToPointCloudSensor_nws_ros.cpp.

◆ RGBDToPointCloudSensor_nws_ros() [2/3]

RGBDToPointCloudSensor_nws_ros::RGBDToPointCloudSensor_nws_ros ( const RGBDToPointCloudSensor_nws_ros )
delete

◆ RGBDToPointCloudSensor_nws_ros() [3/3]

RGBDToPointCloudSensor_nws_ros::RGBDToPointCloudSensor_nws_ros ( RGBDToPointCloudSensor_nws_ros &&  )
delete

◆ ~RGBDToPointCloudSensor_nws_ros()

RGBDToPointCloudSensor_nws_ros::~RGBDToPointCloudSensor_nws_ros ( )
override

Definition at line 29 of file RGBDToPointCloudSensor_nws_ros.cpp.

Member Function Documentation

◆ attach()

bool RGBDToPointCloudSensor_nws_ros::attach ( yarp::dev::PolyDriver poly)
overridevirtual

Specify which sensor this thread has to read from.

Implements yarp::dev::IWrapper.

Definition at line 111 of file RGBDToPointCloudSensor_nws_ros.cpp.

◆ close()

bool RGBDToPointCloudSensor_nws_ros::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 81 of file RGBDToPointCloudSensor_nws_ros.cpp.

◆ detach()

bool RGBDToPointCloudSensor_nws_ros::detach ( )
overridevirtual

WrapperSingle interface.

Implements yarp::dev::IWrapper.

Definition at line 100 of file RGBDToPointCloudSensor_nws_ros.cpp.

◆ fromConfig()

bool RGBDToPointCloudSensor_nws_ros::fromConfig ( yarp::os::Searchable params)

◆ open()

bool RGBDToPointCloudSensor_nws_ros::open ( yarp::os::Searchable params)
overridevirtual

Device driver interface.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 36 of file RGBDToPointCloudSensor_nws_ros.cpp.

◆ operator=() [1/2]

RGBDToPointCloudSensor_nws_ros & RGBDToPointCloudSensor_nws_ros::operator= ( const RGBDToPointCloudSensor_nws_ros )
delete

◆ operator=() [2/2]

RGBDToPointCloudSensor_nws_ros & RGBDToPointCloudSensor_nws_ros::operator= ( RGBDToPointCloudSensor_nws_ros &&  )
delete

◆ run()

void RGBDToPointCloudSensor_nws_ros::run ( )
overridevirtual

Loop function.

This is the thread itself. The thread calls the run() function every <period> ms. At the end of each run, the thread will sleep the amounth of time required, taking into account the time spent inside the loop function. Example: requested period is 10ms, the run() function take 3ms to be executed, the thread will sleep for 7ms.

Note: after each run is completed, the thread will call a yield() in order to facilitate other threads to run.

Implements yarp::os::PeriodicThread.

Definition at line 245 of file RGBDToPointCloudSensor_nws_ros.cpp.

◆ threadInit()

bool RGBDToPointCloudSensor_nws_ros::threadInit ( )
overridevirtual

Initialization method.

The thread executes this function when it starts and before "run". This is a good place to perform initialization tasks that need to be done by the thread itself (device drivers initialization, memory allocation etc). If the function returns false the thread quits and never calls "run". The return value of threadInit() is notified to the class and passed as a parameter to afterStart(). Note that afterStart() is called by the same thread that is executing the "start" method.

Reimplemented from yarp::os::PeriodicThread.

Definition at line 131 of file RGBDToPointCloudSensor_nws_ros.cpp.

◆ threadRelease()

void RGBDToPointCloudSensor_nws_ros::threadRelease ( )
overridevirtual

Release method.

The thread executes this function once when it exits, after the last "run". This is a good place to release resources that were initialized in threadInit() (release memory, and device driver resources).

Reimplemented from yarp::os::PeriodicThread.

Definition at line 137 of file RGBDToPointCloudSensor_nws_ros.cpp.


The documentation for this class was generated from the following files: