YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches

Rangefinder2D_nwc_yarp: The client side of any ILaserRangefinder2D capable device. More...

#include <networkWrappers/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.h>

+ Inheritance diagram for Rangefinder2D_nwc_yarp:

Public Member Functions

bool open (yarp::os::Searchable &config) override
 Open the DeviceDriver.
 
bool close () override
 Close the DeviceDriver.
 
yarp::dev::ReturnValue getLaserMeasurement (std::vector< yarp::sig::LaserMeasurementData > &data, double *timestamp=nullptr) override
 Get the device measurements.
 
yarp::dev::ReturnValue getRawData (yarp::sig::Vector &data, double *timestamp=nullptr) override
 Get the device measurements.
 
yarp::dev::ReturnValue getDeviceStatus (Device_status &status) override
 get the device status
 
yarp::dev::ReturnValue getDistanceRange (double &min, double &max) override
 get the device detection range
 
yarp::dev::ReturnValue setDistanceRange (double min, double max) override
 set the device detection range.
 
yarp::dev::ReturnValue getScanLimits (double &min, double &max) override
 get the scan angular range.
 
yarp::dev::ReturnValue setScanLimits (double min, double max) override
 set the scan angular range.
 
yarp::dev::ReturnValue getHorizontalResolution (double &step) override
 get the angular step between two measurements.
 
yarp::dev::ReturnValue setHorizontalResolution (double step) override
 get the angular step between two measurements (if available)
 
yarp::dev::ReturnValue getScanRate (double &rate) override
 get the scan rate (scans per seconds)
 
yarp::dev::ReturnValue setScanRate (double rate) override
 set the scan rate (scans per seconds)
 
yarp::dev::ReturnValue getDeviceInfo (std::string &device_info) override
 get the device hardware characteristics
 
- 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::IRangefinder2D
virtual ~IRangefinder2D ()
 
- Public Member Functions inherited from Rangefinder2D_nwc_yarp_ParamsParser
 Rangefinder2D_nwc_yarp_ParamsParser ()
 
 ~Rangefinder2D_nwc_yarp_ParamsParser () override=default
 
bool parseParams (const yarp::os::Searchable &config) override
 Parse the DeviceDriver parameters.
 
std::string getDeviceClassName () const override
 Get the name of the DeviceDriver class.
 
std::string getDeviceName () const override
 Get the name of the device (i.e.
 
std::string getDocumentationOfDeviceParams () const override
 Get the documentation of the DeviceDriver's parameters.
 
std::vector< std::string > getListOfParams () const override
 Return a list of all params used by the device.
 
- Public Member Functions inherited from yarp::dev::IDeviceDriverParams
virtual ~IDeviceDriverParams ()
 

Protected Attributes

Rangefinder2D_InputPortProcessor m_inputPort
 
IRangefinder2DMsgs m_RPC
 
std::mutex m_mutex
 
yarp::os::Port m_rpcPort
 
yarp::os::Stamp m_lastTs
 
std::string m_deviceId
 
double m_scan_angle_min = std::nan("1")
 
double m_scan_angle_max = std::nan("1")
 
std::string m_laser_frame_name
 
std::string m_robot_frame_name
 

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
}
 
- Public Attributes inherited from Rangefinder2D_nwc_yarp_ParamsParser
const std::string m_device_classname = {"Rangefinder2D_nwc_yarp"}
 
const std::string m_device_name = {"rangefinder2D_nwc_yarp"}
 
bool m_parser_is_strict = false
 
const parser_version_type m_parser_version = {}
 
const std::string m_local_defaultValue = {""}
 
const std::string m_remote_defaultValue = {""}
 
const std::string m_carrier_defaultValue = {"tcp"}
 
std::string m_local = {}
 
std::string m_remote = {}
 
std::string m_carrier = {"tcp"}
 

Detailed Description

Rangefinder2D_nwc_yarp: The client side of any ILaserRangefinder2D capable device.

Parameters required by this device are shown in class: Rangefinder2D_nwc_yarp_ParamsParser

Definition at line 69 of file Rangefinder2D_nwc_yarp.h.

Member Function Documentation

◆ close()

bool Rangefinder2D_nwc_yarp::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 205 of file Rangefinder2D_nwc_yarp.cpp.

◆ getDeviceInfo()

ReturnValue Rangefinder2D_nwc_yarp::getDeviceInfo ( std::string &  device_info)
overridevirtual

get the device hardware characteristics

Parameters
device_infostring containing the device infos
Returns
true/false.

Implements yarp::dev::IRangefinder2D.

Definition at line 357 of file Rangefinder2D_nwc_yarp.cpp.

◆ getDeviceStatus()

ReturnValue Rangefinder2D_nwc_yarp::getDeviceStatus ( Device_status status)
overridevirtual

get the device status

Parameters
statusthe device status
Returns
true/false.

Implements yarp::dev::IRangefinder2D.

Definition at line 350 of file Rangefinder2D_nwc_yarp.cpp.

◆ getDistanceRange()

ReturnValue Rangefinder2D_nwc_yarp::getDistanceRange ( double min,
double max 
)
overridevirtual

get the device detection range

Parameters
minthe minimum detection distance
maxthe maximum detection distance
Returns
true/false.

Implements yarp::dev::IRangefinder2D.

Definition at line 255 of file Rangefinder2D_nwc_yarp.cpp.

◆ getHorizontalResolution()

ReturnValue Rangefinder2D_nwc_yarp::getHorizontalResolution ( double step)
overridevirtual

get the angular step between two measurements.

Parameters
stepthe angular step between two measurements
Returns
true/false.

Implements yarp::dev::IRangefinder2D.

