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
skeleton.h
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (C) 2005-2011 LpzRobots development team *
3  * Georg Martius <georg dot martius at web dot de> *
4  * Frank Guettler <guettler at informatik dot uni-leipzig dot de *
5  * Frank Hesse <frank at nld dot ds dot mpg dot de> *
6  * Ralf Der <ralfder at mis dot mpg dot de> *
7  * *
8  * This program is free software; you can redistribute it and/or modify *
9  * it under the terms of the GNU General Public License as published by *
10  * the Free Software Foundation; either version 2 of the License, or *
11  * (at your option) any later version. *
12  * *
13  * This program is distributed in the hope that it will be useful, *
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
16  * GNU General Public License for more details. *
17  * *
18  * You should have received a copy of the GNU General Public License *
19  * along with this program; if not, write to the *
20  * Free Software Foundation, Inc., *
21  * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
22  * *
23  ***************************************************************************/
24 #ifndef __SKELETON_H
25 #define __SKELETON_H
26 
27 #include <ode_robots/oderobot.h>
28 #include <ode_robots/gripper.h>
29 
30 namespace lpzrobots {
31 
32  class Primitive;
33  class Joint;
34  class OneAxisServo;
35  class TwoAxisServo;
36  class AngularMotor;
37 
38 
39  typedef struct {
40  public:
41  double size; ///< scaling factor for robot (height)
42  double massfactor; ///< mass factor for all parts
43  bool useDensity; ///< massfactor is interpreted as a density
44 
45  bool useVelocityServos; ///< if true the more stable velocity controlling servos are used
46 
47  double relLegmass; ///< relative overall leg mass
48  double relArmmass; ///< relative overall arm mass
49  double relFeetmass; ///< relative overall feet mass
50 
51  double hipPower; ///< maximal force for at hip joint motors
52  double hipDamping; ///< damping of hip joint servos
53  double hipVelocity; ///< velocity of hip joint servos
54  double hipJointLimit; ///< angle range for legs
55  double hip2Power; ///< maximal force for at hip2 (sagital joint axis) joint motors
56  double hip2Damping; ///< damping of hip2 joint servos
57  double hip2JointLimit; ///< angle range for hip joint in lateral direction
58  double neckPower; ///< spring strength in the neck
59  double neckDamping; ///< damping in the neck
60  double neckVelocity; ///< velocity in the neck
61  double neckJointLimit; ///< angle range for neck
62  double kneePower; ///< spring strength in the knees
63  double kneeDamping; ///< damping in the knees
64  double kneeVelocity; ///< velocity in the knees
65  double kneeJointLimit; ///< angle range for knees
66  double anklePower; ///< spring strength in the ankles
67  double ankleDamping; ///< damping in the ankles
68  double ankleVelocity; ///< velocity in the ankles
69  double ankleJointLimit; ///< angle range for ankles
70  double armPower; ///< maximal force for at arm (shoulder) joint motors
71  double armDamping; ///< damping of arm ((shoulder)) joint servos
72  double armVelocity; ///< velocity of arm ((shoulder)) joint servos
73  double armJointLimit; ///< angle range of arm joint
74  double elbowPower; ///< maximal force for at elbow (shoulder) joint motors
75  double elbowDamping; ///< damping of elbow ((shoulder)) joint servos
76  double elbowVelocity; ///< velocity of elbow ((shoulder)) joint servos
77  double elbowJointLimit; ///< angle range of elbow joint
78  double pelvisPower; ///< maximal force for at pelvis joint motor
79  double pelvisDamping; ///< damping of pelvis joint servo
80  double pelvisVelocity; ///< velocity of pelvis joint servo
81  double pelvisJointLimit; ///< angle range of pelvis joint
82  double backPower; ///< maximal force for at back joint motor
83  double backDamping; ///< damping of back joint servo
84  double backVelocity; ///< velocity of back joint servo
85  double backJointLimit; ///< angle range of back joint
86 
87  double powerFactor; ///< scale factor for maximal forces of the servos
88  double relForce; ///< factor between arm force and rest
89  double dampingFactor; ///< scale factor for damping of the servos
90 
91  double jointLimitFactor; ///< factor between servo range (XXXJointLimit, see above) and physical joint limit
92 
93 
94  bool onlyPrimaryFunctions; ///< true: only leg and arm are controlable, false: all joints
95  bool onlyMainParameters; ///< true: only a few parameters are exported for configuration
96 
97  bool handsRotating; ///< hands are attached with a ball joint
98  bool useGripper; ///< hands have a gripper: use getGrippers and add grippables
99  double gripDuration; ///< time the gripper can grasp
100  double releaseDuration; ///< time the gripper has to release before grasping again
101 
102  bool movableHead; ///< if false then no neck movement
103  bool useBackJoint; ///< whether to use the joint in the back
104  bool backSideBend; ///< whether to use a joint to bend the back sideways
105 
106 
107  bool irSensors; ///< whether to use the irsensor eyes
108 
109  std::string headColor; ///< special color of head (typically like body)
110  std::string bodyColor; ///< color of skin
111  std::string trunkColor; ///< color of upper body (pullover-color)
112  std::string trouserColor;///< color of upper legs and hands (trousers-color)
113 
114 
115  std::string headTexture; // texture of the head
116  std::string bodyTexture; // texture of the body
117  std::string trunkTexture; // texture of the trunk and thorax
118 
119 
120  } SkeletonConf;
121 
122 
123  /** should look like a humanoid
124  */
125  class Skeleton : public OdeRobot, public Inspectable{
126  public:
127 
135 
136 
137  /**
138  * constructor of Skeleton robot
139  * @param odeHandle data structure for accessing ODE
140  * @param osgHandle ata structure for accessing OSG
141  * @param conf configuration object
142  */
144  const std::string& name);
145 
146  virtual ~Skeleton(){ destroy(); };
147 
149  SkeletonConf c;
150  c.size = 1;
151  c.massfactor = 1;
152  c.relLegmass = 1; // unused
153  c.relFeetmass = 1; // .1; unused
154  c.relArmmass = 1; // 0.3; unused
155  c.useDensity = false;
156 
157  c.useVelocityServos = true;
158  c.powerFactor = 1.0;
159  c.relForce = 1.0;
160  c.dampingFactor = 1.0;
161  c.jointLimitFactor = 1.1; // factor between servo range and physical limit
162 
163  c.hipPower = 20;
164  c.hipDamping = 0.2;
165  c.hipVelocity = 20;
166 
167  c.hip2Power = 20;
168  c.hip2Damping = 0.2;
169 
170  c.neckPower = 2;
171  c.neckDamping = 0.1;
172  c.neckVelocity = 20;
173 
174  c.kneePower = 10;
175  c.kneeDamping = 0.1;
176  c.kneeVelocity = 20;
177 
178  c.anklePower = 3;
179  c.ankleDamping = 0.1;
180  c.ankleVelocity = 20;
181 
182  c.armPower = 8;
183  c.armDamping = 0.1;
184  c.armVelocity = 20;
185 
186  c.elbowPower = 4;
187  c.elbowDamping = 0.1;
188  c.elbowVelocity = 20;
189 
190  c.pelvisPower = 20;
191  c.pelvisDamping = 0.2;
192  c.pelvisVelocity = 20;
193 
194  c.backPower = 20;
195  c.backDamping = 0.1;
196  c.backVelocity = 20;
197 
198  c.hipJointLimit = 2.1; //1.6;
199  c.hip2JointLimit = .8; //
200 
201  c.kneeJointLimit = 2; // 2.8; // + 300, -20 degree
202  c.ankleJointLimit = M_PI/2; // - 90 + 45 degree
203 
204  c.armJointLimit = M_PI/2; // +- 90 degree
205  c.elbowJointLimit = 1.4;
206 
207  c.pelvisJointLimit = M_PI/10; // +- 18 degree
208 
209  c.neckJointLimit = M_PI/5;
210  c.backJointLimit = M_PI/3;//4// // +- 60 degree (half of it to the back)
211 
212  c.onlyMainParameters = false;
213  c.onlyPrimaryFunctions = false;
214  c.handsRotating = false;
215  c.movableHead = false;
216  c.useBackJoint = true;
217  c.backSideBend = false;
218  c.irSensors = false;
219  c.useGripper = false;
220  c.gripDuration = 30;
221  c.releaseDuration = 1;
222 
223  // c.headTexture = "Images/really_white.rgb";
224  c.headTexture = "Images/dusty.rgb";
225  c.headColor = "robot4";
226  // c.bodyTexture = "Images/whitemetal_farbig_small.rgb";
227  c.bodyTexture = "Images/dusty.rgb";
228  c.bodyColor = "robot4";
229  c.trunkTexture = "Images/dusty.rgb"; //"Images/whitemetal_farbig_small.rgb";
230  c.trunkColor = "robot1";
231  c.trouserColor = "robot2";
232  return c;
233  }
234 
237 
238  c.useVelocityServos = true;
239 
240  c.hipDamping = 0.01;
241  c.hip2Damping = 0.01;
242  c.neckDamping = 0.01;
243  c.kneeDamping = 0.01;
244  c.ankleDamping = 0.01;
245  c.armDamping = 0.01;
246  c.elbowDamping = 0.01;
247  c.pelvisDamping = 0.01;
248  c.backDamping = 0.01;
249 
250 
251  return c;
252  }
253 
254 
255  /** sets the pose of the vehicle
256  @param pose desired pose matrix
257  */
258  virtual void placeIntern(const osg::Matrix& pose);
259 
260  virtual int getSensorsIntern(sensor* sensors, int sensornumber);
261  virtual void setMotorsIntern(const motor* motors, int motornumber);
262  virtual int getSensorNumberIntern();
263  virtual int getMotorNumberIntern();
264 
265 
266  /******** CONFIGURABLE ***********/
267  virtual void notifyOnChange(const paramkey& key);
268 
269  /** the main object of the robot, which is used for position and speed tracking */
270  virtual Primitive* getMainPrimitive() const { return objects[Thorax]; } // Trunk_comp
271 
272  /** returns the position of the head */
273  virtual Position getHeadPosition();
274 
275  /** returns the position of the trunk */
276  virtual Position getTrunkPosition();
277 
278  /// returns a the gripper list
280 
281 
282  protected:
283 
284  /** creates vehicle at desired pose
285  @param pose 4x4 pose matrix
286  */
287  virtual void create(const osg::Matrix& pose);
288 
289  /** destroys vehicle and space
290  */
291  virtual void destroy();
292 
294 
295  bool created; // true if robot was created
296 
297  OdeHandle ignoreColSpace; // odehandle with space within collisions are ignored
298 
299  std::vector<TwoAxisServo*> hipservos; // motors
300  std::vector<OneAxisServo*> kneeservos; // motors
301  std::vector<OneAxisServo*> ankleservos; // motors
302  std::vector<TwoAxisServo*> armservos; // motors
303  std::vector<OneAxisServo*> arm1servos; // motors
304 /* std::vector<OneAxisServo*> headservos; // motors */
305  std::vector<TwoAxisServo*> headservos; // motors
306 
307  OneAxisServo* pelvisservo; // between Hip and Trunk_comp
308  std::vector<OneAxisServo*> backservos;
309  std::vector<TwoAxisServo*> backservos2;
310 
311  std::vector<AngularMotor*> frictionmotors;
312 
315  };
316 
317 }
318 
319 #endif
SkelParts
Definition: skeleton.h:128
bool useGripper
hands have a gripper: use getGrippers and add grippables
Definition: skeleton.h:98
double hipJointLimit
angle range for legs
Definition: skeleton.h:54
bool onlyPrimaryFunctions
true: only leg and arm are controlable, false: all joints
Definition: skeleton.h:94
double massfactor
mass factor for all parts
Definition: skeleton.h:42
bool useBackJoint
whether to use the joint in the back
Definition: skeleton.h:103
std::string headTexture
Definition: skeleton.h:115
double kneeJointLimit
angle range for knees
Definition: skeleton.h:65
double gripDuration
time the gripper can grasp
Definition: skeleton.h:99
virtual int getSensorNumberIntern()
overload this function in a subclass to specific the number of custom sensors
Definition: skeleton.cpp:235
virtual Position getTrunkPosition()
returns the position of the trunk
Definition: skeleton.cpp:1124
double dampingFactor
scale factor for damping of the servos
Definition: skeleton.h:89
Data structure for accessing the ODE.
Definition: odehandle.h:44
static SkeletonConf getDefaultConfVelServos()
Definition: skeleton.h:235
double ankleVelocity
velocity in the ankles
Definition: skeleton.h:68
double elbowJointLimit
angle range of elbow joint
Definition: skeleton.h:77
Definition: skeleton.h:128
double hipVelocity
velocity of hip joint servos
Definition: skeleton.h:53
virtual ~Skeleton()
Definition: skeleton.h:146
double elbowPower
maximal force for at elbow (shoulder) joint motors
Definition: skeleton.h:74
virtual Primitive * getMainPrimitive() const
the main object of the robot, which is used for position and speed tracking
Definition: skeleton.h:270
Definition: skeleton.h:130
double powerFactor
scale factor for maximal forces of the servos
Definition: skeleton.h:87
bool onlyMainParameters
true: only a few parameters are exported for configuration
Definition: skeleton.h:95
Matrixd Matrix
Definition: osgforwarddecl.h:47
Definition: skeleton.h:134
charArray paramkey
Definition: avrtypes.h:36
double armPower
maximal force for at arm (shoulder) joint motors
Definition: skeleton.h:70
std::vector< TwoAxisServo * > backservos2
Definition: skeleton.h:309
double hip2Power
maximal force for at hip2 (sagital joint axis) joint motors
Definition: skeleton.h:55
Definition: skeleton.h:132
double relForce
factor between arm force and rest
Definition: skeleton.h:88
double sensor
Definition: types.h:29
virtual void notifyOnChange(const paramkey &key)
Is called when a parameter was changes via setParam().
Definition: skeleton.cpp:1025
virtual int getSensorsIntern(sensor *sensors, int sensornumber)
overload this function in a subclass to do specific sensor handling, not needed for generic sensors ...
Definition: skeleton.cpp:268
iparamkey name
Definition: inspectable.h:251
virtual void create(const osg::Matrix &pose)
creates vehicle at desired pose
Definition: skeleton.cpp:341
double armDamping
damping of arm ((shoulder)) joint servos
Definition: skeleton.h:71
double jointLimitFactor
factor between servo range (XXXJointLimit, see above) and physical joint limit
Definition: skeleton.h:91
double relArmmass
relative overall arm mass
Definition: skeleton.h:48
double neckPower
spring strength in the neck
Definition: skeleton.h:58
Definition: skeleton.h:128
should look like a humanoid
Definition: skeleton.h:125
Data structure for accessing the OpenSceneGraph.
Definition: osghandle.h:79
std::vector< Gripper * > GripperList
Definition: gripper.h:116
Definition: skeleton.h:131
Definition: skeleton.h:131
OdeHandle ignoreColSpace
Definition: skeleton.h:297
double relLegmass
relative overall leg mass
Definition: skeleton.h:47
double size
scaling factor for robot (height)
Definition: skeleton.h:41
double neckVelocity
velocity in the neck
Definition: skeleton.h:60
double elbowVelocity
velocity of elbow ((shoulder)) joint servos
Definition: skeleton.h:76
double kneeDamping
damping in the knees
Definition: skeleton.h:63
std::string trouserColor
color of upper legs and hands (trousers-color)
Definition: skeleton.h:112
Definition: skeleton.h:130
double kneePower
spring strength in the knees
Definition: skeleton.h:62
Definition: position.h:30
std::vector< TwoAxisServo * > headservos
Definition: skeleton.h:305
double pelvisPower
maximal force for at pelvis joint motor
Definition: skeleton.h:78
bool created
Definition: skeleton.h:295
Definition: skeleton.h:133
Definition: skeleton.h:131
double anklePower
spring strength in the ankles
Definition: skeleton.h:66
double kneeVelocity
velocity in the knees
Definition: skeleton.h:64
std::vector< OneAxisServo * > backservos
Definition: skeleton.h:308
std::string bodyColor
color of skin
Definition: skeleton.h:110
Definition: skeleton.h:130
bool backSideBend
whether to use a joint to bend the back sideways
Definition: skeleton.h:104
virtual void destroy()
destroys vehicle and space
Definition: skeleton.cpp:973
double releaseDuration
time the gripper has to release before grasping again
Definition: skeleton.h:100
double ankleJointLimit
angle range for ankles
Definition: skeleton.h:69
OneAxisServo * pelvisservo
Definition: skeleton.h:307
virtual int getMotorNumberIntern()
overload this function in a subclass to specific the number of custom sensors
Definition: skeleton.cpp:150
Interface class for primitives represented in the physical and graphical world.
Definition: primitive.h:80
double backPower
maximal force for at back joint motor
Definition: skeleton.h:82
double hipDamping
damping of hip joint servos
Definition: skeleton.h:52
double backVelocity
velocity of back joint servo
Definition: skeleton.h:84
double pelvisDamping
damping of pelvis joint servo
Definition: skeleton.h:79
std::vector< OneAxisServo * > ankleservos
Definition: skeleton.h:301
Definition: skeleton.h:128
double pelvisVelocity
velocity of pelvis joint servo
Definition: skeleton.h:80
double backJointLimit
angle range of back joint
Definition: skeleton.h:85
GripperList & getGrippers()
returns a the gripper list
Definition: skeleton.cpp:966
std::list< SensorAttachment > sensors
Definition: oderobot.h:269
Definition: skeleton.h:128
std::vector< TwoAxisServo * > hipservos
Definition: skeleton.h:299
std::vector< OneAxisServo * > kneeservos
Definition: skeleton.h:300
Interface for inspectable objects.
Definition: inspectable.h:48
double relFeetmass
relative overall feet mass
Definition: skeleton.h:49
double armVelocity
velocity of arm ((shoulder)) joint servos
Definition: skeleton.h:72
std::string trunkColor
color of upper body (pullover-color)
Definition: skeleton.h:111
double hip2Damping
damping of hip2 joint servos
Definition: skeleton.h:56
double pelvisJointLimit
angle range of pelvis joint
Definition: skeleton.h:81
Definition: skeleton.h:132
std::string bodyTexture
Definition: skeleton.h:116
std::vector< AngularMotor * > frictionmotors
Definition: skeleton.h:311
std::string trunkTexture
Definition: skeleton.h:117
static SkeletonConf getDefaultConf()
Definition: skeleton.h:148
OsgHandle osgHandle
Definition: oderobot.h:278
OdeHandle odeHandle
Definition: oderobot.h:277
double motor
Definition: types.h:30
virtual Position getHeadPosition()
returns the position of the head
Definition: skeleton.cpp:1113
int backbendindex
Definition: skeleton.h:314
double hip2JointLimit
angle range for hip joint in lateral direction
Definition: skeleton.h:57
double backDamping
damping of back joint servo
Definition: skeleton.h:83
bool irSensors
whether to use the irsensor eyes
Definition: skeleton.h:107
Abstract class for ODE robots.
Definition: oderobot.h:64
bool handsRotating
hands are attached with a ball joint
Definition: skeleton.h:97
bool useVelocityServos
if true the more stable velocity controlling servos are used
Definition: skeleton.h:45
Definition: skeleton.h:133
bool movableHead
if false then no neck movement
Definition: skeleton.h:102
Definition: skeleton.h:133
Definition: skeleton.h:132
double neckDamping
damping in the neck
Definition: skeleton.h:59
Skeleton(const OdeHandle &odeHandle, const OsgHandle &osgHandle, SkeletonConf &conf, const std::string &name)
constructor of Skeleton robot
Definition: skeleton.cpp:47
double neckJointLimit
angle range for neck
Definition: skeleton.h:61
Primitives objects
list of objects (should be populated by subclasses)
Definition: oderobot.h:265
Definition: skeleton.h:39
Definition: skeleton.h:128
double ankleDamping
damping in the ankles
Definition: skeleton.h:67
std::vector< OneAxisServo * > arm1servos
Definition: skeleton.h:303
virtual void setMotorsIntern(const motor *motors, int motornumber)
overload this function in a subclass to do specific sensor handling, not needed for generic motors ...
Definition: skeleton.cpp:162
Definition: skeleton.h:129
virtual void placeIntern(const osg::Matrix &pose)
sets the pose of the vehicle
Definition: skeleton.cpp:329
general servo motor to achieve position control
Definition: oneaxisservo.h:38
std::list< MotorAttachment > motors
Definition: oderobot.h:270
std::vector< TwoAxisServo * > armservos
Definition: skeleton.h:302
GripperList grippers
Definition: skeleton.h:313
int c
Definition: hexapod.cpp:56
double hipPower
maximal force for at hip joint motors
Definition: skeleton.h:51
std::string headColor
special color of head (typically like body)
Definition: skeleton.h:109
double elbowDamping
damping of elbow ((shoulder)) joint servos
Definition: skeleton.h:75
double armJointLimit
angle range of arm joint
Definition: skeleton.h:73
SkeletonConf conf
Definition: skeleton.h:293
bool useDensity
massfactor is interpreted as a density
Definition: skeleton.h:43