lpzrobots Namespace Reference

forward declarations More...

Classes

class  TrackablePrimitive
class  TraceDrawer
class  OdeAgent
 Specialised agent for ode robots. More...
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  DummyMotor
class  Motor
 Abstact base class for attachable motors. More...
class  OneAxisServo
 general servo motor to achieve position control More...
class  OneAxisServoCentered
 general servo motor to achieve position control with zero position centered More...
class  OneAxisServoVel
 general servo motor to achieve position control. More...
class  PID
class  Speaker
 This "motor" emulates a speaker or piezo element to produce sound. More...
class  Spring
class  TwoAxisServo
 general servo motor for 2 axis joints More...
class  TwoAxisServoCentered
 general servo motor for 2 axis joints with zero position centered More...
class  TwoAxisServoVel
 general servo motor to achieve position control for 2 axis joints that internally controls the velocity of the motor (much more stable) with centered zero position. More...
class  AbstractGround
class  AbstractObstacle
 Abstract class (interface) for obstacles. More...
class  Boxpile
 Boxpile. More...
class  ClosedPlayground
class  PolyLine
class  ComplexPlayground
 Playground that uses an xfig file with polylines linetype 0 is normal wall linetype 1 is border thickness is used as well, thickness is multiplied with wallthickness. More...
class  DummyGround
 DummyGround which holds a DummyPrimitive (so getMainPrimitive() works). More...
class  DummyObstacle
 DummyObstacle which holds a DummyPrimitive (so getMainPrimitive() works). More...
class  MeshGround
class  MeshObstacle
class  OctaPlayground
class  PassiveBox
 (Passive) box as obstacle More...
class  PassiveCapsule
 (Passive) capsule as obstacle More...
class  PassiveMesh
 (Passive) mesh as obstacle More...
class  PassiveSphere
 (Passive) sphere as obstacle More...
class  Playground
struct  RandomObstaclesConf
class  RandomObstacles
 Passive random obstacles: with spawn and remove obstacles can be created and removed. More...
class  Seesaw
 Seesaw. More...
class  TerrainGround
 Class provides an terrain based on HeightFields. More...
class  OdeConfig
 The class $name holds the configurable parameters of the simulation environment. More...
class  MoveEarthySkyWithEyePointTransform
class  Base
class  BoundingShape
 class for reading bounding shape description files (.bbox) and to create appropriate geoms More...
class  CameraManipulator
 CameraManipulator is a MatrixManipulator which provides a flying camera 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...
struct  Indices
struct  Vertex
class  HeightField
 Height field primitive. More...
class  HUDStatisticsManager
 manages all the stuff displaying statistics on the graphics window. More...
class  Joint
class  OneAxisJoint
class  TwoAxisJoint
class  FixedJoint
class  HingeJoint
class  Hinge2Joint
class  UniversalJoint
class  BallJoint
class  SliderJoint
class  LpzHelpHandler
 Event handler for adding on screen help to Viewers. More...
class  LPZViewer
 Viewer holds a single view on to a single scene that supports the rendering of offscreen RRT (render to texture) cameras at any time (without sync). More...
class  MotionBlurOperation
 a class that enables motion blur for the scenegraph should be called in the main simulation loop More...
class  MotionBlurDrawCallback
 a class that enables motion blur for the scenegraph should be called in the main simulation loop More...
class  OSGHeightField
 Graphical HeightField. More...
class  TextureDescr
 holds texture file and repeat information. More...
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  OSGBoxTex
 Graphical box with Textures. 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  OSGText
 Text to be displayed on the hud. 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  Cylinder
 Cylinder primitive. More...
class  Ray
 Ray primitive The actual visual representation can have different length than the ray object. More...
class  Mesh
 Mesh 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...
class  RobotCameraManager
 Manages camera sensors. More...
struct  AnisotropFrictionData
class  Substance
 Physical substance definition, used for collision detection/treatment What we need is mu, slip and kp,kd parameter for the collision Definition of substance parameters: More...
class  DebugSubstance
class  AddSensors2RobotAdapter
 Robot adapter to add sensors and also motors to robots without the need to modify the robot itself. More...
