rec::robotino::api2 C++ interface
Public Member Functions | Friends | List of all members
rec::robotino::api2::CompactBHA Class Reference

Access to Robotino's (optional) compact version of the Bionic Handling Assistant. See Robotino XT. More...

#include <CompactBHA.h>

Inheritance diagram for rec::robotino::api2::CompactBHA:
rec::robotino::api2::ComObject

Public Member Functions

void setComId (const ComId &id)
 
void setPressures (const float *pressures)
 
void setCompressorsEnabled (bool enabled)
 
void setWaterDrainValve (bool open)
 
void setGripperValve1 (bool open)
 
void setGripperValve2 (bool open)
 
void pressures (float *readings) const
 
bool pressureSensor () const
 
void stringPots (float *readings) const
 
float foilPot () const
 
virtual void pressuresChangedEvent (const float *pressures, unsigned int size)
 
virtual void pressureSensorChangedEvent (bool pressureSensor)
 
virtual void stringPotsChangedEvent (const float *readings, unsigned int size)
 
virtual void foilPotChangedEvent (float value)
 
- Public Member Functions inherited from rec::robotino::api2::ComObject
 ComObject ()
 
virtual ~ComObject ()
 
ComId comId () const
 

Friends

class CompactBHAImpl
 

Additional Inherited Members

- Protected Attributes inherited from rec::robotino::api2::ComObject
ComId _comID
 

Detailed Description

Access to Robotino's (optional) compact version of the Bionic Handling Assistant. See Robotino XT.

Member Function Documentation

float rec::robotino::api2::CompactBHA::foilPot ( ) const

Read foil potentiometer

Returns
The current reading from the foil pot.
Exceptions
RobotinoExceptionif given com object is invalid.
virtual void rec::robotino::api2::CompactBHA::foilPotChangedEvent ( float  value)
virtual

Called when a signal from the foil potentiometer is received.

Parameters
valueSignal from the foil pot.
Exceptions
nothing.
Remarks
This function is called from the thread in which Com::processEvents() is called.
See also
Com::processEvents
void rec::robotino::api2::CompactBHA::pressures ( float *  readings) const

Read current pressure of all bellows

Parameters
[out]readingsArray of pressures in bar. Size of this array must be 8.
Exceptions
RobotinoExceptionif given com object is invalid.
virtual void rec::robotino::api2::CompactBHA::pressuresChangedEvent ( const float *  pressures,
unsigned int  size 
)
virtual

Called when pressure readings from the CBHA are received.

Parameters
pressuresArray of current pressures in bar.
sizeSize of pressures array.
Exceptions
nothing.
Remarks
This function is called from the thread in which Com::processEvents() is called.
See also
Com::processEvents
bool rec::robotino::api2::CompactBHA::pressureSensor ( ) const

Read pressure sensor

Returns
The signal from the pressure sensor
Exceptions
RobotinoExceptionif given com object is invalid.
virtual void rec::robotino::api2::CompactBHA::pressureSensorChangedEvent ( bool  pressureSensor)
virtual

Called when a signal from the pressure sensor is received.

Parameters
pressureSensorSignal from the pressure sensor.
Exceptions
nothing.
Remarks
This function is called from the thread in which Com::processEvents() is called.
See also
Com::processEvents
void rec::robotino::api2::CompactBHA::setComId ( const ComId id)

Sets the associated communication object.

Parameters
idThe id of the associated communication object.
Exceptions
RobotinoExceptionIf the given communication object doesn't provide a camera.
void rec::robotino::api2::CompactBHA::setCompressorsEnabled ( bool  enabled)

Turns compressors on and off. If on, they do only run when pressure is too low.

Parameters
enabledState of compressors.
Exceptions
RobotinoExceptionif given com object is invalid.
void rec::robotino::api2::CompactBHA::setGripperValve1 ( bool  open)

Opens and closes the gripper valve 1.

Parameters
openState of the valve.
Exceptions
RobotinoExceptionif given com object is invalid.
void rec::robotino::api2::CompactBHA::setGripperValve2 ( bool  open)

Opens and closes the gripper valve 2.

Parameters
openState of the valve.
Exceptions
RobotinoExceptionif given com object is invalid.
void rec::robotino::api2::CompactBHA::setPressures ( const float *  pressures)

Sets pressure of all bellows

Parameters
pressuresArray of pressures in bar. Size of this array must be 8.
Exceptions
RobotinoExceptionif given com object is invalid.
void rec::robotino::api2::CompactBHA::setWaterDrainValve ( bool  open)

Opens and closes the water drain valve.

Parameters
openState of the valve.
Exceptions
RobotinoExceptionif given com object is invalid.
void rec::robotino::api2::CompactBHA::stringPots ( float *  readings) const

Read string potentiometers

Parameters
[out]readingsArray of readings. Size of this array must be 6.
Exceptions
RobotinoExceptionif given com object is invalid.
virtual void rec::robotino::api2::CompactBHA::stringPotsChangedEvent ( const float *  readings,
unsigned int  size 
)
virtual

Called when signals from the string potentiometers are received.

Parameters
readingsArray of signals from the string pots.
sizeSize of values array.
Exceptions
nothing.
Remarks
This function is called from the thread in which Com::processEvents() is called.
See also
Com::processEvents

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