PositionCameraSensor Class Reference

This CameraSensor calculates the position of the visible object(s) that is essentially the center of gravity of the image. More...

#include <camerasensors.h>

Inherits lpzrobots::CameraSensor.

Inherited by MotionCameraSensor.

Collaboration diagram for PositionCameraSensor:
Collaboration graph
[legend]

List of all members.

Public Types

enum  ValueTypes { None = 0, Position = 1, Size = 2, SizeChange = 4 }
 

additional sensor values.

More...
typedef short Values
 combination of ValueTypes

Public Member Functions

 PositionCameraSensor (Values values=Position, Dimensions dims=XY)
 The camera image should be black and white (e.g.
virtual ~PositionCameraSensor ()
virtual void intern_init ()
 overload this function to initialized you data structures.
virtual bool sense (const GlobalData &globaldata)
 Performs the calculations.
virtual int getSensorNumber () const
 overload this function and return the number of sensor values
virtual int get (sensor *sensors, int length) const
 overload this function and return the sensor values

Static Public Member Functions

static bool calcImgCOG (const osg::Image *img, double &x, double &y, double &size, int threshold=1)
 calculates the Center of Gravity of an image normalized to -1 to 1

Protected Attributes

int num
Dimensions dims
Values values
sensordata
double oldsize

Detailed Description

This CameraSensor calculates the position of the visible object(s) that is essentially the center of gravity of the image.

The position in normalized to -1 to 1. Probably you want to use an image processor like ColorFilterImgProc before.


Member Typedef Documentation

typedef short Values

combination of ValueTypes


Member Enumeration Documentation

enum ValueTypes

additional sensor values.

Size is the size of the object (only one value, independent of the dimensions

Enumerator:
None 
Position 
Size 
SizeChange 

Constructor & Destructor Documentation

PositionCameraSensor ( Values  values = Position,
Dimensions  dims = XY 
) [inline]

The camera image should be black and white (e.g.

See also:
BWImageProcessor or ColorFilterImgProc)
CameraSensor for further parameter explanation.
Parameters:
values sensor values to compute (
See also:
PositionCameraSensor::ValueTypes)
Parameters:
dims dimensions to return the position (X means horizonal, Y vertical)
virtual ~PositionCameraSensor (  )  [inline, virtual]

Member Function Documentation

static bool calcImgCOG ( const osg::Image *  img,
double &  x,
double &  y,
double &  size,
int  threshold = 1 
) [inline, static]

calculates the Center of Gravity of an image normalized to -1 to 1

Returns:
false if image is image
virtual int get ( sensor sensors,
int  length 
) const [inline, virtual]

overload this function and return the sensor values

Implements CameraSensor.

virtual int getSensorNumber (  )  const [inline, virtual]

overload this function and return the number of sensor values

Implements CameraSensor.

virtual void intern_init (  )  [inline, virtual]

overload this function to initialized you data structures.

Use camera->getImage() to get the image from the camera

Implements CameraSensor.

virtual bool sense ( const GlobalData globaldata  )  [inline, virtual]

Performs the calculations.

Implements CameraSensor.

Reimplemented in MotionCameraSensor.


Member Data Documentation

sensor* data [protected]
Dimensions dims [protected]
int num [protected]
double oldsize [protected]
Values values [protected]

The documentation for this class was generated from the following file:
Generated on Fri Nov 4 10:59:41 2011 for Robot Simulator of the Robotics Group for Self-Organization of Control by  doxygen 1.6.3