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
arm2segm.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 __ARM2SEGM_H
25 #define __ARM2SEGM_H
26 
27 #include "oderobot.h"
28 #include <selforg/configurable.h>
29 #include <vector>
30 
31 #include "primitive.h"
32 #include "joint.h"
33 
34 #include "angularmotor.h"
35 namespace lpzrobots{
36 
37  typedef struct {
38  double max_force; // maximal force for motors
39  int segmentsno; // number of segments
40 
41  double base_mass; // mass of base
42  double base_length;
43  double base_width;
44 
45  double arm_mass; // mass of arms
46  double arm_width;
47  double arm_length;
48  double arm_offset; // used for placing of arms
49 
50  double joint_offset; // used for placing of arms
51  } Arm2SegmConf;
52 
53 
54 
55  class Arm2Segm : public OdeRobot{
56  public:
57 
59 
60  virtual ~Arm2Segm(){};
61 
64  conf.max_force=5; // maximal force for motors
65  conf.segmentsno=4; // number of segments
66  conf.base_mass=0.5; // mass of base segment
67  conf.base_length= 0.4; // length of base segment
68  conf.base_width= 0.1; // width of base segment
69  conf.arm_mass=0.1; // mass of arm elements
70  conf.arm_width=0.2; // width (thickness) of arms
71  conf.arm_length = 1.2; // length of arms
72  conf.arm_offset= 0.03; // offset between arms (so that they do not touch)
73  conf.joint_offset=0.2; // overlapping of arms (to have area for joints)
74  return conf;
75  }
76 
77  /// update the subcomponents
78  virtual void update();
79 
80  /** sets the pose of the vehicle
81  @param pose desired 4x4 pose matrix
82  */
83  virtual void placeIntern(const osg::Matrix& pose);
84 
85  /** returns actual sensorvalues
86  @param sensors sensors scaled to [-1,1]
87  @param sensornumber length of the sensor array
88  @return number of actually written sensors
89  */
90  virtual int getSensorsIntern(sensor* sensors, int sensornumber);
91 
92  /** sets actual motorcommands
93  @param motors motors scaled to [-1,1]
94  @param motornumber length of the motor array
95  */
96  virtual void setMotorsIntern(const double* motors, int motornumber);
97 
98  /** returns number of sensors
99  */
100  virtual int getSensorNumberIntern(){
101  return sensorno;
102  };
103 
104  /** returns number of motors
105  */
106  virtual int getMotorNumberIntern(){
107  return motorno;
108  };
109 
110  /** returns a vector with the positions of all segments of the robot
111  @param poslist vector of positions (of all robot segments)
112  @return length of the list
113  */
114  virtual int getSegmentsPosition(std::vector<Position> &poslist);
115 
116  /** the main object of the robot, which is used for position and speed tracking */
117  virtual Primitive* getMainPrimitive() const;
118 
119  protected:
120 
121  /** creates vehicle at desired pose
122  @param pose 4x4 pose matrix
123  */
124  virtual void create(const osg::Matrix& pose);
125 
126  /** destroys vehicle and space
127  */
128  virtual void destroy();
129 
130  dSpaceID parentspace;
131 
133 
134 
135 
136  std::vector <AngularMotor1Axis*> amotors;
137 
138  std::string name;
141 
142  int sensorno; //number of sensors
143  int motorno; // number of motors
144 
145  bool created; // true if robot was created
146  };
147 };
148 #endif
double arm_width
Definition: arm2segm.h:46
Definition: arm2segm.h:55
Data structure for accessing the ODE.
Definition: odehandle.h:44
Definition: arm2segm.h:37
double arm_offset
Definition: arm2segm.h:48
Arm2SegmConf conf
Definition: arm2segm.h:132
Matrixd Matrix
Definition: osgforwarddecl.h:47
virtual void placeIntern(const osg::Matrix &pose)
sets the pose of the vehicle
Definition: arm2segm.cpp:104
paramval factorSensors
Definition: arm2segm.h:140
virtual void create(const osg::Matrix &pose)
creates vehicle at desired pose
Definition: arm2segm.cpp:153
dSpaceID parentspace
Definition: arm2segm.h:130
double sensor
Definition: types.h:29
double base_length
Definition: arm2segm.h:42
Data structure for accessing the OpenSceneGraph.
Definition: osghandle.h:79
double base_width
Definition: arm2segm.h:43
virtual Primitive * getMainPrimitive() const
the main object of the robot, which is used for position and speed tracking
Definition: arm2segm.cpp:144
virtual int getMotorNumberIntern()
returns number of motors
Definition: arm2segm.h:106
bool created
Definition: arm2segm.h:145
double paramval
Definition: configurable.h:88
virtual void update()
update the subcomponents
Definition: arm2segm.cpp:136
virtual int getSensorNumberIntern()
returns number of sensors
Definition: arm2segm.h:100
virtual int getSegmentsPosition(std::vector< Position > &poslist)
returns a vector with the positions of all segments of the robot
Definition: arm2segm.cpp:127
paramval speed
Definition: arm2segm.h:139
virtual ~Arm2Segm()
Definition: arm2segm.h:60
Interface class for primitives represented in the physical and graphical world.
Definition: primitive.h:80
double arm_mass
Definition: arm2segm.h:45
int sensorno
Definition: arm2segm.h:142
virtual void setMotorsIntern(const double *motors, int motornumber)
sets actual motorcommands
Definition: arm2segm.cpp:52
static Arm2SegmConf getDefaultConf()
Definition: arm2segm.h:62
std::list< SensorAttachment > sensors
Definition: oderobot.h:269
virtual int getSensorsIntern(sensor *sensors, int sensornumber)
returns actual sensorvalues
Definition: arm2segm.cpp:82
OsgHandle osgHandle
Definition: oderobot.h:278
Arm2Segm(const OdeHandle &odeHandle, const OsgHandle &osgHandle, const Arm2SegmConf)
Definition: arm2segm.cpp:31
OdeHandle odeHandle
Definition: oderobot.h:277
std::string name
Definition: arm2segm.h:138
Abstract class for ODE robots.
Definition: oderobot.h:64
double joint_offset
Definition: arm2segm.h:50
int segmentsno
Definition: arm2segm.h:39
virtual void destroy()
destroys vehicle and space
Definition: arm2segm.cpp:228
double arm_length
Definition: arm2segm.h:47
int motorno
Definition: arm2segm.h:143
std::vector< AngularMotor1Axis * > amotors
Definition: arm2segm.h:136
double max_force
Definition: arm2segm.h:38
std::list< MotorAttachment > motors
Definition: oderobot.h:270
double base_mass
Definition: arm2segm.h:41