laserFromPointCloud
: Documentation to be added
More...
#include <laserFromPointCloud/laserFromPointCloud.h>
Public Member Functions | |
LaserFromPointCloud (double period=0.01) | |
~LaserFromPointCloud () | |
bool | open (yarp::os::Searchable &config) override |
Open the DeviceDriver. | |
bool | close () override |
Close the DeviceDriver. | |
bool | threadInit () override |
Initialization method. | |
void | threadRelease () override |
Release method. | |
void | run () override |
Loop function. | |
bool | setDistanceRange (double min, double max) override |
set the device detection range. | |
bool | setScanLimits (double min, double max) override |
set the scan angular range. | |
bool | setHorizontalResolution (double step) override |
get the angular step between two measurements (if available) | |
bool | setScanRate (double rate) override |
set the scan rate (scans per seconds) | |
bool | acquireDataFromHW () override final |
This method should be implemented by the user, and contain the logic to grab data from the hardware. | |
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. | |
Public Member Functions inherited from yarp::dev::Lidar2DDeviceBase | |
bool | parseConfiguration (yarp::os::Searchable &config) |
Lidar2DDeviceBase () | |
bool | getRawData (yarp::sig::Vector &data, double *timestamp=nullptr) override |
Get the device measurements. | |
bool | getLaserMeasurement (std::vector< yarp::sig::LaserMeasurementData > &data, double *timestamp=nullptr) override |
Get the device measurements. | |
bool | getDeviceStatus (Device_status &status) override |
get the device status | |
bool | getDeviceInfo (std::string &device_info) override |
get the device hardware characteristics | |
bool | getDistanceRange (double &min, double &max) override |
get the device detection range | |
bool | getScanLimits (double &min, double &max) override |
get the scan angular range. | |
bool | getHorizontalResolution (double &step) override |
get the angular step between two measurements. | |
bool | getScanRate (double &rate) override |
get the scan rate (scans per seconds) | |
Public Member Functions inherited from yarp::dev::IRangefinder2D | |
virtual | ~IRangefinder2D () |
Public Member Functions inherited from yarp::dev::DeviceDriver | |
DeviceDriver () | |
DeviceDriver (const DeviceDriver &other)=delete | |
DeviceDriver (DeviceDriver &&other) noexcept=delete | |
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
DeviceDriver & | operator= (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 DeviceDriver * | getImplementation () |
Some drivers are bureaucrats, pointing at others. | |
Additional Inherited Members | |
Public Types inherited from yarp::dev::IRangefinder2D | |
enum | Device_status { DEVICE_OK_STANDBY = 0 , DEVICE_OK_IN_USE = 1 , DEVICE_GENERAL_ERROR = 2 , DEVICE_TIMEOUT = 3 } |
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(). | |
Protected Member Functions inherited from yarp::dev::Lidar2DDeviceBase | |
virtual bool | updateLidarData () |
This utility method calls in sequence: grabDataFromHW(), updateTimestamp and applyLimitsOnLaserData(). | |
virtual bool | updateTimestamp () |
By default, it automatically updates the internal timestamp with the yarp time. | |
virtual bool | applyLimitsOnLaserData () |
Apply the limits on the internally stored lidar measurements. | |
laserFromPointCloud
: Documentation to be added
Definition at line 38 of file laserFromPointCloud.h.
|
inline |
Definition at line 67 of file laserFromPointCloud.h.
|
inline |
Definition at line 71 of file laserFromPointCloud.h.
|
finaloverridevirtual |
This method should be implemented by the user, and contain the logic to grab data from the hardware.
Implements yarp::dev::Lidar2DDeviceBase.
Definition at line 246 of file laserFromPointCloud.cpp.
|
overridevirtual |
Close the DeviceDriver.
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 177 of file laserFromPointCloud.cpp.
|
overridevirtual |
Open the DeviceDriver.
config | is a list of parameters for the device. Which parameters are effective for your device can vary. See device invocation examples. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device). |
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 54 of file laserFromPointCloud.cpp.
|
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 455 of file laserFromPointCloud.cpp.
set the device detection range.
Invalid setting will be discarded.
min | the minimum detection distance |
max | the maximum detection distance |
Implements yarp::dev::IRangefinder2D.
Definition at line 193 of file laserFromPointCloud.cpp.
get the angular step between two measurements (if available)
step | the angular step between two measurements |
Implements yarp::dev::IRangefinder2D.
Definition at line 209 of file laserFromPointCloud.cpp.
set the scan angular range.
min | start angle of the scan |
max | end angle of the scan |
Implements yarp::dev::IRangefinder2D.
Definition at line 202 of file laserFromPointCloud.cpp.
set the scan rate (scans per seconds)
rate | the scan rate |
Implements yarp::dev::IRangefinder2D.
Definition at line 216 of file laserFromPointCloud.cpp.
|
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 224 of file laserFromPointCloud.cpp.
|
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 462 of file laserFromPointCloud.cpp.
|
protected |
Definition at line 60 of file laserFromPointCloud.h.
|
protected |
Definition at line 62 of file laserFromPointCloud.h.
|
protected |
Definition at line 48 of file laserFromPointCloud.h.
|
protected |
Definition at line 51 of file laserFromPointCloud.h.
|
protected |
Definition at line 47 of file laserFromPointCloud.h.
|
protected |
Definition at line 61 of file laserFromPointCloud.h.
|
protected |
Definition at line 59 of file laserFromPointCloud.h.
|
protected |
Definition at line 50 of file laserFromPointCloud.h.
|
protected |
Definition at line 42 of file laserFromPointCloud.h.
|
protected |
Definition at line 45 of file laserFromPointCloud.h.
|
protected |
Definition at line 56 of file laserFromPointCloud.h.
|
protected |
Definition at line 54 of file laserFromPointCloud.h.
|
protected |
Definition at line 55 of file laserFromPointCloud.h.
|
protected |
Definition at line 63 of file laserFromPointCloud.h.
|
protected |
Definition at line 49 of file laserFromPointCloud.h.
|
protected |
Definition at line 41 of file laserFromPointCloud.h.
|
protected |
Definition at line 44 of file laserFromPointCloud.h.
|
protected |
Definition at line 64 of file laserFromPointCloud.h.