struct  AmosIIConf
class  AmosII
struct  ArmConf
class  Arm
struct  Arm2SegmConf
class  Arm2Segm
class  Barrel2Masses
 A barrel-like robot with 2 internal masses, which can slide on their orthogonal axes. More...
class  Barrel2Masses2nd
 A barrel-like robot with 2 internal masses, which can slide on their orthogonal axes. More...
class  CaterPillar
 This is a class, which models a snake like robot. More...
struct  CaterPillarConf
class  DefaultCaterPillar
 This is a class, which models a snake like robot. More...
struct  DiscusConf
 configuration object for the Discus robot. More...
class  Discus
 A spherical robot with 3 internal masses, which can slide on their orthogonal axes. More...
class  ForcedSphereConf
class  ForcedSphere
class  Formel1
 Robot that looks like a Nimm 2 Bonbon :-) 4 wheels and a capsule like body. More...
struct  FourWheeledConf
class  FourWheeled
 Robot is based on nimm4 with 4 wheels and a capsule like body. More...
struct  HandConf
class  Hand
 Artificial Hand. More...
struct  HexapodConf
struct  Leg
class  Hexapod
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 Wheelorder: front left, front right, rear left, rear right. More...
class  OdeRobot
 Abstract class for ODE robots. More...
class  PlattfussSchlange
 This is a class, which models a snake like robot with flat ends and a big body in the middle. More...
class  PrimitiveComponent
 Component consisting of one Primitive. More...
class  ReplayRobot
struct  RobotChainConf
class  RobotChain
 Chain of 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  SkeletonConf
class  Skeleton
 should look like a humanoid More...
struct  SliderWheelieConf
class  SliderWheelie
 This is a class, which models an annular robot. More...
struct  SphererobotConf
class  Sphererobot
 This is a class, which models a snake like robot. More...
struct  Sphererobot3MassesConf
 configuration object for the Sphererobot3Masses robot. More...
class  Sphererobot3Masses
 A spherical robot with 3 internal masses, which can slide on their orthogonal axes. More...
class  TruckMesh
 Robot that looks like a Nimm 2 Bonbon :-) 4 wheels and a truck mesh like body. More...
struct  TwoWheeledConf
class  TwoWheeled
 Robot is based on nimm2 with a camera installed. More...
struct  UwoConf
class  Uwo
 UWO: Unknown Walk Object :-), looks like a plate with a lot of legs. More...
struct  VierBeinerConf
class  VierBeiner
 robot that should look like a dog More...
class  AxisOrientationSensor
 Class for sensing the axis orienation of a primitive (robot). More...
struct  CameraConf
class  Camera
 A Robot Camera. More...
class  CameraSensor
 Class to connect a Camera as a sensor to a robot. More...
class  DirectCameraSensor
 This CameraSensor implements a direct conversion from pixels to sensors. More...
struct  PositionCameraSensorConf
class  PositionCameraSensor
 This CameraSensor calculates the position of the visible object(s) that is essentially the center of gravity of the image. More...
struct  MotionCameraSensorConf
class  MotionCameraSensor
 This CameraSensor calculates the global optical flow of the camera image using the center of gravity method. More...
class  ContactSensor
 Class for a contact sensor. More...
struct  ImageProcessor
 Base class for image processing units. More...
struct  StdImageProcessor
 Standard image processor - convenience class for 1 to 1 image processing. More...
struct  BWImageProcessor
 black and white image More...
struct  HSVImgProc
 converts the image to a HSV coded image More...
struct  ColorFilterImgProc
 filters for a specific color (requires HSV, so use HSVImgProc before) More...
struct  LineImgProc
 creates a lightsensitive sensorline. More...
struct  AvgImgProc
 time average of image More...
class  IRSensor
 Class for IR sensors. More...
struct  OpticalFlowConf
 configuration object for OpticalFlow More...
class  OpticalFlow
 This CameraSensor calculates the optical flow at few points of the image based on a box matching technique. More...
class  RaySensor
 Abstract class for Ray-based sensors. More...
class  RaySensorBank
 Class for a bank (collection) of ray sensors. More...
class  RelativePositionSensor
 Class for relative position sensing. More...
class  Sensor
 Abstract class for sensors that can be plugged into a robot. More...
class  SoundSensor
 Sound sensor with possible direction and frequency detection and also distance dependence (Not implemented yet) This works, but is not very well tested and documented. More...