Definition at line 304 of file Rangefinder2D_nwc_yarp.cpp.

◆ getLaserMeasurement()

ReturnValue Rangefinder2D_nwc_yarp::getLaserMeasurement ( std::vector< yarp::sig::LaserMeasurementData > &  data,
double timestamp = nullptr 
)
overridevirtual

Get the device measurements.

Parameters
dataa vector containing the measurement data, expressed in Cartesian/polar format
timestampthe timestamp of the retrieved data.
Returns
true/false

Implements yarp::dev::IRangefinder2D.

Definition at line 228 of file Rangefinder2D_nwc_yarp.cpp.

◆ getRawData()

ReturnValue Rangefinder2D_nwc_yarp::getRawData ( yarp::sig::Vector data,
double timestamp = nullptr 
)
overridevirtual

Get the device measurements.

Parameters
rangesthe vector containing the raw measurement data, as acquired by the device.
timestampthe timestamp of the retrieved data.
Returns
true/false.

Implements yarp::dev::IRangefinder2D.

Definition at line 213 of file Rangefinder2D_nwc_yarp.cpp.

◆ getScanLimits()

ReturnValue Rangefinder2D_nwc_yarp::getScanLimits ( double min,
double max 
)
overridevirtual

get the scan angular range.

Parameters
minstart angle of the scan
maxend angle of the scan
Returns
true/false.

Implements yarp::dev::IRangefinder2D.

Definition at line 280 of file Rangefinder2D_nwc_yarp.cpp.

◆ getScanRate()

ReturnValue Rangefinder2D_nwc_yarp::getScanRate ( double rate)
overridevirtual

get the scan rate (scans per seconds)

Parameters
ratethe scan rate
Returns
true/false.

Implements yarp::dev::IRangefinder2D.

Definition at line 327 of file Rangefinder2D_nwc_yarp.cpp.

◆ open()

bool Rangefinder2D_nwc_yarp::open ( yarp::os::Searchable config)
overridevirtual

Open the DeviceDriver.

Parameters
configis 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).
Returns
true/false upon success/failure

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 155 of file Rangefinder2D_nwc_yarp.cpp.

◆ setDistanceRange()

ReturnValue Rangefinder2D_nwc_yarp::setDistanceRange ( double  min,
double  max 
)
overridevirtual

set the device detection range.

Invalid setting will be discarded.

Parameters
minthe minimum detection distance
maxthe maximum detection distance
Returns
true/false on success/failure.

Implements yarp::dev::IRangefinder2D.

Definition at line 268 of file Rangefinder2D_nwc_yarp.cpp.

◆ setHorizontalResolution()

ReturnValue Rangefinder2D_nwc_yarp::setHorizontalResolution ( double  step)
overridevirtual

get the angular step between two measurements (if available)

Parameters
stepthe angular step between two measurements
Returns
true/false on success/failure.

Implements yarp::dev::IRangefinder2D.

Definition at line 316 of file Rangefinder2D_nwc_yarp.cpp.

◆ setScanLimits()

ReturnValue Rangefinder2D_nwc_yarp::setScanLimits ( double  min,
double  max 
)
overridevirtual

set the scan angular range.

Parameters
minstart angle of the scan
maxend angle of the scan
Returns
true/false on success/failure.

Implements yarp::dev::IRangefinder2D.

Definition at line 293 of file Rangefinder2D_nwc_yarp.cpp.

◆ setScanRate()

ReturnValue Rangefinder2D_nwc_yarp::setScanRate ( double  rate)
overridevirtual

set the scan rate (scans per seconds)

Parameters
ratethe scan rate
Returns
true/false on success/failure.

Implements yarp::dev::IRangefinder2D.

Definition at line 339 of file Rangefinder2D_nwc_yarp.cpp.

Member Data Documentation

◆ m_deviceId

std::string Rangefinder2D_nwc_yarp::m_deviceId
protected

Definition at line 81 of file Rangefinder2D_nwc_yarp.h.

◆ m_inputPort

Rangefinder2D_InputPortProcessor Rangefinder2D_nwc_yarp::m_inputPort
protected

Definition at line 75 of file Rangefinder2D_nwc_yarp.h.

◆ m_laser_frame_name

std::string Rangefinder2D_nwc_yarp::m_laser_frame_name
protected

Definition at line 85 of file Rangefinder2D_nwc_yarp.h.

◆ m_lastTs

yarp::os::Stamp Rangefinder2D_nwc_yarp::m_lastTs
protected

Definition at line 80 of file Rangefinder2D_nwc_yarp.h.

◆ m_mutex

std::mutex Rangefinder2D_nwc_yarp::m_mutex
protected

Definition at line 77 of file Rangefinder2D_nwc_yarp.h.

◆ m_robot_frame_name

std::string Rangefinder2D_nwc_yarp::m_robot_frame_name
protected

Definition at line 86 of file Rangefinder2D_nwc_yarp.h.

◆ m_RPC

IRangefinder2DMsgs Rangefinder2D_nwc_yarp::m_RPC
protected

Definition at line 76 of file Rangefinder2D_nwc_yarp.h.

◆ m_rpcPort

yarp::os::Port Rangefinder2D_nwc_yarp::m_rpcPort
protected

Definition at line 79 of file Rangefinder2D_nwc_yarp.h.

◆ m_scan_angle_max

double Rangefinder2D_nwc_yarp::m_scan_angle_max = std::nan("1")
protected

Definition at line 84 of file Rangefinder2D_nwc_yarp.h.

◆ m_scan_angle_min

double Rangefinder2D_nwc_yarp::m_scan_angle_min = std::nan("1")
protected

Definition at line 83 of file Rangefinder2D_nwc_yarp.h.


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