YARP  2.3.70.1
Yet Another Robot Platform
yarp::dev::AnalogWrapper Class Reference

Device that expose an AnalogSensor (using the IAnalogSensor interface) on the YARP or ROS network. More...

#include <AnalogWrapper/AnalogWrapper.h>

+ Inheritance diagram for yarp::dev::AnalogWrapper:

Public Member Functions

 AnalogWrapper ()
 
YARP_DEPRECATED AnalogWrapper (const char *name, int rate=20)
 It reads the data from an analog sensor and sends them on one or more ports. More...
 
YARP_DEPRECATED AnalogWrapper (const std::vector< yarp::dev::impl::AnalogPortEntry > &_analogPorts, int rate=20)
 
 ~AnalogWrapper ()
 
bool open (yarp::os::Searchable &params) override
 Open the DeviceDriver. More...
 
bool close () override
 Close the DeviceDriver. More...
 
yarp::os::Bottle getOptions ()
 
void setId (const std::string &id)
 
std::string getId ()
 
bool attachAll (const PolyDriverList &p) override
 Specify which analog sensor this thread has to read from. More...
 
bool detachAll () override
 Detach the object (you must have first called attach). More...
 
void attach (yarp::dev::IAnalogSensor *s)
 
void detach ()
 
bool threadInit () override
 Initialization method. More...
 
void threadRelease () override
 Release method. More...
 
void run () override
 Loop function. More...
 
- Public Member Functions inherited from yarp::os::RateThread
 RateThread (int period)
 Constructor. More...
 
virtual ~RateThread ()
 
bool start ()
 Call this to start the thread. More...
 
bool step ()
 Call this to "step" the thread rather than starting it. More...
 
void stop ()
 Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() called). More...
 
void askToStop ()
 Stop the thread. More...
 
bool isRunning ()
 Returns true when the thread is started, false otherwise. More...
 
bool isSuspended ()
 Returns true when the thread is suspended, false otherwise. More...
 
bool setRate (int period)
 Set the (new) rate of the thread. More...
 
double getRate ()
 Return the current rate of the thread. More...
 
void suspend ()
 Suspend the thread, the thread keeps running by doLoop is never executed. More...
 
void resume ()
 Resume the thread if previously suspended. More...
 
void resetStat ()
 Reset thread statistics. More...
 
double getEstPeriod ()
 Return estimated period since last reset. More...
 
void getEstPeriod (double &av, double &std)
 Return estimated period since last reset. More...
 
unsigned int getIterations ()
 Return the number of iterations performed since last reset. More...
 
double getEstUsed ()
 Return the estimated duration of the run() function since last reset. More...
 
void getEstUsed (double &av, double &std)
 Return estimated duration of the run() function since last reset. More...
 
virtual void beforeStart ()
 Called just before a new thread starts. More...
 
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(). More...
 
int setPriority (int priority, int policy=-1)
 Set the priority and scheduling policy of the thread, if the OS supports that. More...
 
int getPriority ()
 Query the current priority of the thread, if the OS supports that. More...
 
int getPolicy ()
 Query the current scheduling policy of the thread, if the OS supports that. More...
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
virtual ~DeviceDriver ()
 Destructor. More...
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver. More...
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others. More...
 
- Public Member Functions inherited from yarp::os::IConfig
virtual ~IConfig ()
 Destructor. More...
 
virtual bool configure (Searchable &config)
 Change online parameters. More...
 
- Public Member Functions inherited from yarp::dev::IMultipleWrapper
virtual ~IMultipleWrapper ()
 Destructor. More...
 

Detailed Description

Device that expose an AnalogSensor (using the IAnalogSensor interface) on the YARP or ROS network.

Description of input parameters

It reads the data from an analog sensor and sends them on one or more ports. It creates one rpc port and its related handler for every output port..

Parameters required by this device are:

Parameter name SubParameter Type Units Default Value Required Description Notes
name - string - - Yes full name of the port opened by the device, like /robotName/part/ MUST start with a '/' character
period - int ms 20 No refresh period of the broadcasted values in ms optional, default 20ms
subdevice - string - - alternative to netwok group name of the subdevice to instantiate when used, parameters for the subdevice must be provided as well
ports - group - - alternative to subdevice this is expected to be a group parameter in xml format, a list in .ini file format. SubParameter are mandatory if this is used-
- portName_1 4 * int channel number - if ports is used describe how to match subdevice_1 channels with the wrapper channels. First 2 numbers indicate first/last wrapper channel, last 2 numbers are subdevice first/last channel The channels are intended to be consequent
- ... 4 * int channel number - if ports is used same as above The channels are intended to be consequent
- portName_n 4 * int channel number - if ports is used same as above The channels are intended to be consequent
- channels int - - if ports is used total number of channels handled by the wrapper MUST match the sum of channels from all the ports
ROS - group - - No Group containing parameter for ROS topic initialization if missing, it is assumed to not use ROS topics
- useROS string true/false/only- if ROS group is present set 'true' to have both yarp ports and ROS topic, set 'only' to have only ROS topic and no yarp port-
- ROS_topicName string - - if ROS group is present set the name for ROS topic must start with a leading '/'
- ROS_nodeName string - - if ROS group is present set the name for ROS node must start with a leading '/'
- channelNames string - - deprecated channels names are now got from attached motionControl device names order must match with the channel order, from 0 to N