class  SpeedSensor
 Class for speed sensing of robots. More...
class  TorqueSensor
 Class for sensing the torque that are applied the joint by a motor. More...
class  Simulation
class  Axis
class  CameraHandle
 Class which holds all data used by CameraManipulators. More...
class  Color
struct  print_func
class  ColorSchema
 A store for colors with a set of aliases. More...
struct  COMMAND
class  IException
class  GlobalData
 Data structure holding all essential global information. More...
class  VideoStream
struct  GripperConf
 Configure object for Gripper. More...
class  Gripper
 A gripper can be attached to a primitive via its substance and implements gripping (a fixed joint) on collision with specified objects. More...
struct  geomPairHash
class  OdeHandle
 Data structure for accessing the ODE. More...
class  Operator
class  LimitOrientationOperator
 An Operator for limiting the orientation of the main primitive of a robot. More...
struct  LiftUpOperatorConf
class  LiftUpOperator
 An Operator for lifting up a robot from time to time. More...
class  PullToPointOperator
 An Operator for pulling the main primitive of a robot towards a point. More...
class  BoxRingOperator
 An Operator for keeping robots within a sphere / box. More...
struct  OsgConfig
 Data structure containing some configuration variables for OSG. More...
struct  OsgScene
 Data structure containing the scene notes (e.g. More...
class  OsgHandle
 Data structure for accessing the OpenSceneGraph. More...
class  Pos
class  SimulationTask
struct  SimulationTaskHandle
 struct which holds all structural data for the simulations. More...
class  SimulationTaskSupervisor
class  Sound
 Object that represents a sound signal in the simulator. More...
class  TaskedSimulation
class  TaskedSimulationCreator
 Defines a method to construct a TaskedSimulation. More...
class  TmpObject
 this is the base-class for objects that exist temporarily like some indicator of manipulation are a message More...
class  TmpPrimitive
 holding a temporary primitive More...
class  TmpDisplayItem
 holding a temporary graphical item More...
class  TmpJoint
 holding a temporary joint More...

Typedefs

typedef std::list< PlotOptionPlotOptionList
typedef std::list< Operator * > OperatorList
typedef std::list< TraceDrawerTraceDrawerList
typedef OneAxisServo SliderServo
typedef OneAxisServo HingeServo
typedef OneAxisServo Hinge2Servo
typedef TwoAxisServo UniversalServo
typedef int(* CollisionCallback )(dSurfaceParameters &params, GlobalData &globaldata, void *userdata, dContact *contacts, int numContacts, dGeomID o1, dGeomID o2, const Substance &s1, const Substance &s2)
 function to be called at a collision event between the two geoms.
typedef struct lpzrobots::Bumper Bumper
typedef std::vector< Primitive * > Primitives
typedef std::vector
< ImageProcessor * > 
ImageProcessors
typedef bool(* commandfunc_t )(GlobalData &globalData, char *, char *)
typedef std::list< std::string > ParameterList
typedef std::vector
< AbstractObstacle * > 
ObstacleList
typedef
Configurable::configurableList 
ConfigList
typedef BackCallerVector
< OdeAgent * > 
OdeAgentList
typedef std::list< SoundSoundList
typedef std::multimap< double,
TmpObject * > 
TmpObjectMap
typedef std::list< std::pair
< double, TmpObject * > > 
TmpObjectList
typedef std::vector< Gripper * > GripperList
typedef osg::Matrix Pose

Enumerations

enum  ODEAMOTORAXISREF { GlobalFrame = 0, FirstBody = 1, SecondBody = 2 }
enum  parts {
  base, shoulder1, shoulder2, upperArm,
  foreArm, hand, base, upperArm,
  lowerArm, mainMuscle11, mainMuscle12, mainMuscle21,
  mainMuscle22, smallMuscle11, smallMuscle12, smallMuscle21,
  smallMuscle22, smallMuscle31, smallMuscle32, smallMuscle41,
  smallMuscle42, hand, NUMParts
}
enum  Motor_type { With_servo_motor, Without_servo_motor }
enum  IrSensor_Type { irDrawAll, irBack, irSide, irFront }
enum  GripMode { lateral, precision }
enum  parts {
  base, shoulder1, shoulder2, upperArm,
  foreArm, hand, 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,
  FJ_lAH, NUMJoints
}

Functions

void printCornerPointsXY (Box *box, FILE *f)
ref_ptr< Material > getMaterial (const Color &c, Material::ColorMode mode=Material::DIFFUSE)
osg::Geode * createRectangle (const OsgHandle &, const osg::Vec3 &v1, const osg::Vec3 &v2, const osg::Vec3 &v3, double repeatOnR, double repeatOnS)
void addTexture (Geode *geode, const TextureDescr &tex)
Geode * test ()
Pose osgPose (dGeomID geom)
 returns the osg (4x4) pose matrix of the ode geom
Pose osgPose (dBodyID body)
 returns the osg (4x4) pose matrix of the ode body
Pose osgPose (const double *position, const double *rotation)
 converts a position vector and a rotation matrix from ode to osg 4x4 matrix
void odeRotation (const Pose &pose, dMatrix3 &odematrix)
 converts the rotation component of pose into an ode rotation matrix
int dummyCallBack (dSurfaceParameters &params, GlobalData &globaldata, void *userdata, dContact *contacts, int numContacts, dGeomID o1, dGeomID o2, const Substance &s1, const Substance &s2)
static int anisocallback (dSurfaceParameters &params, GlobalData &globaldata, void *userdata, dContact *contacts, int numContacts, dGeomID o1, dGeomID o2, const Substance &s1, const Substance &s2)
int contactCollCallback (dSurfaceParameters &params, GlobalData &globaldata, void *userdata, dContact *contacts, int numContacts, dGeomID o1, dGeomID o2, const Substance &s1, const Substance &s2)
int irCollCallback (dSurfaceParameters &params, GlobalData &globaldata, void *userdata, dContact *contacts, int numContacts, dGeomID o1, dGeomID o2, const Substance &s1, const Substance &s2)
static void * odeStep_run (void *p)
 redirection function, because we can't call member function direct
static void * osgStep_run (void *p)
 redirection function, because we can't call member function direct
static void printODEMessage (int num, const char *msg, va_list ap)
void createNewDir (const char *base, char *newdir)
 creates a new directory with the stem base, which is not yet there (using subsequent numbers) and returns its name in newdir
bool com_list (GlobalData &globalData, char *, char *)
bool com_show (GlobalData &globalData, char *, char *)
bool com_store (GlobalData &globalData, char *, char *)
bool com_load (GlobalData &globalData, char *, char *)
bool com_storecfg (GlobalData &globalData, char *, char *)
bool com_loadcfg (GlobalData &globalData, char *, char *)
bool com_contrs (GlobalData &globalData, char *, char *)
bool com_set (GlobalData &globalData, char *, char *)
bool com_help (GlobalData &globalData, char *, char *)
bool com_quit (GlobalData &globalData, char *, char *)
char * stripwhite (char *string)
COMMANDfind_command (char *name)
bool execute_line (GlobalData &globalData, char *line)
int valid_argument (const char *caller, const char *arg)
void printConfigs (const ConfigList &configs)
void printConfig (const Configurable *config)
char * dupstr (const char *s)
char * dupstrpluseq (const char *s)
vector< string > splitstring (string s)
bool handleConsole (GlobalData &globalData)
 offers a console interface the possibility to change parameter of all configurable objects in globalData storeing and restoreing of controllers .
char * command_generator (const char *, int)
char * params_generator (const char *, int)
char ** console_completion (const char *, int, int)
void initializeConsole ()
 should be called at the start
void closeConsole ()
 should be called at the end (to store history)
int getListLen (char **strings)
 EXCEPTION_TEMPLATE (IndexOutOfBoundsException)
 EXCEPTION_TEMPLATE (InvalidArgumentException)
 EXCEPTION_TEMPLATE (DimensionMismatchException)
osg::Matrix osgRotate (const double &alpha, const double &beta, const double &gamma)
 returns a rotation matrix (osg) with the given angles alpha, beta and gamma
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)
matrix::Matrix odeRto3x3RotationMatrixT (const double R[12])
 converts an ode rotation matrix into a 3x3 rotation matrix (matrixlib)
