Public Member Functions | |
| BARRETT_UNITS_TYPEDEFS (DOF) | |
| Hand (const std::vector< Puck * > &pucks) | |
| ~Hand () | |
| void | initialize () const |
| void | idle () const |
| bool | doneMoving (unsigned int whichDigits=WHOLE_HAND, bool realtime=false) const |
| void | waitUntilDoneMoving (unsigned int whichDigits=WHOLE_HAND, double period_s=0.1) const |
| void | open (unsigned int whichDigits=WHOLE_HAND, bool blocking=true) const |
| void | open (bool blocking) const |
| void | close (unsigned int whichDigits=WHOLE_HAND, bool blocking=true) const |
| void | close (bool blocking) const |
| void | trapezoidalMove (const jp_type &jp, unsigned int whichDigits=WHOLE_HAND, bool blocking=true) const |
| void | trapezoidalMove (const jp_type &jp, bool blocking) const |
| void | velocityMove (const jv_type &jv, unsigned int whichDigits=WHOLE_HAND) const |
| void | setPositionMode (unsigned int whichDigits=WHOLE_HAND) const |
| void | setPositionCommand (const jp_type &jp, unsigned int whichDigits=WHOLE_HAND) const |
| void | setTorqueMode (unsigned int whichDigits=WHOLE_HAND) const |
| void | setTorqueCommand (const jt_type &jt, unsigned int whichDigits=WHOLE_HAND) const |
| void | update (unsigned int sensors=S_ALL, bool realtime=false) |
| const jp_type & | getInnerLinkPosition () const |
| const jp_type & | getOuterLinkPosition () const |
| const std::vector< int > & | getPrimaryEncoderPosition () const |
| const std::vector< int > & | getSecondaryEncoderPosition () const |
| void | enableBreakawayEncoders (bool enable) |
| bool | hasFingertipTorqueSensors () const |
| const std::vector< int > & | getFingertipTorque () const |
| bool | hasTactSensors () const |
| const std::vector< TactilePuck * > & | getTactilePucks () const |
Static Public Attributes | |
| static const size_t | DOF = 4 |
| static const unsigned int | F1 = 1 << 0 |
| static const unsigned int | F2 = 1 << 1 |
| static const unsigned int | F3 = 1 << 2 |
| static const unsigned int | SPREAD = 1 << 3 |
| static const unsigned int | GRASP = F1 | F2 | F3 |
| static const unsigned int | WHOLE_HAND = GRASP | SPREAD |
| static const unsigned int | S_POSITION = 1 << 0 |
| static const unsigned int | S_FINGERTIP_TORQUE = 1 << 1 |
| static const unsigned int | S_TACT_FULL = 1 << 2 |
| static const unsigned int | S_ALL = S_POSITION | S_FINGERTIP_TORQUE | S_TACT_FULL |
| static const size_t | SPREAD_INDEX = 3 |
Protected Member Functions | |
| bool | digitsInclude (unsigned int whichDigits, size_t index) const |
| void | setProperty (unsigned int whichDigits, enum Puck::Property prop, int value) const |
| void | setProperty (unsigned int whichDigits, enum Puck::Property prop, const v_type &values) const |
| void | blockIf (bool blocking, unsigned int whichDigits) const |
Protected Attributes | |
| bool | hasFtt |
| bool | hasTact |
| bool | useSecondaryEncoders |
| int | holds [DOF] |
| v_type | j2pp |
| v_type | j2pt |
| v_type | pt |
|
std::vector < MotorPuck::CombinedPositionParser < int >::result_type > | encoderTmp |
| std::vector< int > | primaryEncoder |
| std::vector< int > | secondaryEncoder |
| jp_type | innerJp |
| jp_type | outerJp |
| std::vector< int > | ftt |
| std::vector< TactilePuck * > | tactilePucks |
Static Protected Attributes | |
| static const double | J2_RATIO = 125.0 |
| static const double | J2_ENCODER_RATIO = 50.0 |
| static const double | J3_RATIO = 375.0 |
| static const double | SPREAD_RATIO = 17.5 |
| barrett::Hand::Hand | ( | const std::vector< Puck * > & | _pucks | ) |
Hand Constructor
Hand Destructor
| void barrett::Hand::blockIf | ( | bool | blocking, |
| unsigned int | whichDigits | ||
| ) | const [protected] |
blockIf Method
| void barrett::Hand::close | ( | unsigned int | whichDigits = WHOLE_HAND, |
| bool | blocking = true |
||
| ) | const |
close Method
| void barrett::Hand::close | ( | bool | blocking | ) | const [inline] |
close Method
| bool barrett::Hand::digitsInclude | ( | unsigned int | whichDigits, |
| size_t | index | ||
| ) | const [inline, protected] |
| bool barrett::Hand::doneMoving | ( | unsigned int | whichDigits = WHOLE_HAND, |
| bool | realtime = false |
||
| ) | const |
doneMoving Method
| void barrett::Hand::enableBreakawayEncoders | ( | bool | enable | ) | [inline] |
enableBreakawayEncoders Method actives or deactivates the Secondary Encoders
| const std::vector<int>& barrett::Hand::getFingertipTorque | ( | ) | const [inline] |
getFingertipTorque Method gets the fingertip torques in torque units
| const jp_type& barrett::Hand::getInnerLinkPosition | ( | ) | const [inline] |
getInnerLinkPosition Method
| const jp_type& barrett::Hand::getOuterLinkPosition | ( | ) | const [inline] |
getOuterLinkPosition Method
| const std::vector<int>& barrett::Hand::getPrimaryEncoderPosition | ( | ) | const [inline] |
getPrimaryEncoderPosition Method
| const std::vector<int>& barrett::Hand::getSecondaryEncoderPosition | ( | ) | const [inline] |
getSecondaryEncoderPosition Method
| const std::vector<TactilePuck*>& barrett::Hand::getTactilePucks | ( | ) | const [inline] |
getTactilePucks Method creates container of pucks to get tactile sensor data from possible locations
| bool barrett::Hand::hasFingertipTorqueSensors | ( | ) | const [inline] |
hasFingertipTorqueSensors Method returns status of installed fingertip torque sensors
| bool barrett::Hand::hasTactSensors | ( | ) | const [inline] |
hasTactSensors Method returns whether or not Tactile Sensors are present on hand.
| void barrett::Hand::idle | ( | ) | const [inline] |
idle Method
| void barrett::Hand::initialize | ( | ) | const |
initialize Method
| void barrett::Hand::open | ( | unsigned int | whichDigits = WHOLE_HAND, |
| bool | blocking = true |
||
| ) | const |
open Method
| void barrett::Hand::open | ( | bool | blocking | ) | const [inline] |
open Method
| void barrett::Hand::setPositionCommand | ( | const jp_type & | jp, |
| unsigned int | whichDigits = WHOLE_HAND |
||
| ) | const |
setPositionCommand Method
| void barrett::Hand::setPositionMode | ( | unsigned int | whichDigits = WHOLE_HAND | ) | const |
setPositionMode Method
| void barrett::Hand::setProperty | ( | unsigned int | whichDigits, |
| enum Puck::Property | prop, | ||
| int | value | ||
| ) | const [protected] |
| void barrett::Hand::setProperty | ( | unsigned int | whichDigits, |
| enum Puck::Property | prop, | ||
| const v_type & | values | ||
| ) | const [protected] |
setProperty Method
| void barrett::Hand::setTorqueCommand | ( | const jt_type & | jt, |
| unsigned int | whichDigits = WHOLE_HAND |
||
| ) | const |
setTorqueCommand Method
| void barrett::Hand::setTorqueMode | ( | unsigned int | whichDigits = WHOLE_HAND | ) | const |
setTorqueMode Method
| void barrett::Hand::trapezoidalMove | ( | const jp_type & | jp, |
| unsigned int | whichDigits = WHOLE_HAND, |
||
| bool | blocking = true |
||
| ) | const |
trapezoidalMove Method
| void barrett::Hand::trapezoidalMove | ( | const jp_type & | jp, |
| bool | blocking | ||
| ) | const [inline] |
trapezoidalMove Method
| void barrett::Hand::update | ( | unsigned int | sensors = S_ALL, |
| bool | realtime = false |
||
| ) |
update Method
| void barrett::Hand::velocityMove | ( | const jv_type & | jv, |
| unsigned int | whichDigits = WHOLE_HAND |
||
| ) | const |
velocityMove Method
| void barrett::Hand::waitUntilDoneMoving | ( | unsigned int | whichDigits = WHOLE_HAND, |
| double | period_s = 0.1 |
||
| ) | const |
waitUntilDoneMoving Method
waitUntilDoneMoving Method prevents any subsequent actions until finger movement is completed.
1.7.6.1