Robot Simulator of the Robotics Group for Self-Organization of Control  0.8.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Hand Class Reference

Artificial Hand. More...

#include <hand.h>

Inheritance diagram for Hand:
Collaboration diagram for Hand:

Public Member Functions

 Hand (const OdeHandle &odeHandle, const OsgHandle &osgHandle, const HandConf &conf, const std::string &name)
 constructor of hand More...
 
virtual void update ()
 update the subcomponents More...
 
virtual void placeIntern (const osg::Matrix &pose)
 sets the pose of the vehicle More...
 
virtual void sense (GlobalData &globalData) override
 this function is called each controlstep before control. More...
 
virtual int getSensorsIntern (sensor *sensors, int sensornumber)
 returns actual sensorvalues More...
 
virtual void setMotorsIntern (const double *motors, int motornumber)
 sets actual motorcommands More...
 
virtual int getSensorNumberIntern ()
 returns number of sensors More...
 
virtual int getMotorNumberIntern ()
 returns number of motors More...
 
virtual void notifyOnChange (const paramkey &key)
 returns a vector with the positions of all segments of the robot More...
 
- Public Member Functions inherited from OdeRobot
 OdeRobot (const OdeHandle &odeHandle, const OsgHandle &osgHandle, const std::string &name, const std::string &revision)
 Constructor. More...
 
virtual ~OdeRobot ()
 calls cleanup() More...
 
virtual int getSensors (double *sensors, int sensornumber) final
 returns actual sensorvalues More...
 
virtual void setMotors (const double *motors, int motornumber) final
 sets actual motorcommands More...
 
virtual int getSensorNumber () final
 returns number of sensors More...
 
virtual int getMotorNumber () final
 returns number of motors More...
 
virtual std::list
< SensorMotorInfo
getSensorInfos () override
 returns the information for the sensors. More...
 
virtual std::list
< SensorMotorInfo
getMotorInfos () override
 returns the information for the motors. More...
 
virtual void addSensor (std::shared_ptr< Sensor > sensor, Attachment attachment=Attachment())
 adds a sensor to the robot. More...
 
virtual void addMotor (std::shared_ptr< Motor > motor, Attachment attachment=Attachment())
 adds a motor to the robot. More...
 
virtual std::list
< SensorAttachment
getAttachedSensors ()
 returns all generic sensors with their attachment More...
 
virtual std::list
< MotorAttachment
getAttachedMotors ()
 returns all generic motors with their attachment More...
 
virtual void addTorqueSensors (double maxtorque=1.0, int avg=1)
 adds a torque sensor to each joint. Call it after placement of robot. More...
 
virtual void place (const Pos &pos) final
 sets the vehicle to position pos More...
 
virtual void place (const osg::Matrix &pose) final
 sets the pose of the vehicle More...
 
virtual bool collisionCallback (void *data, dGeomID o1, dGeomID o2)
 
virtual void doInternalStuff (GlobalData &globalData)
 this function is called in each simulation timestep (always after control). More...
 
virtual void setColor (const Color &col)
 sets color of the robot More...
 
virtual Position getPosition () const
 returns position of the object More...
 
virtual Position getSpeed () const
 returns linear speed vector of the object More...
 
virtual Position getAngularSpeed () const
 returns angular velocity vector of the object More...
 
virtual matrix::Matrix getOrientation () const
 returns the orientation of the object More...
 
virtual Primitives getAllPrimitives () const
 returns a list of all primitives of the robot (used to store and restore the robot) More...
 
virtual PrimitivesgetAllPrimitives ()
 
virtual Joints getAllJoints () const
 returns a list of all primitives of the robot (const version) (used to store and restore the robot) More...
 
virtual JointsgetAllJoints ()
 
virtual bool store (FILE *f) const
 returns a list of all joints of the robot (const version) More...
 
virtual bool restore (FILE *f)
 loads the object from the given file stream (ASCII preferred). More...
 
virtual void moveToPosition (Pos pos=Pos(0, 0, 0.5), int primitiveID=-1)
 relocates robot such its primitive with the given ID is at the new postion (keep current pose). More...
 
virtual void moveToPose (Pose pose, int primitiveID=-1)
 relocates robot such its primitive with the given ID is at the new pose (keep relative pose of all primitives). More...
 