ROS message type used for force/torque is geometry_msgs/WrenchedStamped.msg (http://docs.ros.org/indigo/api/geometry_msgs/html/msg/WrenchStamped.html)

Some example of configuration files:

Configuration file using .ini format, using subdevice keyword.

device analogServer
subdevice fakeAnalogSensor
name /myAnalogSensor
** parameter for 'fakeAnalogSensor' subdevice follows here **
...

Configuration file using .ini format, using ports keyword

device analogServer
name /myAnalogServer
period 20
ports (FirstSetOfChannels SecondSetOfChannels ThirdSetOfChannels)
channels 1344
FirstSetOfChannels 0 191 0 191
SecondSetOfChannels 192 575 0 383
ThirdSetOfChannels 576 1343 0 767

Configuration file using .xml format.

<device name="/myAnalogServer" type="analogServer">
<param name="period"> 20 </param>
<param name="channels"> 1344 </param>
<paramlist name="ports">
<elem name="FirstSetOfChannels"> 0 191 0 191</elem>
<elem name="SecondSetOfChannels"> 192 575 0 383</elem>
<elem name="ThirdSetOfChannels"> 576 1343 0 767</elem>
</paramlist>
<action phase="startup" level="5" type="attach">
<paramlist name="networks">
<!-- The param value must match the device name in the corresponding analogSensor config file.
AnalogWrapper is able to attach to only one subdevice. -->
<elem name="myAnalogSensor"> my_analog_sensor </elem>
</paramlist>
</action>
<action phase="shutdown" level="5" type="detach" />
</device>

Configuration for ROS topic using .ini format.

[ROS]
useROS true
ROS_topicName /left_arm/forceTorque
ROS_nodeName /torquePublisher
ROS_msgType geometry_msgs/WrenchedStamped
frame_id r_shoulder

Configuration for ROS topic using .xml format.

<group name="ROS">
<param name="useROS"> true </param> // use 'only' if you want only ROS topic and NOT yarp ports
<param name="ROS_topicName"> /left_arm/forceTorque </param>
<param name="ROS_nodeName"> /torquePublisher </param>
<param name="ROS_msgType"> geometry_msgs/WrenchedStamped </param>
<param name="frame_id"> r_shoulder </param>
</group>

Definition at line 169 of file AnalogWrapper.h.

Constructor & Destructor Documentation

◆ AnalogWrapper() [1/3]

AnalogWrapper::AnalogWrapper ( )

Definition at line 206 of file AnalogWrapper.cpp.

◆ AnalogWrapper() [2/3]

AnalogWrapper::AnalogWrapper ( const char *  name,
int  rate = 20 
)

It reads the data from an analog sensor and sends them on one or more ports.

Deprecated:
since YARP 2.3.70

It creates one rpc port and its related handler for every output port.

Definition at line 151 of file AnalogWrapper.cpp.

◆ AnalogWrapper() [3/3]

YARP_DEPRECATED yarp::dev::AnalogWrapper::AnalogWrapper ( const std::vector< yarp::dev::impl::AnalogPortEntry > &  _analogPorts,
int  rate = 20 
)
Deprecated:
since YARP 2.3.70

◆ ~AnalogWrapper()

AnalogWrapper::~AnalogWrapper ( )

Definition at line 223 of file AnalogWrapper.cpp.

Member Function Documentation

◆ attach()

void AnalogWrapper::attach ( yarp::dev::IAnalogSensor s)

Definition at line 354 of file AnalogWrapper.cpp.

◆ attachAll()

bool AnalogWrapper::attachAll ( const PolyDriverList p)
overridevirtual

Specify which analog sensor this thread has to read from.

Implements yarp::dev::IMultipleWrapper.

Definition at line 310 of file AnalogWrapper.cpp.

◆ close()

bool AnalogWrapper::close ( void  )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 897 of file AnalogWrapper.cpp.

◆ detach()

void AnalogWrapper::detach ( )

Definition at line 366 of file AnalogWrapper.cpp.

◆ detachAll()

bool AnalogWrapper::detachAll ( )
overridevirtual

Detach the object (you must have first called attach).

Returns
true/false on success failure.

Implements yarp::dev::IMultipleWrapper.

Definition at line 339 of file AnalogWrapper.cpp.

◆ getId()

std::string AnalogWrapper::getId ( )

Definition at line 395 of file AnalogWrapper.cpp.

◆ getOptions()

yarp::os::Bottle yarp::dev::AnalogWrapper::getOptions ( )

◆ open()

bool AnalogWrapper::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 606 of file AnalogWrapper.cpp.

◆ run()

void AnalogWrapper::run ( )
overridevirtual

Loop function.

This is the thread itself.

Implements yarp::os::RateThread.

Definition at line 786 of file AnalogWrapper.cpp.

◆ setId()

void AnalogWrapper::setId ( const std::string &  id)

Definition at line 390 of file AnalogWrapper.cpp.

◆ threadInit()

bool AnalogWrapper::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::RateThread.

Definition at line 376 of file AnalogWrapper.cpp.

◆ threadRelease()

void AnalogWrapper::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::RateThread.

Definition at line 777 of file AnalogWrapper.cpp.


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