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
amosII.h
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (C) 2012 by *
3  * Martin Biehl <mab@physik3.gwdg.de> *
4  * Guillaume de Chambrier <s0672742@sms.ed.ac.uk> *
5  * martius@informatik.uni-leipzig.de *
6  * Timo Nachstedt <nachstedt@physik3.gwdg.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 
25 #ifndef __AMOSII_H
26 #define __AMOSII_H
27 
28 #include <ode_robots/oderobot.h>
29 #include <selforg/inspectable.h>
30 #include <ode_robots/contactsensor.h>
31 //-------------Add by Ren relativepositionsensor.h-------
32 #include <ode_robots/relativepositionsensor.h>
33 #include <ode_robots/amosiisensormotordefinition.h>
34 #include <ode_robots/axisorientationsensor.h>
35 
36 /**
37  * forward declarations
38  */
39 namespace lpzrobots {
40  class HingeJoint;
41  class IRSensor;
42  class Joint;
43  class OneAxisServo;
44  class Primitive;
45  class RaySensorBank;
46  class SliderJoint;
47  class SpeedSensor;
48  class Spring;
49  class TwoAxisServo;
50  // Added sound sensors (2) class
51  class SoundSensor;
52 }
53 
54 namespace lpzrobots {
55 
56  struct AmosIIConf {
57  /**
58  * @name flags
59  *
60  * Enable or disable different element and features
61  */
62  /**@{*/
63  /** fix the shoulder element to the trunk. */
65  /** whether to use joints at the knees or fix them */
67  /** use spring foot */
68  bool useFoot;
69  /** use the hinge joint in the back */
70  bool useBack;
71  /**
72  * if true, rubber substance is used for feet instead of the substance
73  * used for the rest of the robot
74  */
75  bool rubberFeet;
76  /** decide whether you wand to use a local velocity sensors.
77  * If yes it gets velocity vector in local coordinates and pass it as
78  * sensorvalues */
80  /** Use binary leg contact sensors. If false, a force sensor is used. */
82  /**@}*/
83 
84  /** scaling factor for robot (length of body) */
85  double size;
86  /** trunk width */
87  double width;
88  /** trunk height */
89  double height;
90  /** length of the front of the body (if back joint is used) */
91  double frontLength;
92  /** radius of a wheel */
93  double wheel_radius;
94  /** width of a wheel */
95  double wheel_width;
96  /** mass of a wheel */
97  double wheel_mass;
98 
99  /** trunk mass */
100  double trunkMass;
101  /** mass of the front part of the robot (if backboine joint is used) */
102  double frontMass;
103  /** mass of the shoulders (if used) */
104  double shoulderMass;
105  /** mass of the coxa limbs */
106  double coxaMass;
107  /** mass of the second limbs */
108  double secondMass;
109  /** mass of the tebia limbs */
110  double tebiaMass;
111  /** mass of the feet */
112  double footMass;
113 
114  /** fix legs to trunk at this distance from bottom of trunk */
116 
117  /** distance between hindlegs and middle legs */
118  double legdist1;
119 
120  /** distance between middle legs and front legs */
121  double legdist2;
122 
123  /** @name Leg extension from trunk
124  *
125  * amosII has a fixed but adjustable joint that decides how the legs
126  * extend from the trunk.here you can adjust these joints, if
127  * shoulder = 0 this still influences how the legs extend (the coxa-trunk
128  * connection in that case)
129  */
130  /**@{*/
131  /** angle in rad around vertical axis at leg-trunk fixation for front
132  * legs*/
134  /** angle in rad around horizontal axis at leg-trunk fixation for front
135  * legs */
137  /** rotation of front legs around own axis */
138  double fLegRotAngle;
139  /** angle in rad around vertical axis at leg-trunk fixation for middle
140  * legs */
142  /** angle in rad around horizontal axis at leg-trunk fixation for middle
143  * legs */
145  /** rotation of middle legs around own axis */
146  double mLegRotAngle;
147  /** angle in rad around vertical axis at leg-trunk fixation for rear legs
148  * */
150  /** angle in rad around horizontal axis at leg-trunk fixation for rear
151  * legs */
153  /** rotation of rear legs around own axis */
154  double rLegRotAngle;
155  /**@}*/
156 
157  /**
158  * @name leg part dimensions
159  *
160  * the lengths and radii of the individual leg parts
161  */
162  /**@{*/
163  /** length of the shoulder limbs (if used) */
165  /** radius of the shoulder limbs (if used) */
167  /** length of the coxa limbs */
168  double coxaLength;
169  /** radius of the coxa limbs */
170  double coxaRadius;
171  /** length of the second limbs */
172  double secondLength;
173  /** radius of the second limbs */
174  double secondRadius;
175  /** length of the tebia limbs including fully extended foot spring
176  * (if used) */
177  double tebiaLength;
178  /** radius of the tebia limbs */
179  double tebiaRadius;
180  /** range of the foot spring */
181  double footRange;
182  /** radius of the foot capsules, choose different from tebiaRadius */
183  double footRadius;
184  /**@}*/
185 
186  /**
187  * @name Joint Limits
188  *
189  * set limits for each joint
190  */
191  /**{*/
192  /** smaller limit of the backbone joint, positive is down */
194  /** upper limit of the backbone joint, positive is down */
196  /** forward limit of the front TC joints, negative is forward
197  * (zero specified by fcoxazero) */
199  /** backward limit of the front TC joints, negative is forward
200  * (zero specified by fcoxaZero) */
202  /** forward limit of the middle TC joints, negative is forward
203  * (zero specified by fcoxaZero) */
205  /** backward limit of the middle TC joints, negative is forward
206  * (zero specified by fcoxaZero) */
208  /** forward limit of the rear TC joints, negative is forward
209  * (zero specified by fcoxaZero) */
211  /** backward limit of the rear TC joints, negative is forward
212  * (zero specified by fcoxaZero) */
214  /** lower limit of the CTr joints, positive is down */
216  /** upper limit of the CTr joints, positive is down */
218  /** lower limit of the FTi joints, positive is down */
220  /** upper limit of the FTi joints, positive is down */
222  /**}*/
223 
224  /** preload of the foot spring */
226  /** upper limit of the foot spring = maximum value
227  * (negative is downwards (spring extends)) */
229  /** lower limit of the foot spring = minimum value
230  * (negative is downwards (spring extends)) */
232 
233  /** maximal force of the backbone joint */
234  double backPower;
235  /** maximal force of the TC joint servos */
236  double coxaPower;
237  /** maximal force of the CTr joint servos */
238  double secondPower;
239  /** maximal force of the FTi joint servos */
240  double tebiaPower;
241  /** maximal force of the foot spring servos */
242  double footPower;
243 
244  /** damping of the backbone joint servo */
245  double backDamping;
246  /** damping of the TC joint servos */
247  double coxaDamping;
248  /** damping of the CTr joint servo */
250  /** damping of the FTi joint servo */
251  double tebiaDamping;
252  /** damping of the foot spring servo */
253  double footDamping;
254 
255  /** maximal velocity of the backbone joint servo */
256  double backMaxVel;
257  /** maximal velocity of the TC joint servo */
258  double coxaMaxVel;
259  /** maximal velocity of the CTr joint servo */
260  double secondMaxVel;
261  /** maximal velocity of the FTi joint servo */
262  double tebiaMaxVel;
263  /** maximal velocity of the foot spring servo */
264  double footMaxVel;
265 
266  /**
267  * @name front ultrasonic sensors
268  *
269  * configure the front ultrasonic sensors
270  */
271  /**{*/
272  /** angle versus x axis */
273  double usAngleX;
274  /** angle versus y axis */
275  double usAngleY;
276  /** choose between parallel or antiparallel front ultrasonic sensors true
277  * means parallel */
279  /** range of the front ultrasonic sensors */
280  double usRangeFront;
281  /**}*/
282 
283  /** range of the infrared sensors at the legs */
284  double irRangeLeg;
285 
286  /** path to texture for legs */
287  std::string texture;
288  /** path to texture for trunk */
289  std::string bodyTexture;
290 
291  //-----------Add GoalSensor by Ren------------------------
292  std::vector<Primitive*> GoalSensor_references;
293  //-----------Add GoalSensor by Ren------------------------
294 
295 
296  // Internal variable storing the currently used version
298 
299  /***
300  * Author: Subhi Shaker Barikhan
301  * Date:03.06.2014
302  * highFootContactsensoryFeedback=true ==> the threshold of foot contact sensor signal is 4
303  * otherwise is 1
304  */
306 
307  };
308 
309  class AmosII : public OdeRobot, public Inspectable {
310  public:
311  enum LegPos {
313  };
314  enum LegPosUsage {
316  };
318  // thoroca-coxal joint for forward (+) and backward (-) movements
319  TC,
320  // coxa-trochanteral joint for elevation (+) and depression (-) of
321  // the leg
323  // femur-tibia joints for extension (+) and flexion (-) of the
324  // tibia
326  // maximum value, used for iteration
328  };
331 
332  /**
333  * Returns the default configuration values
334  */
335  static AmosIIConf getDefaultConf(double _scale = 1.0, bool _useShoulder = 1, bool _useFoot = 1,
336  bool _useBack = 0,bool _highFootContactsensoryFeedback=false);
337 
338  static AmosIIConf getAmosIIv1Conf(double _scale = 1.0, bool _useShoulder = 1, bool _useFoot = 1,
339  bool _useBack = 0,bool _highFootContactsensoryFeedback=false);
340 
341  static AmosIIConf getAmosIIv2Conf(double _scale = 1.0, bool _useShoulder = 1, bool _useFoot = 1,
342  bool _useBack = 0, bool _highFootContactsensoryFeedback=false);
343 
344  /*
345  * Coordinated locomotion between two hexapod robots
346  * */
347 
350 
351  /**
352  * constructor
353  * @param odeHandle data structure for accessing ODE
354  * @param osgHandle ata structure for accessing OSG
355  * @param conf configuration object
356  * @param name name to display for this robot
357  */
358  AmosII(const OdeHandle& odeHandle, const OsgHandle& osgHandle, const AmosIIConf& conf = getDefaultConf(),
359  const std::string& name = "AmosII robot");
360 
361  virtual ~AmosII();
362 
363  /**
364  * updates the OSG nodes of the vehicle
365  */
366  virtual void update();
367 
368  /**
369  * sets the pose of the vehicle
370  * @param pose desired pose matrix
371  */
372  virtual void placeIntern(const osg::Matrix& pose);
373 
374  /**
375  * returns actual sensorvalues
376  * @param sensors sensor array with sensors scaled to [-1,1]
377  * @param sensornumber length of the sensor array
378  * @return number of actually written sensors
379  */
380  virtual int getSensorsIntern(sensor* sensors, int sensornumber);
381 
382  /**
383  * sets actual motorcommands
384  * @param motors motors scaled to [-1,1]
385  * @param motornumber length of the motor array
386  */
387  virtual void setMotorsIntern(const double* motors, int motornumber);
388 
389  /**
390  * returns number of sensors
391  */
392  virtual int getSensorNumberIntern();
393 
394  /**
395  * returns number of motors
396  */
397  virtual int getMotorNumberIntern();
398 
399  /**
400  * this function is called in each timestep. It should perform
401  * robot-internal checks,like space-internal collision detection, sensor
402  * resets/update etc.
403  * @param globalData structure that contains global data from the
404  * simulation environment
405  */
406  virtual void doInternalStuff(GlobalData& globalData);
407 
408  virtual void sense(GlobalData& globalData) override;
409 
410  virtual double getMassOfRobot();
411 
412  void setLegPosUsage(LegPos leg, LegPosUsage usage);
413 
414  // Configurable Interface
415  virtual bool setParam(const paramkey& key, paramval val);
416 
417  /**
418  * the main object of the robot, which is used for position and speed
419  * tracking
420  */
421  virtual Primitive* getMainPrimitive() const;
422 
423  /**
424  * returns the MotorName enum value for the given joint at the given
425  * leg. If the value for leg or joint are not valid AMOSII_MOTOR_MAX
426  * is returned.
427  *
428  * @param leg leg position
429  * @param joint leg joint type
430  * @return the motor name value or AMOSII_MOTOR_MAX if parameters are
431  * invalid
432  */
433  static MotorName getMotorName(LegPos leg, LegJointType joint);
434 
435  /**
436  * Returns the joint type of the given motor. If the given motor name
437  * is not associated with a leg joint JOINT_TYPE_MAX is returend and a
438  * warning is given out.
439  *
440  * @param MotorName name of the motor
441  * @return joint type controlled by this motor or JOINT_TYPE_MAX if
442  * MotorName is invalid
443  */
445 
446  /**
447  * Returns the leg of the given motor. If the given motor name is not
448  * associated wit a leg LEG_POS_MAX is returned and a warning is given
449  * out.
450  *
451  * @param MotorName name of the motor
452  * @return the leg on which this motor operates or LEG_POS_MAX if
453  * MotorName is invalid
454  */
456 
457  protected:
458 
459  struct Leg {
460  Leg();
464  /*Slider*/Joint * footJoint;
474  };
475 
476  /**
477  * creates vehicle at desired pose
478  *
479  * @param pose 4x4 pose matrix
480  */
481  virtual void create(const osg::Matrix& pose);
482 
483  /**
484  * destroys vehicle and space
485  */
486  virtual void destroy();
487 
488  /**
489  * Assign a human readable name to a motor. This name is used for the
490  * associated inspectable value as used e.g. in guilogger.
491  *
492  * @param motorNo index of the motor (for standard motors defined by
493  * the MotorName enum)
494  * @param name human readable name for the motor
495  */
496  void nameMotor(const int motorNo, const char* name);
497 
498  /**
499  * Assign a human readable name to a sensor. This name is used for the
500  * associated inspectable value as used e.g. in guilogger.
501  *
502  * @param motorNo index of the motor (for standard motors defined by
503  * the SensorName enum)
504  * @param name human readable name for the sensor
505  */
506  void nameSensor(const int sensorNo, const char* name);
507 
508  private:
509 
510  /** typedefs */
511  typedef std::map<LegPos, HingeJoint*> HingeJointMap;
512  typedef std::map<LegPos, Leg> LegMap;
513  typedef std::map<LegPos, ContactSensor*> LegContactMap;
514  typedef std::map<MotorName, OneAxisServo*> MotorMap;
515  typedef std::map<LegPos, LegPosUsage> LegPosUsageMap;
516  typedef std::map<LegPos, IRSensor*> LegIRSensorMap;
517  typedef std::vector<Primitive*> PrimitiveList;
518  typedef std::vector<Joint*> JointList;
519  typedef std::vector<OneAxisServo*> ServoList;
520 
521  //-----------Add Orientation Sensor by Ren----------------
522  AxisOrientationSensor* OrientationSensor;
523  //-----------Add Orientation Sensor by Ren----------------
524 
525  AmosIIConf conf;
526  bool created; // true if robot was created
527 
528  /** a collection of ir sensors **/
529  RaySensorBank * irSensorBank;
530 
531  /** speed sensor */
532  SpeedSensor * speedsensor;
533 
534  /** sound sensors */ // Added sound sensors (3) --vector
535  std::vector<SoundSensor*> soundsensors;
536 
537  /**
538  * statistics
539  * theses values are updated in every timestep and have to be updated
540  * to make them available to the lpzrobots::Inspectable interface
541  */
542  /** position of the robot */
543  Position position;
544 
545  /**
546  * defines for everey leg position the way it is used (e.g place
547  * a leg or a wheel at this position)
548  */
549  LegPosUsageMap legPosUsage;
550 
551  /**
552  * used for detection of leg contacts
553  */
554  LegContactMap legContactSensors;
555 
556  // this map knows which IR sensor to find at which leg
557  LegIRSensorMap irLegSensors;
558 
559  // holds the two front ultrasonic sensors
560  IRSensor * usSensorFrontLeft;
561  IRSensor * usSensorFrontRight;
562 
563  // body in case of no hinge joint being used
564  Primitive *trunk;
565 
566  // front part of body (when hinge joint is used)
567  Primitive *front;
568 
569  // back part of body (when hinge joint is used)
570  Primitive *center;
571 
572  // information on all legs
573  LegMap legs;
574 
575  // back bone joint
576  OneAxisServo * backboneServo;
577 
578 
579  // passive servos without a Motorname
580  ServoList passiveServos;
581 
582  // contains all active servos
583  MotorMap servos;
584 
585  //---------------Add GoalSensor by Ren---------------
586  std::vector<RelativePositionSensor> GoalSensor; // Relative position sensors
587  bool GoalSensor_active;
588  //---------------Add GoalSensor by Ren---------------
589 
590  };
591 }
592 
593 #endif
Class for a bank (collection) of ray sensors.
Definition: raysensorbank.h:36
double secondDamping
damping of the CTr joint servo
Definition: amosII.h:249
double tebiaJointLimitU
upper limit of the FTi joints, positive is down
Definition: amosII.h:221
double footRadius
radius of the foot capsules, choose different from tebiaRadius
Definition: amosII.h:183
static AmosIIConf getAmosIIv2Conf(double _scale=1.0, bool _useShoulder=1, bool _useFoot=1, bool _useBack=0, bool _highFootContactsensoryFeedback=false)
Definition: amosII.cpp:1507
void nameMotor(const int motorNo, const char *name)
Assign a human readable name to a motor.
Definition: amosII.cpp:314
double legdist1
distance between hindlegs and middle legs
Definition: amosII.h:118
void nameSensor(const int sensorNo, const char *name)
Assign a human readable name to a sensor.
Definition: amosII.cpp:296
AmosIISensorNames
Definition: amosiisensormotordefinition.h:12
double backJointLimitD
{
Definition: amosII.h:193
Definition: amosII.h:312
double footSpringLimitU
upper limit of the foot spring = maximum value (negative is downwards (spring extends)) ...
Definition: amosII.h:228
double shoulderLength
length of the shoulder limbs (if used)
Definition: amosII.h:164
double rLegTrunkAngleV
angle in rad around vertical axis at leg-trunk fixation for rear legs
Definition: amosII.h:149
double wheel_radius
radius of a wheel
Definition: amosII.h:93
bool useFoot
use spring foot
Definition: amosII.h:68
double coxaMaxVel
maximal velocity of the TC joint servo
Definition: amosII.h:258
double secondMass
mass of the second limbs
Definition: amosII.h:108
Data structure for accessing the ODE.
Definition: odehandle.h:44
Primitive * shoulder
Definition: amosII.h:469
std::string paramkey
Definition: configurable.h:85
double shoulderHeight
fix legs to trunk at this distance from bottom of trunk
Definition: amosII.h:115
LegPos
Definition: amosII.h:311
double size
scaling factor for robot (length of body)
Definition: amosII.h:85
Definition: amosII.h:325
double backDamping
damping of the backbone joint servo
Definition: amosII.h:245
OneAxisServo * tcServo
Definition: amosII.h:465
void setLegPosUsage(LegPos leg, LegPosUsage usage)
Definition: amosII.cpp:1465
double rLegTrunkAngleH
angle in rad around horizontal axis at leg-trunk fixation for rear legs
Definition: amosII.h:152
double fLegTrunkAngleH
angle in rad around horizontal axis at leg-trunk fixation for front legs
Definition: amosII.h:136
virtual double getMassOfRobot()
Definition: amosII.cpp:667
bool useBack
use the hinge joint in the back
Definition: amosII.h:70
double wheel_mass
mass of a wheel
Definition: amosII.h:97
bool highFootContactsensoryFeedback
Definition: amosII.h:305
Definition: amosII.h:312
double backMaxVel
maximal velocity of the backbone joint servo
Definition: amosII.h:256
double tebiaMass
mass of the tebia limbs
Definition: amosII.h:110
Matrixd Matrix
Definition: osgforwarddecl.h:47
double trunkMass
trunk mass
Definition: amosII.h:100
double coxaRadius
radius of the coxa limbs
Definition: amosII.h:170
Definition: amosII.h:312
double coxaLength
length of the coxa limbs
Definition: amosII.h:168
double footDamping
damping of the foot spring servo
Definition: amosII.h:253
Definition: joint.h:41
Definition: amosII.h:312
Definition: amosII.h:315
Class for sensing the axis orienation of a primitive (robot)
Definition: axisorientationsensor.h:33
virtual void sense(GlobalData &globalData) override
this function is called each controlstep before control.
Definition: amosII.cpp:679
double footRange
range of the foot spring
Definition: amosII.h:181
virtual int getSensorsIntern(sensor *sensors, int sensornumber)
returns actual sensorvalues
Definition: amosII.cpp:364
double secondLength
length of the second limbs
Definition: amosII.h:172
double backJointLimitU
upper limit of the backbone joint, positive is down
Definition: amosII.h:195
bool rubberFeet
if true, rubber substance is used for feet instead of the substance used for the rest of the robot ...
Definition: amosII.h:75
Definition: amosII.h:315
double footMaxVel
maximal velocity of the foot spring servo
Definition: amosII.h:264
iparamkey name
Definition: inspectable.h:251
double tebiaRadius
radius of the tebia limbs
Definition: amosII.h:179
static AmosIIConf getAmosIIv1Conf(double _scale=1.0, bool _useShoulder=1, bool _useFoot=1, bool _useBack=0, bool _highFootContactsensoryFeedback=false)
Definition: amosII.cpp:1724
std::vector< Primitive * > GoalSensor_references
Definition: amosII.h:292
double fcoxaJointLimitB
backward limit of the front TC joints, negative is forward (zero specified by fcoxaZero) ...
Definition: amosII.h:201
double mLegTrunkAngleH
angle in rad around horizontal axis at leg-trunk fixation for middle legs
Definition: amosII.h:144
Definition: amosII.h:56
Data structure for accessing the OpenSceneGraph.
Definition: osghandle.h:79
Class for IR sensors.
Definition: irsensor.h:39
double rLegRotAngle
rotation of rear legs around own axis
Definition: amosII.h:154
virtual int getSensorNumberIntern()
returns number of sensors
Definition: amosII.cpp:348
double usAngleY
angle versus y axis
Definition: amosII.h:275
double footSpringPreload
}
Definition: amosII.h:225
double irRangeLeg
}
Definition: amosII.h:284
double usRangeFront
range of the front ultrasonic sensors
Definition: amosII.h:280
double rcoxaJointLimitF
forward limit of the rear TC joints, negative is forward (zero specified by fcoxaZero) ...
Definition: amosII.h:210
virtual ~AmosII()
Definition: amosII.cpp:279
static MotorName getMotorName(LegPos leg, LegJointType joint)
returns the MotorName enum value for the given joint at the given leg.
Definition: amosII.cpp:1344
virtual void create(const osg::Matrix &pose)
creates vehicle at desired pose
Definition: amosII.cpp:733
LegPosUsage
Definition: amosII.h:314
double fLegTrunkAngleV
angle in rad around vertical axis at leg-trunk fixation for front legs
Definition: amosII.h:133
Definition: position.h:30
static AmosIIConf getDefaultConf(double _scale=1.0, bool _useShoulder=1, bool _useFoot=1, bool _useBack=0, bool _highFootContactsensoryFeedback=false)
Returns the default configuration values.
Definition: amosII.cpp:1503
double coxaMass
mass of the coxa limbs
Definition: amosII.h:106
bool useTebiaJoints
whether to use joints at the knees or fix them
Definition: amosII.h:66
double paramval
Definition: configurable.h:88
double frontLength
length of the front of the body (if back joint is used)
Definition: amosII.h:91
double tebiaJointLimitD
lower limit of the FTi joints, positive is down
Definition: amosII.h:219
double secondMaxVel
maximal velocity of the CTr joint servo
Definition: amosII.h:260
Definition: amosII.h:312
Definition: amosII.h:319
virtual void placeIntern(const osg::Matrix &pose)
sets the pose of the vehicle
Definition: amosII.cpp:625
Joint * footJoint
Definition: amosII.h:464
double coxaDamping
damping of the TC joint servos
Definition: amosII.h:247
double mcoxaJointLimitB
backward limit of the middle TC joints, negative is forward (zero specified by fcoxaZero) ...
Definition: amosII.h:207
double footPower
maximal force of the foot spring servos
Definition: amosII.h:242
Primitive * getTibiaPrimitive(LegPos leg)
Definition: amosII.cpp:1491
bool legContactSensorIsBinary
Use binary leg contact sensors.
Definition: amosII.h:81
Interface class for primitives represented in the physical and graphical world.
Definition: primitive.h:80
double shoulderRadius
radius of the shoulder limbs (if used)
Definition: amosII.h:166
Primitive * coxa
Definition: amosII.h:470
virtual void update()
updates the OSG nodes of the vehicle
Definition: amosII.cpp:645
AmosII(const OdeHandle &odeHandle, const OsgHandle &osgHandle, const AmosIIConf &conf=getDefaultConf(), const std::string &name="AmosII robot")
constructor
Definition: amosII.cpp:91
double rcoxaJointLimitB
backward limit of the rear TC joints, negative is forward (zero specified by fcoxaZero) ...
Definition: amosII.h:213
static LegJointType getLegJointType(MotorName)
Returns the joint type of the given motor.
Definition: amosII.cpp:1393
Data structure holding all essential global information.
Definition: globaldata.h:57
Definition: amosII.h:312
Definition: amosII.h:322
double frontMass
mass of the front part of the robot (if backboine joint is used)
Definition: amosII.h:102
virtual Primitive * getMainPrimitive() const
the main object of the robot, which is used for position and speed tracking
Definition: amosII.cpp:724
Primitive * getShoulderPrimitive(LegPos leg)
Definition: amosII.cpp:1476
std::list< SensorAttachment > sensors
Definition: oderobot.h:269
Class for speed sensing of robots.
Definition: speedsensor.h:34
double usAngleX
{
Definition: amosII.h:273
Primitive * tibia
Definition: amosII.h:472
double tebiaLength
length of the tebia limbs including fully extended foot spring (if used)
Definition: amosII.h:177
LegJointType
Definition: amosII.h:317
Interface for inspectable objects.
Definition: inspectable.h:48
Definition: amosII.h:315
Primitive * foot
Definition: amosII.h:473
virtual int getMotorNumberIntern()
returns number of motors
Definition: amosII.cpp:283
double mLegRotAngle
rotation of middle legs around own axis
Definition: amosII.h:146
static LegPos getMotorLegPos(MotorName)
Returns the leg of the given motor.
Definition: amosII.cpp:1432
Spring * footSpring
Definition: amosII.h:468
double shoulderMass
mass of the shoulders (if used)
Definition: amosII.h:104
double secondRadius
radius of the second limbs
Definition: amosII.h:174
OsgHandle osgHandle
Definition: oderobot.h:278
OdeHandle odeHandle
Definition: oderobot.h:277
double footMass
mass of the feet
Definition: amosII.h:112
HingeJoint * ftiJoint
Definition: amosII.h:463
Primitive * second
Definition: amosII.h:471
double tebiaPower
maximal force of the FTi joint servos
Definition: amosII.h:240
HingeJoint * ctrJoint
Definition: amosII.h:462
virtual bool setParam(const paramkey &key, paramval val)
Definition: amosII.cpp:1271
AmosIISensorNames SensorName
Definition: amosII.h:330
double tebiaMaxVel
maximal velocity of the FTi joint servo
Definition: amosII.h:262
Abstract class for ODE robots.
Definition: oderobot.h:64
Definition: amosII.h:309
int amos_version
Definition: amosII.h:297
std::string bodyTexture
path to texture for trunk
Definition: amosII.h:289
Definition: spring.h:30
double fcoxaJointLimitF
forward limit of the front TC joints, negative is forward (zero specified by fcoxazero) ...
Definition: amosII.h:198
OneAxisServo * ftiServo
Definition: amosII.h:467
double fLegRotAngle
rotation of front legs around own axis
Definition: amosII.h:138
OneAxisServo * ctrServo
Definition: amosII.h:466
Definition: amosII.h:312
double sensor
Definition: abstractrobot.h:43
bool usParallel
choose between parallel or antiparallel front ultrasonic sensors true means parallel ...
Definition: amosII.h:278
double tebiaDamping
damping of the FTi joint servo
Definition: amosII.h:251
AmosIIMotorNames
Definition: amosiisensormotordefinition.h:222
bool useShoulder
fix the shoulder element to the trunk.
Definition: amosII.h:64
double height
trunk height
Definition: amosII.h:89
double mcoxaJointLimitF
forward limit of the middle TC joints, negative is forward (zero specified by fcoxaZero) ...
Definition: amosII.h:204
AmosIIMotorNames MotorName
Definition: amosII.h:329
virtual void doInternalStuff(GlobalData &globalData)
this function is called in each timestep.
Definition: amosII.cpp:704
std::string texture
path to texture for legs
Definition: amosII.h:287
Definition: joint.h:183
virtual void destroy()
destroys vehicle and space
Definition: amosII.cpp:1200
HingeJoint * tcJoint
Definition: amosII.h:461
double legdist2
distance between middle legs and front legs
Definition: amosII.h:121
bool useLocalVelSensor
decide whether you wand to use a local velocity sensors.
Definition: amosII.h:79
double footSpringLimitD
lower limit of the foot spring = minimum value (negative is downwards (spring extends)) ...
Definition: amosII.h:231
double secondPower
maximal force of the CTr joint servos
Definition: amosII.h:238
double mLegTrunkAngleV
angle in rad around vertical axis at leg-trunk fixation for middle legs
Definition: amosII.h:141
general servo motor to achieve position control
Definition: oneaxisservo.h:38
std::list< MotorAttachment > motors
Definition: oderobot.h:270
double wheel_width
width of a wheel
Definition: amosII.h:95
Definition: amosII.h:459
virtual void setMotorsIntern(const double *motors, int motornumber)
sets actual motorcommands
Definition: amosII.cpp:328
double width
trunk width
Definition: amosII.h:87
double backPower
maximal force of the backbone joint
Definition: amosII.h:234
Leg()
Definition: amosII.cpp:71
double secondJointLimitU
upper limit of the CTr joints, positive is down
Definition: amosII.h:217
double coxaPower
maximal force of the TC joint servos
Definition: amosII.h:236
double secondJointLimitD
lower limit of the CTr joints, positive is down
Definition: amosII.h:215