virtual Pose getInitialPose ()
 returns the initial pose of the main primitive (use it e.g. with moveToPose) More...
 
virtual Pose getRelativeInitialPose ()
 returns the initial relative pose of the main primitive (use it with moveToPose to further translate or rotate). More...
 
virtual void fixate (GlobalData &global, int primitiveID=-1, double duration=0)
 fixates the given primitive of the robot at its current position to the world for a certain time. More...
 
virtual bool unFixate (GlobalData &global)
 release the robot in case it is fixated and return true in this case More...
 
- Public Member Functions inherited from AbstractRobot
 AbstractRobot (const std::string &name="abstractRobot", const std::string &revision="$ID$")
 Constructor. More...
 
virtual ~AbstractRobot ()
 
virtual std::string getTrackableName () const
 returns name of trackable More...
 
- Public Member Functions inherited from Trackable
 Trackable ()
 Constructor. More...
 
virtual ~Trackable ()
 
- Public Member Functions inherited from Configurable
 Configurable ()
 
 Configurable (const std::string &name, const std::string &revision)
 intialise with name and revision (use "$ID$") More...
 
virtual ~Configurable ()
 
virtual void addParameter (const paramkey &key, paramval *val, paramval minBound, paramval maxBound, const paramdescr &descr=paramdescr())
 This is the new style for adding configurable parameters. More...
 
virtual void addParameter (const paramkey &key, paramval *val, const paramdescr &descr=paramdescr())
 See addParameter(const paramkey& key, paramval* val, paramval minBound, paramval maxBound, const paramdescr& descr) More...
 
virtual void addParameter (const paramkey &key, parambool *val, const paramdescr &descr=paramdescr())
 See addParameter(const paramkey& key, paramval* val) but for bool values. More...
 
virtual void addParameter (const paramkey &key, paramint *val, paramint minBound, paramint maxBound, const paramdescr &descr=paramdescr())
 See addParameter(const paramkey& key, paramval* val) but for int values. More...
 
virtual void addParameter (const paramkey &key, paramint *val, const paramdescr &descr=paramdescr())
 
virtual void addParameterDef (const paramkey &key, paramval *val, paramval def, paramval minBound, paramval maxBound, const paramdescr &descr=paramdescr())
 This function is only provided for convenience. More...
 
virtual void addParameterDef (const paramkey &key, paramval *val, paramval def, const paramdescr &descr=paramdescr())
 
virtual void addParameterDef (const paramkey &key, parambool *val, parambool def, const paramdescr &descr=paramdescr())
 See addParameterDef(const paramkey&, paramval*, paramval) More...
 
virtual void addParameterDef (const paramkey &key, paramint *val, paramint def, paramint minBound, paramint maxBound, const paramdescr &descr=paramdescr())
 See addParameterDef(const paramkey&, paramval*, paramval) More...
 
virtual void addParameterDef (const paramkey &key, paramint *val, paramint def, const paramdescr &descr=paramdescr())
 
virtual void setParamDescr (const paramkey &key, const paramdescr &descr, bool traverseChildren=true)
 sets a description for the given parameter More...
 
int getId () const
 return the id of the configurable objects, which is created by random on initialisation More...
 
virtual paramkey getName () const
 return the name of the object More...
 
virtual paramkey getRevision () const
 returns the revision of the object More...
 
virtual void setName (const paramkey &name, bool callSetNameOfInspectable=true)
 Sets the name of the configurable. More...
 
virtual void setRevision (const paramkey &revision)
 sets the revision Hint: { return "$ID$"; } More...
 
virtual paramval getParam (const paramkey &key, bool traverseChildren=true) const
 returns the value of the requested parameter or 0 (+ error message to stderr) if unknown. More...
 
virtual bool hasParam (const paramkey &key, bool traverseChildren=true) const
 Returns if the requested parameter is part of the configurable or their children. More...
 
virtual bool setParam (const paramkey &key, paramval val, bool traverseChildren=true)
 sets the value of the given parameter or does nothing if unknown. More...
 
virtual void setParamBounds (const paramkey &key, paramval minBound, paramval maxBound, bool traverseChildren=true)
 Sets the bounds (minBound and maxBound) of the given parameter. More...
 