matrix::Matrix odeRto3x3RotationMatrix (const double R[12])
 converts an ode rotation matrix into a 3x3 rotation matrix (matrixlib)
Position multMatrixPosition (const matrix::Matrix &r, Position &p)
 Multiplies 3x3 matrix with position.
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::Matrix &pose)
 removes the translation in the matrix
Matrix removeRotationInMatrix (const matrix::Matrix &pose)
 removes the rotation in the matrix
double getAngle (Position a, Position b)
 returns the angle between two vectors
template<typename T >
normalize360 (T v)

Variables

char fragmentShaderSource_noBaseTexture []
char fragmentShaderSource_withBaseTexture []
int globalNumVelocityViolations = 0
 counts number of max velocity violations at joints (Attention, this is a global variable, initialized to 0 at start)
int t = 1
int c = 1
static FILE * ODEMessageFile = 0
COMMAND commands []
ParameterList parameters

Detailed Description

forward declarations

read the installation PREFIX (to find data directory)

Namespace for the 3D robot simulator ode_robots


Typedef Documentation

typedef struct lpzrobots::Bumper Bumper
typedef int(* CollisionCallback)(dSurfaceParameters &params, GlobalData &globaldata, void *userdata, dContact *contacts, int numContacts, dGeomID o1, dGeomID o2, const Substance &s1, const Substance &s2)

