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
IRSensor Class Reference

Class for IR sensors. More...

#include <irsensor.h>

Inheritance diagram for IRSensor:
Collaboration diagram for IRSensor:

Public Member Functions

 IRSensor (double exponent=1, double size=0.05, double range=2, rayDrawMode drawMode=drawSensor)
 
virtual bool sense (const GlobalData &globaldata) override
 performs sense action More...
 
virtual int get (sensor *sensors, int length) const override
 writes the sensor values (usually in the range [-1,1] ) into the given sensor array and returns the number of sensors written. More...
 
virtual std::list< sensorgetList () const override
 returns a list of sensor values (usually in the range [-1,1] ) This function should be overloaded. More...
 
virtual double getValue ()
 
virtual double getExponent () const
 returns the exponent of the sensor characteritic (default: 1 (linear)) More...
 
virtual void setExponent (double exp)
 sets the exponent of the sensor characteritic (default: 1 (linear)) More...
 
- Public Member Functions inherited from RaySensor
 RaySensor ()
 
 RaySensor (double size, double range, rayDrawMode drawMode)
 
 ~RaySensor ()
 
virtual RaySensorclone () const
 Create a copy of this without initialization. More...
 
void setPose (const osg::Matrix &pose) override
 changes the relative pose of the sensor More...
 
void init (Primitive *own, Joint *joint=0) override
 initialises sensor with a body of robot and optionally with a joint. More...
 
bool sense (const GlobalData &globaldata) override
 performs sense action More...
 
int get (sensor *sensors, int length) const override
 writes the sensor values (usually in the range [-1,1] ) into the given sensor array and returns the number of sensors written. More...
 
std::list< sensorgetList () const override
 returns a list of sensor values (usually in the range [-1,1] ) This function should be overloaded. More...
 
virtual int getSensorNumber () const override
 returns the number of sensors values produced by this sensor More...
 
virtual void update () override
 to update any visual appearance More...
 
virtual void setRange (double range)
 Set maximum range of ray. More...
 
virtual void setDrawMode (rayDrawMode drawMode)
 Set draw mode of ray. More...
 
void setLength (double len, long int time)
 Set length of ray (needed for callback) More...
 
- Public Member Functions inherited from PhysicalSensor
 PhysicalSensor ()
 
virtual ~PhysicalSensor ()
 
virtual void setInitData (const OdeHandle &odeHandle, const OsgHandle &osgHandle, const osg::Matrix &pose)
 sets the initial data structures More...
 
virtual osg::Matrix getPose ()
 relative pose of the sensor More...
 
- Public Member Functions inherited from Sensor
 Sensor ()
 
virtual ~Sensor ()
 
virtual std::list
< SensorMotorInfo
getSensorInfos () const
 returns a list of sensor infos ( More...
 
std::list< sensorgetListOfArray () const
 helper function for performance implementation of list<> get() based on array-get More...
 
- Public Member Functions inherited from SensorMotorInfoAble
 SensorMotorInfoAble ()
 
void setBaseName (const std::string &basename)
 
void setBaseInfo (const SensorMotorInfo &baseinfo)
 
SensorMotorInfo getBaseInfo ()
 
void setNamingFunc (const NamingFunction &func)
 
NamingFunction getNamingFunc () const
 
void setNames (const std::vector< std::string > &names)
 set names explicitly (basename is anyway suffixed) More...
 
std::string getName (int index) const
 returns the name of a single item. Typically called from within Sensor and Motor class. More...
 
std::list< SensorMotorInfogetInfos (int number) const
 get all infos. More...
 

Protected Member Functions

virtual double characteritic (double len)
 describes the sensor characteritic An exponential curve is used. More...
 
- Protected Member Functions inherited from RaySensor
void defaultInit ()
 

Protected Attributes

double exponent
 
double value
 
- Protected Attributes inherited from RaySensor
double size
 
double range
 
rayDrawMode drawMode
 
double len
 
double lastlen
 
double detection
 
long lasttimeasked
 
OSGCylindersensorBody
 
Transformtransform
 
Rayray
 
bool initialised
 
- Protected Attributes inherited from PhysicalSensor
OdeHandle odeHandle
 
OsgHandle osgHandle
 
osg::Matrix pose
 
bool isInitDataSet
 
- Protected Attributes inherited from SensorMotorInfoAble
NamingFunction func
 
SensorMotorInfo baseinfo
 

Additional Inherited Members

- Public Types inherited from RaySensor
enum  rayDrawMode { drawNothing, drawRay, drawSensor, drawAll }
 
- Public Types inherited from Sensor
enum  Dimensions {
  X = 1, Y = 2, Z = 4, XY = X | Y,
  XZ = X | Z, YZ = Y | Z, XYZ = X | Y | Z
}
 defines which dimensions should be sensed. The meaning is sensor specific. More...
 
- Public Types inherited from SensorMotorInfoAble
typedef std::function
< std::string(int)> 
NamingFunction
 function that returns the name given the index More...
 
- Static Public Member Functions inherited from Sensor
static std::list< sensorselectrows (const matrix::Matrix &m, short dimensions)
 selects the rows specified by dimensions (X->0, Y->1, Z->2) More...
 
static int selectrows (sensor *sensors, int length, const matrix::Matrix &m, short dimensions)
 selects the rows specified by dimensions (X->0, Y->1, Z->2) More...
 
static Dimensions parseSensorDimension (char *str)
 
static std::string dimensions2String (short dimensions)
 
- Static Public Member Functions inherited from SensorMotorInfoAble
static std::string defaultNameing (int index)
 the default implementation is for index==0: basename, otherwise basename + (index+1) More...
 

Detailed Description

Class for IR sensors.

IR sensors are based on distance measurements using the ODE geom class Ray. The sensor value is obtained by collisions, which are handled by the simulation environement. The information of a collision comes to the sensor via the collision callback of the substance used for the ray (actually for the transform). If no collision is detected the value should be zero, so that a stamp is used. The length measured in this way is modified by the 'characteristic' of the IR sensor

Constructor & Destructor Documentation

IRSensor ( double  exponent = 1,
double  size = 0.05,
double  range = 2,
rayDrawMode  drawMode = drawSensor 
)
Parameters
exponentexponent of the sensor characteritic (default: 1 (linear))
sizesize of sensor in simulation
rangemaximum range of the IR sensor
drawModedraw mode of the sensor

Member Function Documentation

double characteritic ( double  len)
protectedvirtual

describes the sensor characteritic An exponential curve is used.

See Also
setExponent()
int get ( sensor sensors,
int  length 
) const
overridevirtual

writes the sensor values (usually in the range [-1,1] ) into the given sensor array and returns the number of sensors written.

A default implementation based on get() is provided. Only if performance matters overwrite this function.

Parameters
sensorscall by refernce array which received the values
lengthcapacity of sensors array
Returns
number of sensor values written

Reimplemented from Sensor.

virtual double getExponent ( ) const
inlinevirtual

returns the exponent of the sensor characteritic (default: 1 (linear))

std::list< sensor > getList ( ) const
overridevirtual

returns a list of sensor values (usually in the range [-1,1] ) This function should be overloaded.

If performance matters, implement get(double*, int) and use getListOfArray to implement this.

Implements Sensor.

double getValue ( )
virtual
bool sense ( const GlobalData globaldata)
overridevirtual

performs sense action

Implements Sensor.

virtual void setExponent ( double  exp)
inlinevirtual

sets the exponent of the sensor characteritic (default: 1 (linear))

Member Data Documentation

double exponent
protected
double value
protected

The documentation for this class was generated from the following files: