Main Page   Class Hierarchy   Alphabetical List   Compound List   Compound Members  

propertyservice::camera::CameraServer Class Reference

#include <CameraServer.h>

Inheritance diagram for propertyservice::camera::CameraServer:

propertyservice::PropertyServer propertyservice::PropertyControl List of all members.

Detailed Description

CameraServer is a class for implementing a property service for a camera resource.

A camera resource represents any single camera or a stereo camera. In a stereo camera, all properties but the location are same for both (or all) cameras. If cameras are to be controlled individually, a property service for each needs to be created.

The standard properties supported by a camera server are as follows:
Global Properties
Property NameRead/
Write
Data TypeExplanation
typerstringThe type of the server. Always "camera" for camera services.
namerstringThe name of the camera.
versionrstringThe version of the camera server software.
propertiesrstringA list of properties known to the camera server.
Camera Properties
Property NameRead/
Write
Data TypeExplanation
camtyperintThe type of the camera. 0 = mono, 1 = stereo, 2 = omni
formatrwFormatThe current image format
format.listrList<Format>A list of possible image formats.
flengthrwdoubleThe focal length of the objective, in millimeters. In some cameras, this is a writable property.
fovrFieldOfViewA two-dimensional vector representing the horizontal and vertical viewing angles of the camera (in radians).
locationrwSensorLocationA six-dimensional vector representing the location of the camera relative to its base. In some cameras, this is a writable property.
chmaskrwintChannel mask. A bit mask representing the channels that need to be sent to the client.
datarBlob<char>The image data.


Public Types

enum  Type { MONO, STEREO, OMNI }
 An enumeration of possible types for a camera.
.
More...



Public Methods

 CameraServer (Type type=MONO)
 Initialize a camera server with default values and the given camera type.

 CameraServer (CORBA::ORB_ptr orb, Type type=MONO)
 Initialize a camera server with a previously created orb and the given camera type.

 CameraServer (string host, string name, Type type=MONO)
 Initialize a camera server and bind it to a name in a naming service.

virtual ~CameraServer ()
virtual void setProperty (const util::List< string > &nameParts, util::Blob< char > value) throw (PropertyException&)
 Default implementation for setProperty as inherited from PropertyServer.

virtual util::Blob< char > * getProperty (const util::List< string > &nameParts) throw (PropertyException&)
 Default implementation for getProperty as inherited from PropertyServer.

virtual string getName () const=0
 Get the name of the camera, e.g.

virtual string getVersion () const=0
 Get the version of the software, e.g.

virtual util::List< string > getProperties ()
 Get a list of recognized properties.

virtual util::Blob< char > * getData (int index)=0
 Get the image data formatted as requested by setFormat.

virtual util::List< FormatgetFormats ()=0
 Get the image formats this camera can produce.

virtual Format getFormat ()
 Get the current image format.

virtual void setFormat (Format format)
 Set the image format.

virtual propertyservice::mobilerobot::SensorLocation getLocation (int index)=0
 Get the position of the camera.

virtual void setLocation (int index, propertyservice::mobilerobot::SensorLocation location)=0
 Set the position of the camera.

virtual double getFocalLength ()=0
 Get the focal length of this camera.

virtual void setFocalLength (double l) throw (InvalidFormatException&)
 Set the focal length of this camera.

virtual FieldOfView getFOV ()=0
 Get the current field of view of this camera.

virtual void setChannelMask (int mask)
 Set the channel mask.

virtual int getChannelMask ()
 Get the current channel mask.


Protected Attributes

int _iChannelMask
 The current channel mask.

Format _format
 The current image format.


Member Enumeration Documentation

enum propertyservice::camera::CameraServer::Type
 

An enumeration of possible types for a camera.
.

  • MONO - a monocular camera
  • STEREO - a binocular (or even trinocular) camera
  • OMNI - a camera with a 360 degrees field of view


Constructor & Destructor Documentation

propertyservice::camera::CameraServer::CameraServer string    host,
string    name,
Type    type = MONO
[inline]
 

Initialize a camera server and bind it to a name in a naming service.

Parameters:
host  the host name (and port) of the naming service
name  the name of the server at the host


Member Function Documentation

virtual util::Blob<char>* propertyservice::camera::CameraServer::getData int    index [pure virtual]
 

Get the image data formatted as requested by setFormat.

A pointer to the image data accompanied with the length of the data are stored into a Blob.

Parameters:
index  the index of the camera whose image data is to be retrieved

virtual propertyservice::mobilerobot::SensorLocation propertyservice::camera::CameraServer::getLocation int    index [pure virtual]
 

Get the position of the camera.

Typically, position is measured relative to a moving base, e.g. a mobile robot.

Parameters:
index  the index of the wanted camera. This is zero for monocular cameras.

virtual string propertyservice::camera::CameraServer::getName   const [pure virtual]
 

Get the name of the camera, e.g.

"YC-02B".

List< string > propertyservice::camera::CameraServer::getProperties   [virtual]
 

Get a list of recognized properties.

The default implementation returns the standard property names (see above). If your implementation adds properties, you need to add them to the returned list.

Blob< char > * propertyservice::camera::CameraServer::getProperty const util::List< string > &    nameParts throw (PropertyException&) [virtual]
 

Default implementation for getProperty as inherited from PropertyServer.

This method parses the given property name parts, and recognizes the standard property names. Subclasses may add whatever properties are needed by overriding this method. If the default behaviour is still needed, one may call CameraServer::getProperty from the overridden method.

Parameters:
nameParts  the property name split into parts
Returns:
the serialized property value(s) in a blob

virtual string propertyservice::camera::CameraServer::getVersion   const [pure virtual]
 

Get the version of the software, e.g.

"1.2".

virtual void propertyservice::camera::CameraServer::setChannelMask int    mask [inline, virtual]
 

Set the channel mask.

Ones in the binary representation of this number represent active channels (i.e. channels that are sent to the client) 1 means channel 0, 2 means channel 1, 5 (=1+4) means channels 0 and 2 and so on. For an illustrative example, setting the channel mask to 6 will request th G and B channels in RGB color space.

virtual void propertyservice::camera::CameraServer::setFocalLength double    l throw (InvalidFormatException&) [inline, virtual]
 

Set the focal length of this camera.

The default implementation does nothing as many cameras have a fixed of manually modifiable focal length.

virtual void propertyservice::camera::CameraServer::setLocation int    index,
propertyservice::mobilerobot::SensorLocation    location
[pure virtual]
 

Set the position of the camera.

Cameras equipped with a pan-tilt unit, for example, are able to move themselves.

Parameters:
index  the index of the wanted camera. This is zero for monocular cameras.
location  a new location for the camera

void propertyservice::camera::CameraServer::setProperty const util::List< string > &    nameParts,
util::Blob< char >    value
throw (PropertyException&) [virtual]
 

Default implementation for setProperty as inherited from PropertyServer.

This method parses the given property name parts, and recognizes the standard property names. Subclasses may add whatever properties are needed by overriding this method. If the default behaviour is still needed, one may call CameraServer::setProperty from the overridden method.

Parameters:
nameParts  the property name split into parts
value  the new value for the property


The documentation for this class was generated from the following files:
Documentation generated on 11.09.2003 with Doxygen.
The documentation is copyrighted material.
Copyright © Topi Mäenpää 2003. All rights reserved.