function to be called at a collision event between the two geoms.

Parameters:
params surface parameter, which should be changed/calculated by this function
globaldata global information
userdata pointer to user data for this callback (stored in substance)
contacts array of contact information
numContacts length of contact information array
o1 geom corresponding to substance of this callback
o2 other geom
s1 substance of this callback
s2 other substance
Returns:
0 if collision should not be treated; 1 if collision should be treated otherwise (by other callback or standard methods); 2 if collision to be treated and parameters for collision are set in params
typedef bool(* commandfunc_t)(GlobalData &globalData, char *, char *)
typedef std::vector<Gripper*> GripperList
typedef std::vector<ImageProcessor* > ImageProcessors
typedef std::vector<AbstractObstacle*> ObstacleList
typedef std::list<Operator*> OperatorList
typedef std::list<std::string> ParameterList
typedef std::list< PlotOption > PlotOptionList
typedef osg::Matrix Pose
typedef std::vector<Primitive*> Primitives
typedef std::list<Sound> SoundList
typedef std::list< std::pair<double, TmpObject*> > TmpObjectList
typedef std::multimap<double, TmpObject* > TmpObjectMap
typedef std::list<TraceDrawer> TraceDrawerList

Enumeration Type Documentation

enum GripMode
Enumerator:
lateral 
precision 
Enumerator:
irDrawAll 
irBack 
irSide 
irFront 
enum joints
Enumerator:
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 
FJ_lAH 
NUMJoints 
enum Motor_type
Enumerator:
With_servo_motor 
Without_servo_motor 
Enumerator:
GlobalFrame 
FirstBody 
SecondBody 
enum parts
Enumerator:
base 
shoulder1 
shoulder2 
upperArm 
foreArm 
hand 
base 
upperArm 
lowerArm 
mainMuscle11 
mainMuscle12 
mainMuscle21 
mainMuscle22 
smallMuscle11 
smallMuscle12 
smallMuscle21 
smallMuscle22 
smallMuscle31 
smallMuscle32 
smallMuscle41 
smallMuscle42 
hand 
NUMParts 
enum parts
Enumerator:
base 
shoulder1 
shoulder2 
upperArm 
foreArm 
hand 
base 
upperArm 
lowerArm 
mainMuscle11 
mainMuscle12 
mainMuscle21 
mainMuscle22 
smallMuscle11 
smallMuscle12 
smallMuscle21 
smallMuscle22 
smallMuscle31 
smallMuscle32 
smallMuscle41 
smallMuscle42 
hand 
NUMParts 

Function Documentation

void addTexture ( Geode *  geode,
const TextureDescr &  tex 
)
static int lpzrobots::anisocallback ( dSurfaceParameters &  params,
GlobalData &  globaldata,
void *  userdata,
dContact *  contacts,
int  numContacts,
dGeomID  o1,
dGeomID  o2,
const Substance &  s1,
const Substance &  s2 
) [static]
void closeConsole (  ) 

should be called at the end (to store history)