virtual void setParamBounds (const paramkey &key, paramint minBound, paramint maxBound, bool traverseChildren=true)
 
virtual void setParamBounds (const paramkey &key, paramvalBounds bounds, bool traverseChildren=true)
 
virtual void setParamBounds (const paramkey &key, paramintBounds bounds, bool traverseChildren=true)
 
virtual paramlist getParamList () const
 The list of all parameters with there value as allocated lists. More...
 
virtual std::list< paramkeygetAllParamNames (bool traverseChildren=true)
 returns all names that are configureable More...
 
virtual parammap getParamValMap () const
 
virtual paramintmap getParamIntMap () const
 
virtual paramboolmap getParamBoolMap () const
 
virtual paramdescr getParamDescr (const paramkey &key, bool traverseChildren=true) const
 returns the description for the given parameter More...
 
virtual paramvalBounds getParamvalBounds (const paramkey &key, bool traverseChildren=true) const
 
virtual paramintBounds getParamintBounds (const paramkey &key, bool traverseChildren=true) const
 
virtual bool hasParamDescr (const paramkey &key, bool traverseChildren=true) const
 
virtual bool hasParamvalBounds (const paramkey &key, bool traverseChildren=true) const
 
virtual bool hasParamintBounds (const paramkey &key, bool traverseChildren=true) const
 
virtual bool storeCfg (const char *filenamestem, const std::list< std::string > &comments=std::list< std::string >())
 stores the key values paires into the file : filenamestem.cfg including the comments given in the list More...
 
virtual bool restoreCfg (const char *filenamestem)
 restores the key values paires from the file : filenamestem.cfg More...
 
void print (FILE *f, const char *prefix, int columns=90, bool traverseChildren=true) const
 prints the keys, values and descriptions to the file. Each line is prefixed More...
 
bool parse (FILE *f, const char *prefix=0, bool traverseChildren=true)
 parses the configuration from the given file More...
 
virtual void addConfigurable (Configurable *conf)
 Adds a configurable as a child object. More...
 
virtual void removeConfigurable (Configurable *conf)
 Removes a configurable as a child object. More...
 
virtual const configurableListgetConfigurables () const
 Returns the list containing all configurable children. More...
 
virtual void configurableChanged ()
 Indicates that the configurable itself or the configurable children attached to this configurable have changed. More...
 
- Public Member Functions inherited from BackCaller
 BackCaller ()
 
virtual ~BackCaller ()
 
virtual void addCallbackable (Callbackable *callbackableInstance, CallbackableType type=BackCaller::DEFAULT_CALLBACKABLE_TYPE)
 Adds a Callbackable instance to this caller instance. More...
 
virtual void removeCallbackable (Callbackable *callbackableInstance, CallbackableType type=BackCaller::DEFAULT_CALLBACKABLE_TYPE)
 Removes a Callbackable instance from this caller instance. More...
 
virtual void removeAllCallbackables (CallbackableType type)
 Removes all Callbackable instances from this caller instance. More...
 
virtual void callBack (CallbackableType type=BackCaller::DEFAULT_CALLBACKABLE_TYPE)
 Calls all registered callbackable classes of the determined type. More...
 
virtual void callBackQMP (CallbackableType type=BackCaller::DEFAULT_CALLBACKABLE_TYPE)
 Calls all registered callbackable classes of the determined type. More...
 
- Public Member Functions inherited from Storeable
virtual ~Storeable ()
 
bool storeToFile (const char *filename) const
 Provided for convenience. More...
 
bool restoreFromFile (const char *filename)
 Provided for convenience. More...
 

Static Public Member Functions

static HandConf getDefaultConf ()
 

Protected Member Functions

virtual PrimitivegetMainPrimitive () const
 Returns the palm as the main object of the robot, which is used for position and speed tracking. More...
 
- Protected Member Functions inherited from OdeRobot
void attachSensor (SensorAttachment &sa)
 
void attachMotor (MotorAttachment &ma)
 
virtual void cleanup ()
 deletes all objects (primitives) and joints (is called automatically in destructor) More...
 
- Protected Member Functions inherited from Configurable
void copyParameters (const Configurable &, bool traverseChildren=true)
 copies the internal params of the given configurable More...
 
