Access to Robotino's (optional) compact version of the Bionic Handling Assistant. See Robotino XT.
More...
#include <CompactBHA.h>
Access to Robotino's (optional) compact version of the Bionic Handling Assistant. See Robotino XT.
float rec::robotino::api2::CompactBHA::foilPot |
( |
| ) |
const |
Read foil potentiometer
- Returns
- The current reading from the foil pot.
- Exceptions
-
virtual void rec::robotino::api2::CompactBHA::foilPotChangedEvent |
( |
float |
value | ) |
|
|
virtual |
Called when a signal from the foil potentiometer is received.
- Parameters
-
value | Signal from the foil pot. |
- Exceptions
-
- See also
- Com::processEvents
void rec::robotino::api2::CompactBHA::pressures |
( |
float * |
readings | ) |
const |
Read current pressure of all bellows
- Parameters
-
[out] | readings | Array of pressures in bar. Size of this array must be 8. |
- Exceptions
-
virtual void rec::robotino::api2::CompactBHA::pressuresChangedEvent |
( |
const float * |
pressures, |
|
|
unsigned int |
size |
|
) |
| |
|
virtual |
Called when pressure readings from the CBHA are received.
- Parameters
-
pressures | Array of current pressures in bar. |
size | Size of pressures array. |
- Exceptions
-
- See also
- Com::processEvents
bool rec::robotino::api2::CompactBHA::pressureSensor |
( |
| ) |
const |
Read pressure sensor
- Returns
- The signal from the pressure sensor
- Exceptions
-
virtual void rec::robotino::api2::CompactBHA::pressureSensorChangedEvent |
( |
bool |
pressureSensor | ) |
|
|
virtual |
Called when a signal from the pressure sensor is received.
- Parameters
-
pressureSensor | Signal from the pressure sensor. |
- Exceptions
-
- See also
- Com::processEvents
void rec::robotino::api2::CompactBHA::setComId |
( |
const ComId & |
id | ) |
|
Sets the associated communication object.
- Parameters
-
id | The id of the associated communication object. |
- Exceptions
-
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
-
enabled | State of compressors. |
- Exceptions
-
void rec::robotino::api2::CompactBHA::setGripperValve1 |
( |
bool |
open | ) |
|
Opens and closes the gripper valve 1.
- Parameters
-
- Exceptions
-
void rec::robotino::api2::CompactBHA::setGripperValve2 |
( |
bool |
open | ) |
|
Opens and closes the gripper valve 2.
- Parameters
-
- Exceptions
-
void rec::robotino::api2::CompactBHA::setPressures |
( |
const float * |
pressures | ) |
|
Sets pressure of all bellows
- Parameters
-
pressures | Array of pressures in bar. Size of this array must be 8. |
- Exceptions
-
void rec::robotino::api2::CompactBHA::setWaterDrainValve |
( |
bool |
open | ) |
|
Opens and closes the water drain valve.
- Parameters
-
- Exceptions
-
void rec::robotino::api2::CompactBHA::stringPots |
( |
float * |
readings | ) |
const |
Read string potentiometers
- Parameters
-
[out] | readings | Array of readings. Size of this array must be 6. |
- Exceptions
-
virtual void rec::robotino::api2::CompactBHA::stringPotsChangedEvent |
( |
const float * |
readings, |
|
|
unsigned int |
size |
|
) |
| |
|
virtual |
Called when signals from the string potentiometers are received.
- Parameters
-
readings | Array of signals from the string pots. |
size | Size of values array. |
- Exceptions
-
- See also
- Com::processEvents
The documentation for this class was generated from the following file:
- C:/srcs/git/openrobotino/api2/lib/rec/robotino/api2/CompactBHA.h