bool com_contrs ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_help ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_list ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_load ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_loadcfg ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_quit ( GlobalData &  globalData,
char *  ,
char *   
)
bool com_set ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_show ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_store ( GlobalData &  globalData,
char *  line,
char *  arg 
)
bool com_storecfg ( GlobalData &  globalData,
char *  line,
char *  arg 
)
char * command_generator ( const char *  text,
int  state 
)
char ** console_completion ( const char *  text,
int  start,
int  end 
)
int lpzrobots::contactCollCallback ( dSurfaceParameters &  params,
GlobalData &  globaldata,
void *  userdata,
dContact *  contacts,
int  numContacts,
dGeomID  o1,
dGeomID  o2,
const Substance &  s1,
const Substance &  s2 
)
void createNewDir ( const char *  base,
char *  newdir 
)

creates a new directory with the stem base, which is not yet there (using subsequent numbers) and returns its name in newdir

osg::Geode * createRectangle ( const OsgHandle &  osgHandle,
const osg::Vec3 v1,
const osg::Vec3 v2,
const osg::Vec3 v3,
double  repeatOnR,
double  repeatOnS 
)
int lpzrobots::dummyCallBack ( dSurfaceParameters &  params,
GlobalData &  globaldata,
void *  userdata,
dContact *  contacts,
int  numContacts,
dGeomID  o1,
dGeomID  o2,
const Substance &  s1,
const Substance &  s2 
)
char* lpzrobots::dupstr ( const char *  s  ) 
char* lpzrobots::dupstrpluseq ( const char *  s  ) 
lpzrobots::EXCEPTION_TEMPLATE ( DimensionMismatchException   ) 
lpzrobots::EXCEPTION_TEMPLATE ( InvalidArgumentException   ) 
lpzrobots::EXCEPTION_TEMPLATE ( IndexOutOfBoundsException   ) 
bool execute_line ( GlobalData &  globalData,
char *  line 
)
COMMAND * find_command ( char *  name  ) 
double getAngle ( Position  a,
Position  b 
)

returns the angle between two vectors

double getAngle ( const osg::Vec3 a,
const osg::Vec3 b 
)

returns the angle between two vectors (in rad)

int lpzrobots::getListLen ( char **  strings  ) 
ref_ptr< Material > getMaterial ( const Color &  c,
Material::ColorMode  mode = Material::DIFFUSE 
)
matrix::Matrix getRotationMatrix ( const double &  angle  ) 

returns a rotation matrix with the given angle

matrix::Matrix getTranslationMatrix ( const Position p  ) 

returns a translation matrix with the given Position

bool handleConsole ( GlobalData &  globalData  ) 

offers a console interface the possibility to change parameter of all configurable objects in globalData storeing and restoreing of controllers .

.. also informs agents about changes

Returns:
false if program should exit
void initializeConsole (  ) 

should be called at the start

int lpzrobots::irCollCallback ( dSurfaceParameters &  params,
GlobalData &  globaldata,
void *  userdata,
dContact *  contacts,
int  numContacts,
dGeomID  o1,
dGeomID  o2,
const Substance &  s1,
const Substance &  s2 
)
Position multMatrixPosition ( const Matrix &  r,
Position p 
)

Multiplies 3x3 matrix with position.

T lpzrobots::normalize360 ( v  )  [inline]
void odeRotation ( const Pose &  pose,
dMatrix3 &  odematrix 
)

converts the rotation component of pose into an ode rotation matrix

matrix::Matrix odeRto3x3RotationMatrix ( const double  R[12]  ) 

converts an ode rotation matrix into a 3x3 rotation matrix (matrixlib)

matrix::Matrix odeRto3x3RotationMatrixT ( const double  R[12]  ) 

converts an ode rotation matrix into a 3x3 rotation matrix (matrixlib)

static void * odeStep_run ( void *  p  )  [static]

redirection function, because we can't call member function direct

matrix::Matrix osgMatrix2Matrixlib ( const osg::Matrix m  ) 

converts osg matrix to matrix of matrixlib

Pose osgPose ( const double *  V,
const double *  R 
)

converts a position vector and a rotation matrix from ode to osg 4x4 matrix

Pose osgPose ( dBodyID  body  ) 