void printdescr (FILE *f, const char *prefix, const paramkey &key, int columns, int indent) const
 

Protected Attributes

HandConf conf
 configuration of hand More...
 
std::vector< OSGPrimitive * > osg_objects
 vector containing OSGPrimitives More...
 
std::vector< IRSensor * > ir_sensors
 vector containing Primitivesinfrared sensors More...
 
bool contact_joint_created
 true if contact joint is created More...
 
std::vector< AngularMotor * > frictionmotors
 vector of the joints used in hand More...
 
std::vector< HingeServo * > servos
 vector of the used hinge servos More...
 
RaySensorBank irSensorBank
 a collection of ir sensors More...
 
dSpaceID hand_space
 space containing the hand More...
 
AngularMotorpalm_motor_joint
 motorjoint for actuating the forearm_palm joint (ball joint) More...
 
AngularMotorthumb_motor_joint
 motorjoint for actuating the palm_thumb joint (ball joint) More...
 
HingeJointthumb_bt
 Hinge Joint between thumb_buttom and thumb_top. More...
 
Jointpalm_index
 Hinge Joint between buttom, center and top part of the index finger. More...
 
Jointindex_bc
 
Jointindex_ct
 
Jointpalm_middle
 Hinge Joint between buttom, center and top part of the middle finger. More...
 
Jointmiddle_bc
 
Jointmiddle_ct
 
Jointpalm_ring
 Hinge Joint between buttom, center and top part of the ring finger. More...
 
Jointring_bc
 
Jointring_ct
 
Jointpalm_little
 Hinge Joint between buttom, center and top part of the little finger. More...
 
Jointlittle_bc
 
Jointlittle_ct
 
GripMode gripmode
 for handling lateral and precision grip modes More...
 
Position initial_pos
 initial position of robot More...
 
Pos oldp
 
int sensorno
 
int motorno
 
int sensor_number
 
paramval factorForce
 
paramval frictionGround
 
double velocity
 
- Protected Attributes inherited from OdeRobot
Primitives objects
 list of objects (should be populated by subclasses) More...
 
Joints joints
 list of joints (should be populated by subclasses) More...
 
std::list< SensorAttachmentsensors
 
std::list< MotorAttachmentmotors
 
TmpJointfixationTmpJoint
 
Pose initialPose
 
Pose initialRelativePose
 
OdeHandle odeHandle
 
OsgHandle osgHandle
 
dSpaceID parentspace
 
bool initialized
 
bool askedfornumber
 

Additional Inherited Members

- Public Types inherited from AbstractRobot
typedef double sensor
 
typedef double motor
 
- Public Types inherited from Configurable
typedef std::string paramkey
 
typedef std::string paramdescr
 
typedef double paramval
 
typedef std::list< std::pair
< paramkey, paramval > > 
paramlist
 
typedef std::map< paramkey,
paramval * > 
parammap
 
typedef bool parambool
 
typedef std::list< std::pair
< paramkey, parambool > > 
paramboollist
 
typedef std::map< paramkey,
parambool * > 
paramboolmap
 
typedef int paramint
 
typedef std::list< std::pair
< paramkey, paramint > > 
paramintlist
 
typedef std::map< paramkey,
paramint * > 
paramintmap
 
typedef std::map< paramkey,
paramdescr
paramdescrmap
 
typedef std::pair< paramval,
paramval
paramvalBounds
 
typedef std::map< paramkey,
paramvalBounds
paramvalBoundsMap
 
typedef std::pair< paramint,
paramint
paramintBounds
 
typedef std::map< paramkey,
paramintBounds
paramintBoundsMap
 
typedef std::pair< paramkey,
paramval * > 
paramvalpair
 
typedef std::pair< paramkey,
parambool * > 
paramboolpair
 
typedef std::pair< paramkey,
paramint * > 
paramintpair
 
typedef std::vector
< Configurable * > 
configurableList
 
- Public Types inherited from BackCaller
typedef unsigned long CallbackableType
 
- Static Public Attributes inherited from Configurable
static const CallbackableType CALLBACK_CONFIGURABLE_CHANGED = 11
 
- Static Public Attributes inherited from BackCaller
static const CallbackableType DEFAULT_CALLBACKABLE_TYPE = 0
 This is the default Callbackable type. More...
 
