All Classes Namespaces Files Functions Variables Typedefs Defines
Public Member Functions | Static Public Attributes
virtual_camera::RealCamera Class Reference

#include <RealCamera.hpp>

Inheritance diagram for virtual_camera::RealCamera:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual TableP2ConstPtr getCachedPositions ()=0
virtual
sensor_msgs::CameraInfoConstPtr 
getCameraInfo ()=0
virtual sensor_msgs::ImageConstPtr getImage ()=0
virtual float getWeight (int row, int col)=0
virtual bool isReady ()=0
virtual void setCameraInfo (const sensor_msgs::CameraInfoConstPtr &camInfo)=0
virtual void setPointsCache (std::string frame, const TableV3Ptr &points)=0
virtual void updateImage (const sensor_msgs::ImageConstPtr &image)=0
virtual bool validateCache ()=0
virtual ~RealCamera ()

Static Public Attributes

static const int NOT_VISIBLE = -1

Detailed Description

Interface for all real cameras. These cameras encapsulate the cameras that physically exist in the system. They are able to provide data about points in space that are observable from these real cameras.

Author:
Jan Brabec

Definition at line 30 of file RealCamera.hpp.


Constructor & Destructor Documentation

virtual virtual_camera::RealCamera::~RealCamera ( ) [inline, virtual]

Definition at line 39 of file RealCamera.hpp.


Member Function Documentation

Via setPointsCache() you can precompute positions you are interested in. Via this function you can get the results.

Returns:
TableP2ConstPtr Table with 2D coordinates in the camera image. If the camera can not see the specific point then its coordinates are assigned the NOT_VISIBLE constant.

Implemented in virtual_camera::RealMonoCamera.

virtual sensor_msgs::CameraInfoConstPtr virtual_camera::RealCamera::getCameraInfo ( ) [pure virtual]
Returns:
sensor_msgs::CameraInfoConstPtr

Implements virtual_camera::Camera.

Implemented in virtual_camera::RealMonoCamera.

virtual sensor_msgs::ImageConstPtr virtual_camera::RealCamera::getImage ( ) [pure virtual]
Returns:
sensor_msgs::ImageConstPtr pointer to the current image.

Implemented in virtual_camera::RealMonoCamera.

virtual float virtual_camera::RealCamera::getWeight ( int  row,
int  col 
) [pure virtual]

Weights the position so that position near the center of the camera has higher weight than those near edges.

Parameters:
introw index in the position cache
intcol index in the position cache
Returns:
float number in interval <0;1>

Implemented in virtual_camera::RealMonoCamera.

virtual bool virtual_camera::RealCamera::isReady ( ) [pure virtual]
Returns:
bool true if the camera has received CameraInfo and Image at least once;

Implemented in virtual_camera::RealMonoCamera.

virtual void virtual_camera::RealCamera::setCameraInfo ( const sensor_msgs::CameraInfoConstPtr &  camInfo) [pure virtual]

Updates the cameras configuration via the camera info. const sensor_msgs::CameraInfoConstPtr & camInfo

Implemented in virtual_camera::RealMonoCamera.

virtual void virtual_camera::RealCamera::setPointsCache ( std::string  frame,
const TableV3Ptr points 
) [pure virtual]

Passes precomputed points in the specified frame to the camera. The camera is then able to precompute lookup table with projections of those points onto the image plane.

Parameters:
std::stringframe tf frame where the points are located const TableV3Ptr & points

Implemented in virtual_camera::RealMonoCamera.

virtual void virtual_camera::RealCamera::updateImage ( const sensor_msgs::ImageConstPtr &  image) [pure virtual]

Immediately updates this cameras image.

Parameters:
constsensor_msgs::ImageConstPtr & image

Implemented in virtual_camera::RealMonoCamera.

virtual bool virtual_camera::RealCamera::validateCache ( ) [pure virtual]

Validates the cache of this camera so it is up to date.

Returns:
true if the cache was valid before this call, false otherwise.

Implemented in virtual_camera::RealMonoCamera.


Member Data Documentation

const int virtual_camera::RealCamera::NOT_VISIBLE = -1 [static]

Cached positions that are not seen by the camera are assigned this value.

Definition at line 36 of file RealCamera.hpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Defines


virtual_camera
Author(s): Jan Brabec; maintained by Tomas Petricek / petrito1@cmp.felk.cvut
autogenerated on Tue Dec 10 2013 14:58:12