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.
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 |
sensor * | data |
double | oldsize |
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.
typedef short Values |
combination of ValueTypes
enum ValueTypes |
PositionCameraSensor | ( | Values | values = Position , |
|
Dimensions | dims = XY | |||
) | [inline] |
The camera image should be black and white (e.g.
values | sensor values to compute ( |
dims | dimensions to return the position (X means horizonal, Y vertical) |
virtual ~PositionCameraSensor | ( | ) | [inline, virtual] |
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
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] |
Dimensions dims [protected] |
int num [protected] |
double oldsize [protected] |