- Static Protected Member Functions inherited from OdeRobot
static bool isGeomInPrimitiveList (Primitive **ps, int len, dGeomID geom)
 
static bool isGeomInPrimitiveList (std::list< Primitive * > ps, dGeomID geom)
 

Detailed Description

Artificial Hand.

Constructor & Destructor Documentation

Hand ( const OdeHandle odeHandle,
const OsgHandle osgHandle,
const HandConf conf,
const std::string &  name 
)

constructor of hand

Parameters
odeHandledata structure for accessing ODE
osgHandleata structure for accessing OSG
confconfiguration of robot

Member Function Documentation

static HandConf getDefaultConf ( )
inlinestatic
virtual Primitive* getMainPrimitive ( ) const
inlineprotectedvirtual

Returns the palm as the main object of the robot, which is used for position and speed tracking.

Reimplemented from OdeRobot.

int getMotorNumberIntern ( )
virtual

returns number of motors

Reimplemented from OdeRobot.

int getSensorNumberIntern ( )
virtual

returns number of sensors

Reimplemented from OdeRobot.

int getSensorsIntern ( sensor sensors,
int  sensornumber 
)
virtual

returns actual sensorvalues

Parameters
sensorssensors scaled to [-1,1]
sensornumberlength of the sensor array
Returns
number of actually written sensors

Reimplemented from OdeRobot.

void notifyOnChange ( const paramkey key)
virtual

returns a vector with the positions of all segments of the robot

Parameters
poslistvector of positions (of all robot segments)
Returns
length of the list

Reimplemented from Configurable.

void placeIntern ( const osg::Matrix pose)
virtual

sets the pose of the vehicle

Parameters
posedesired 4x4 pose matrix

Implements OdeRobot.

void sense ( GlobalData globalData)
overridevirtual

this function is called each controlstep before control.

This is the place the perform active sensing (e.g. Image processing). If you overload this function, call the OdeRobot::sense() function.

Parameters
globalDatastructure that contains global data from the simulation environment

Reimplemented from OdeRobot.

void setMotorsIntern ( const double *  motors,
int  motornumber 
)
virtual

sets actual motorcommands

Parameters
motorsmotors scaled to [-1,1]
motornumberlength of the motor array

Reimplemented from OdeRobot.

void update ( )
virtual

update the subcomponents

Reimplemented from OdeRobot.

Member Data Documentation

HandConf conf
protected

configuration of hand

bool contact_joint_created
protected

true if contact joint is created

paramval factorForce
protected
paramval frictionGround
protected
std::vector<AngularMotor*> frictionmotors
protected

vector of the joints used in hand

vector of the angular motors

GripMode gripmode
protected

for handling lateral and precision grip modes

dSpaceID hand_space
protected

space containing the hand

Joint * index_bc
protected
Joint * index_ct
protected
Position initial_pos
protected

initial position of robot

std::vector<IRSensor*> ir_sensors
protected

vector containing Primitivesinfrared sensors

RaySensorBank irSensorBank
protected

a collection of ir sensors

Joint * little_bc
protected
Joint * little_ct
protected
Joint * middle_bc
protected
Joint * middle_ct
protected
int motorno
protected
Pos oldp
protected
std::vector<OSGPrimitive*> osg_objects
protected

vector containing OSGPrimitives

Joint* palm_index
protected

Hinge Joint between buttom, center and top part of the index finger.

Joint* palm_little
protected

Hinge Joint between buttom, center and top part of the little finger.

Joint* palm_middle
protected

Hinge Joint between buttom, center and top part of the middle finger.

AngularMotor* palm_motor_joint
protected

motorjoint for actuating the forearm_palm joint (ball joint)

Joint* palm_ring
protected

Hinge Joint between buttom, center and top part of the ring finger.

Joint * ring_bc
protected
Joint * ring_ct
protected
int sensor_number
protected
int sensorno
protected
std::vector<HingeServo*> servos
protected

vector of the used hinge servos

HingeJoint* thumb_bt
protected

Hinge Joint between thumb_buttom and thumb_top.

AngularMotor* thumb_motor_joint
protected

motorjoint for actuating the palm_thumb joint (ball joint)

double velocity
protected

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