returns the osg (4x4) pose matrix of the ode body

Pose osgPose ( dGeomID  geom  ) 

returns the osg (4x4) pose matrix of the ode geom

osg::Matrix osgRotate ( const double &  alpha,
const double &  beta,
const double &  gamma 
)

returns a rotation matrix (osg) with the given angles alpha, beta and gamma

static void * osgStep_run ( void *  p  )  [static]

redirection function, because we can't call member function direct

char * params_generator ( const char *  text,
int  state 
)
void lpzrobots::printConfig ( const Configurable config  ) 
void printConfigs ( const ConfigList configs  ) 
void lpzrobots::printCornerPointsXY ( Box *  box,
FILE *  f 
)
static void printODEMessage ( int  num,
const char *  msg,
va_list  ap 
) [static]
matrix::Matrix removeRotationInMatrix ( const Matrix &  pose  ) 

removes the rotation in the matrix

matrix::Matrix removeTranslationInMatrix ( const Matrix &  pose  ) 

removes the translation in the matrix

osg::Matrix rotationMatrixFromAxisX ( const Axis &  axis  ) 

returns a Rotation matrix that rotates the x-axis along with the given axis.

The other 2 axis (y,z) are ambiguous.

osg::Matrix rotationMatrixFromAxisZ ( const Axis &  axis  ) 

returns a Rotation matrix that rotates the z-axis along with the given axis.

The other 2 axis (x,y) are ambiguous.

vector<string> lpzrobots::splitstring ( string  s  ) 
char * stripwhite ( char *  string  ) 
Geode* lpzrobots::test (  ) 
int valid_argument ( const char *  caller,
const char *  arg 
)

Variable Documentation

int c = 1
Initial value:
 {
  { "param=val",  com_set, "sets PARAM of all objects to VAL" },
  { "help", com_help, "Display this text" },
  { "?",     com_help, "Synonym for `help'" },
  { "list", com_list, "Lists all configurables and agents" },
  { "ls",   com_list, "Synonym for `list'" },
  { "set",  com_set, "syntax: set [OBJECTID] PARAM=VAL; sets parameter of OBJECTID (or of all objects) to value" },
  { "store", com_store, "stores object. Syntax: store AGENTID FILE, see list" },
  { "load", com_load, "loads object. Syntax: load AGENTID FILE, see list" },
  { "storecfg", com_storecfg, "Store key-values pairs. Syntax: storecfg CONFIGID FILE" },
  { "loadcfg", com_loadcfg, "Load key-values pairs. Syntax: CONFIGID FILE" },
  { "contrs", com_contrs, "Stores the contours of all playgrounds to FILE" },
  { "show", com_show, "[OBJECTID]: Lists parameters of OBJECTID or of all objects (if no id given)" },
  { "view", com_show, "Synonym for `show'" },
  { "quit", com_quit, "Quit program" },
  { (char *)NULL, (commandfunc_t)NULL, (char *)NULL }
}
Initial value:
  "uniform sampler2DShadow shadowTexture; \n"
  "uniform vec2 ambientBias; \n"
  "\n"
  "void main(void) \n"
  "{ \n"
  "    ambientBias.x=0.8f; \n"
  "    ambientBias.y=0.4f; \n"
  "    gl_FragColor = gl_Color * (ambientBias.x + shadow2DProj( shadowTexture, gl_TexCoord[0] ) * ambientBias.y - 0.4f); \n"
  "}\n"
Initial value:
  "uniform sampler2D baseTexture; \n"
  "uniform sampler2DShadow shadowTexture; \n"
  "uniform vec2 ambientBias; \n"
  "\n"
  "void main(void) \n"
  "{ \n"
  "    vec4 color = gl_Color* texture2D( baseTexture, gl_TexCoord[0].xy ); \n"
  "    gl_FragColor = color * (ambientBias.x + shadow2DProj( shadowTexture, gl_TexCoord[1])  * ambientBias.y); \n"
  "}\n"

counts number of max velocity violations at joints (Attention, this is a global variable, initialized to 0 at start)

FILE* ODEMessageFile = 0 [static]
int t = 1
Generated on Thu Jun 28 14:48:38 2012 for Robot Simulator of the Robotics Group for Self-Organization of Control by  doxygen 1.6.3