components are the building parts for robots components can be composed of zero or more sub components components can be bodies + geometry, sensors, ... components may expose wires
the interface to control the robot is a set of wires.
Classes | |
class | OdeAgent |
Specialised agent for ode robots. More... | |
class | CompatSim |
class | IWire |
Wire. More... | |
class | IInputWire |
class | IOutputWire |
class | IBidirectionalWire |
class | IComponent |
Component. More... | |
class | AbstractComponent |
AbstractComponent. More... | |
class | AbstractCompoundComponent |
AbstractCompoundComponent. More... | |
class | SimplePhysicalComponent |
SimplePhysicalComponent. More... | |
class | AbstractMotorComponent |
AbstractMotorComponent. More... | |
class | MotorWire |
class | UniversalMotorComponent |
UniversalMotorComponent. More... | |
class | RobotArmDescription |
class | CCURobotArmComponent |
RobotArmComponent. More... | |
class | PlaneComponentDescription |
class | SpiderDescription |
class | SpiderComponent |
class | ComponentToRobot |
class | AngularMotor |
Abstract angular motor class. More... | |
class | AngularMotor1Axis |
Angular motor for OneAxisJoints. More... | |
class | AngularMotor2Axis |
Angular motor for TwoAxisJoints. More... | |
class | AngularMotor3AxisEuler |
Angular motor for Ball Joints with Euler control. More... | |
class | AngularMotorNAxis |
Angular motor for arbitrary Joints with custom axis (up to 3). More... | |
class | Hinge2Servo |
PID Servo motor for hinge2 joints at axis 1 (steering axis). More... | |
class | HingeServo |
PID Servo motor for hinge joints. More... | |
class | PID |
class | SliderServo |
PID Servo motor for slider joints. More... | |
class | UniversalServo |
PID Servo motor for universal joints. More... | |
class | AbstractObstacle |
Abstract class (interface) for obstacles. More... | |
class | ClosedPlayground |
class | MeshObstacle |
class | OctaPlayground |
class | PassiveBox |
(Passive) box as obstacle More... | |
class | PassiveSphere |
(Passive) sphere as obstacle More... | |
class | Playground |
class | OdeConfig |
class | MoveEarthySkyWithEyePointTransform |
class | Base |
class | BoundingShape |
class for reading bounding shape description files (.bbox) and to create appropriate geoms File Format: Lines wise, every line stands for one primitive. More... | |
class | CameraManipulator |
CameraManipulator is a MatrixManipulator which provides Flying simulator-like updating of the camera position & orientation. More... | |
class | CameraManipulatorFollow |
CameraManipulatorFollow is a MatrixManipulator which provides Flying simulator-like updating of the camera position & orientation. More... | |
class | CameraManipulatorRace |
CameraManipulatorRace is a MatrixManipulator which provides Flying simulator-like updating of the camera position & orientation. More... | |
class | CameraManipulatorTV |
CameraManipulatorTV is a MatrixManipulator which provides Flying simulator-like updating of the camera position & orientation. More... | |
class | ExtendedViewer |
A Producer-based viewer. More... | |
class | InvisibleBox |
class | InvisibleSphere |
class | InvisibleCapsule |
class | Joint |
class | OneAxisJoint |
class | TwoAxisJoint |
class | FixedJoint |
class | HingeJoint |
class | Hinge2Joint |
class | UniversalJoint |
class | BallJoint |
class | SliderJoint |
class | OSGPrimitive |
Interface class for graphic primitives like spheres, boxes, and meshes, which can be drawn by OSG. More... | |
class | OSGDummy |
A dummy graphical object, which has no representation in the graphical world. More... | |
class | OSGPlane |
Graphical plane (represented as a large thin box, because OSG does not draw planes). More... | |
class | OSGBox |
Graphical box. More... | |
class | OSGSphere |
Graphical sphere. More... | |
class | OSGCapsule |
Graphical capsule (a cylinder with round ends). More... | |
class | OSGCylinder |
Graphical cylinder. More... | |
class | OSGMesh |
Graphical Mesh or arbitrary OSG model. More... | |
class | Primitive |
Interface class for primitives represented in the physical and graphical world. More... | |
class | Plane |
Plane primitive. More... | |
class | Box |
Box primitive. More... | |
class | Sphere |
Sphere primitive. More... | |
class | Capsule |
Capsule primitive. More... | |
class | Transform |
Primitive for transforming a geom (primitive without body) in respect to a body (primitive with body). More... | |
class | DummyPrimitive |
Dummy Primitive which returns 0 for geom and body. More... | |
struct | Arm2SegmConf |
class | Arm2Segm |
class | ForcedSphere |
class | Formel1 |
Robot that looks like a Nimm 2 Bonbon :-) 4 wheels and a capsule like body. More... | |
class | HurlingSnake |
Hurling snake is a string a beats. More... | |
struct | MuscledArmConf |
class | MuscledArm |
struct | Bumper |
struct | Nimm2Conf |
class | Nimm2 |
Robot that looks like a Nimm 2 Bonbon :-) 2 wheels and a cylinder like body. More... | |
class | Nimm4 |
Robot that looks like a Nimm 2 Bonbon :-) 4 wheels and a capsule like body. More... | |
class | OdeRobot |
Abstract class for ODE robots. More... | |
struct | SchlangeConf |
class | Schlange |
This is a class, which models a snake like robot. More... | |
class | SchlangeForce |
This is a class, which models a snake like robot. More... | |
class | SchlangeServo |
This is a class, which models a snake like robot. More... | |
class | SchlangeServo2 |
This is a class, which models a snake like robot. More... | |
class | SchlangeVelocity |
This is a class, which models a snake like robot. More... | |
class | ShortCircuit |
struct | SphererobotConf |
class | Sphererobot |
This is a class, which models a snake like robot. More... | |
struct | Sphererobot3MassesConf |
class | Sphererobot3Masses |
class | IRSensor |
Class for IR sensors. More... | |
class | RaySensor |
Abstract class for Ray-based sensors. More... | |
class | RaySensorBank |
Class for a bank of ray sensors. More... | |
class | Simulation |
class | Axis |
class | Color |
class | CubicSpline |
class | IException |
struct | GlobalData |
Data structure holding all essential global information. More... | |
class | VideoStream |
class | TriDiagonalMatrixPair |
class | AbstractMatrix |
class | Matrix |
class | TriDiagonalMatrix |
TriDiagonalMatrix N: number of rows. More... | |
class | OdeHandle |
Data structure for accessing the ODE. More... | |
class | OsgHandle |
Data structure for accessing the ODE. More... | |
class | Pos |
class | Vector |
class | Vector3 |
Typedefs | |
typedef std::list< IComponent * > | ComponentContainer |
typedef Vector3< dReal > | Vertex |
typedef std::list< Vertex > | VertexList |
typedef Vector3< dReal > | Angle |
typedef std::list< Angle > | AngleList |
typedef std::list< IWire * > | WireContainer |
typedef lpzrobots::Bumper | Bumper |
typedef vector< AbstractObstacle * > | ObstacleList |
typedef vector< Configurable * > | ConfigList |
typedef vector< OdeAgent * > | OdeAgentList |
typedef lpzrobots::GlobalData | GlobalData |
Data structure holding all essential global information. | |
typedef Vector3< double > | DVector3 |
typedef Vector3< float > | FVector3 |
Enumerations | |
enum | parts { base, upperArm, lowerArm, mainMuscle11, mainMuscle12, mainMuscle21, mainMuscle22, smallMuscle11, smallMuscle12, smallMuscle21, smallMuscle22, smallMuscle31, smallMuscle32, smallMuscle41, smallMuscle42, hand, NUMParts } |
enum | joints { HJ_BuA, HJ_uAlA, HJ_BmM11, HJ_lAmM12, HJ_BmM21, HJ_lAmM22, HJ_BsM11, HJ_uAsM12, HJ_BsM21, HJ_uAsM22, HJ_lAsM31, HJ_uAsM32, HJ_lAsM41, HJ_uAsM42, SJ_mM1, SJ_mM2, SJ_sM1, SJ_sM2, SJ_sM3, SJ_sM4, NUMJoints } |
enum | CameraType { Static, TV, Following, advancedTV, advancedFollowing } |
Functions | |
ref_ptr< Material > | getMaterial (const Color &c, Material::ColorMode mode=Material::DIFFUSE) |
osg::Matrix | osgPose (dGeomID geom) |
returns the osg (4x4) pose matrix of the ode geom | |
osg::Matrix | osgPose (dBodyID body) |
returns the osg (4x4) pose matrix of the ode body | |
osg::Matrix | osgPose (const double *position, const double *rotation) |
converts a position vector and a rotation matrix from ode to osg 4x4 matrix | |
void | odeRotation (const osg::Matrix &pose, dMatrix3 &odematrix) |
converts the rotation component of pose into an ode rotation matrix | |
int | contains (char **list, int len, const char *str) |
returns the index+1 if the list contains the given string or 0 if not | |
void | showParams (const ConfigList &configs) |
shows all parameters of all given configurable objects | |
void | changeParams (ConfigList &configs) |
offers the possibility to change parameter of all configurable objects | |
void | createNewDir (const char *base, char *newdir) |
creates a new directory with the stem base, which is not yet there (using subsequent numbers) | |
void | moveCamera (CameraType camType, OdeRobot &robot) |
void | moveBehindRobot (OdeRobot &robot) |
void | moveOnRobot (OdeRobot &robot) |
void | printMode (CameraType camType) |
EXCEPTION_TEMPLATE (IndexOutOfBoundsException) | |
EXCEPTION_TEMPLATE (InvalidArgumentException) | |
EXCEPTION_TEMPLATE (DimensionMismatchException) | |
Matrix | osgMatrix2Matrixlib (const osg::Matrix &m) |
converts osg matrix to matrix of matrixlib | |
osg::Matrix | rotationMatrixFromAxisX (const Axis &axis) |
returns a Rotation matrix that rotates the x-axis along with the given axis. | |
osg::Matrix | rotationMatrixFromAxisZ (const Axis &axis) |
returns a Rotation matrix that rotates the z-axis along with the given axis. | |
double | getAngle (const osg::Vec3 &a, const osg::Vec3 &b) |
returns the angle between two vectors (in rad) | |
Position | multMatrixPosition (const Matrix &r, Position &p) |
Matrix | getRotationMatrix (const double &angle) |
returns a rotation matrix with the given angle | |
Matrix | getTranslationMatrix (const Position &p) |
returns a translation matrix with the given Position | |
Matrix | removeTranslationInMatrix (const Matrix &pose) |
Matrix | removeRotationInMatrix (const Matrix &pose) |
double | getAngle (Position a, Position b) |
returns the angle between two vectors | |
template<typename T> | |
T | clip (T v, T minimum, T maximum) |
template<typename T> | |
T | abs (T v) |
template<typename T> | |
T | normalize360 (T v) |
Position | multMatrixPosition (const matrix::Matrix &r, Position &p) |
Multiplies 3x3 matrix with position. | |
matrix::Matrix | removeTranslationInMatrix (const matrix::Matrix &pose) |
removes the translation in the matrix | |
matrix::Matrix | removeRotationInMatrix (const matrix::Matrix &pose) |
removes the rotation in the matrix | |
template<typename T> | |
Vector< T > | solve (const TriDiagonalMatrix< T > &r_mat, const Vector< T > &r_vector) |
solve |
|
Definition at line 95 of file component.h. |
|
Definition at line 96 of file component.h. |
|
|
|
Definition at line 87 of file component.h. |
|
Definition at line 58 of file globaldata.h. |
|
|
|
|
|
Data structure holding all essential global information.
|
|
Definition at line 55 of file globaldata.h. |
|
Definition at line 59 of file globaldata.h. |
|
Definition at line 91 of file component.h. |
|
Definition at line 92 of file component.h. |
|
Definition at line 98 of file component.h. |
|
|
|
Definition at line 99 of file muscledarm.h. |
|
Definition at line 83 of file muscledarm.h. |
|
Definition at line 78 of file mathutils.h. |
|
offers the possibility to change parameter of all configurable objects
Definition at line 782 of file simulation.cpp. |
|
Definition at line 74 of file mathutils.h. |
|
returns the index+1 if the list contains the given string or 0 if not
Definition at line 760 of file simulation.cpp. |
|
creates a new directory with the stem base, which is not yet there (using subsequent numbers)
Definition at line 802 of file simulation.cpp. |
|
|
|
|
|
|
|
returns the angle between two vectors
Definition at line 159 of file mathutils.cpp. |
|
returns the angle between two vectors (in rad)
Definition at line 95 of file mathutils.cpp. |
|
Definition at line 329 of file osgprimitive.cpp. |
|
returns a rotation matrix with the given angle
Definition at line 115 of file mathutils.cpp. |
|
returns a translation matrix with the given Position
Definition at line 126 of file mathutils.cpp. |
|
|
|
|
|
|
|
Multiplies 3x3 matrix with position.
|
|
Definition at line 105 of file mathutils.cpp. |
|
Definition at line 82 of file mathutils.h. |
|
converts the rotation component of pose into an ode rotation matrix
Definition at line 95 of file primitive.cpp. |
|
converts osg matrix to matrix of matrixlib
Definition at line 64 of file mathutils.cpp. |
|
converts a position vector and a rotation matrix from ode to osg 4x4 matrix
Definition at line 87 of file primitive.cpp. |
|
returns the osg (4x4) pose matrix of the ode body
Definition at line 82 of file primitive.cpp. |
|
returns the osg (4x4) pose matrix of the ode geom
Definition at line 77 of file primitive.cpp. |
|
|
|
removes the rotation in the matrix
|
|
Definition at line 149 of file mathutils.cpp. |
|
removes the translation in the matrix
|
|
Definition at line 137 of file mathutils.cpp. |
|
returns a Rotation matrix that rotates the x-axis along with the given axis. The other 2 axis (y,z) are ambiguous. Definition at line 79 of file mathutils.cpp. |
|
returns a Rotation matrix that rotates the z-axis along with the given axis. The other 2 axis (x,y) are ambiguous. Definition at line 87 of file mathutils.cpp. |
|
shows all parameters of all given configurable objects
Definition at line 775 of file simulation.cpp. |
|
solve special solve function for tridiagonal matrices status: tested! (high chance that this function yields correct results) Definition at line 288 of file matrices.h. |