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

#include <RealMonoCamera.hpp>

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

List of all members.

Public Member Functions

TableP2ConstPtr getCachedPositions ()
sensor_msgs::CameraInfoConstPtr getCameraInfo ()
virtual sensor_msgs::ImageConstPtr getImage ()
std::string getName ()
float getWeight (int row, int col)
bool isReady ()
 RealMonoCamera (std::string name, const boost::shared_ptr< tf::TransformListener > &listener)
void setCameraInfo (const sensor_msgs::CameraInfoConstPtr &camInfo)
void setPointsCache (std::string frame, const TableV3Ptr &points)
void updateImage (const sensor_msgs::ImageConstPtr &image)
bool validateCache ()

Private Member Functions

void applyPlumbBobDistortion (tf::Vector3 &p)
bool areTransformsEqual (const tf::StampedTransform &t1, const tf::StampedTransform &t2)
void buildInnerCache ()
void mapPointToInnerCache (int row, int col, tf::StampedTransform &transform)

Private Attributes

sensor_msgs::CameraInfoConstPtr camInfo
sensor_msgs::ImageConstPtr image
tf::Matrix3x3 kMat
std::string name
TableP2Ptr positionCache
std::string requestFrame
TableV3Ptr requestPoints
boost::shared_ptr
< tf::TransformListener > 
transformListener
tf::StampedTransform usedTransform

Detailed Description

Basic implementation of the RealCamera interface

Author:
Jan Brabec

Definition at line 16 of file RealMonoCamera.hpp.


Constructor & Destructor Documentation

virtual_camera::RealMonoCamera::RealMonoCamera ( std::string  name,
const boost::shared_ptr< tf::TransformListener > &  listener 
)
Parameters:
std:stringname name of this camera in the system. The tf frame should be named like this and the topics too.
constboost::shared_ptr<tf::TransformListener> listener instance of listener for this camera can use

Definition at line 7 of file RealMonoCamera.cpp.


Member Function Documentation

void virtual_camera::RealMonoCamera::applyPlumbBobDistortion ( tf::Vector3 &  p) [private]

Applies distortion on the point in the camera frame. Uses the plumb bob distortion model

Parameters:
tf::Vector3& p

Definition at line 136 of file RealMonoCamera.cpp.

bool virtual_camera::RealMonoCamera::areTransformsEqual ( const tf::StampedTransform &  t1,
const tf::StampedTransform &  t2 
) [private]

Checks two transforms for equality

Definition at line 157 of file RealMonoCamera.cpp.

Builds the inner cache with data from the requestPoints. Precondition is that the requestPoints is not empty;

Definition at line 97 of file RealMonoCamera.cpp.

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.

Implements virtual_camera::RealCamera.

Definition at line 73 of file RealMonoCamera.cpp.

sensor_msgs::CameraInfoConstPtr virtual_camera::RealMonoCamera::getCameraInfo ( ) [virtual]
Returns:
sensor_msgs::CameraInfoConstPtr

Implements virtual_camera::RealCamera.

Definition at line 25 of file RealMonoCamera.cpp.

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

Implements virtual_camera::RealCamera.

Definition at line 78 of file RealMonoCamera.cpp.

std::string virtual_camera::RealMonoCamera::getName ( ) [virtual]
Returns:
camera's name

Implements virtual_camera::Camera.

Definition at line 68 of file RealMonoCamera.cpp.

float virtual_camera::RealMonoCamera::getWeight ( int  row,
int  col 
) [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>

Implements virtual_camera::RealCamera.

Definition at line 83 of file RealMonoCamera.cpp.

Returns:
bool true if the camera has received CameraInfo and Image at least once;

Implements virtual_camera::RealCamera.

Definition at line 15 of file RealMonoCamera.cpp.

void virtual_camera::RealMonoCamera::mapPointToInnerCache ( int  row,
int  col,
tf::StampedTransform &  transform 
) [private]

Maps point from the requestPoint to the innerCache

Parameters:
introw row in the requestPoints
intcol column in the requestPoints
tf::StampedTransform& transform transform between the requestFrame and this cameras frame

Definition at line 116 of file RealMonoCamera.cpp.

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

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

Implements virtual_camera::RealCamera.

Definition at line 30 of file RealMonoCamera.cpp.

void virtual_camera::RealMonoCamera::setPointsCache ( std::string  frame,
const TableV3Ptr points 
) [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

Implements virtual_camera::RealCamera.

Definition at line 43 of file RealMonoCamera.cpp.

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

Immediately updates this cameras image.

Parameters:
constsensor_msgs::ImageConstPtr & image

Implements virtual_camera::RealCamera.

Definition at line 38 of file RealMonoCamera.cpp.

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

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

Implements virtual_camera::RealCamera.

Definition at line 50 of file RealMonoCamera.cpp.


Member Data Documentation

sensor_msgs::CameraInfoConstPtr virtual_camera::RealMonoCamera::camInfo [private]

Definition at line 28 of file RealMonoCamera.hpp.

sensor_msgs::ImageConstPtr virtual_camera::RealMonoCamera::image [private]

Definition at line 29 of file RealMonoCamera.hpp.

tf::Matrix3x3 virtual_camera::RealMonoCamera::kMat [private]

Definition at line 19 of file RealMonoCamera.hpp.

std::string virtual_camera::RealMonoCamera::name [private]

Definition at line 18 of file RealMonoCamera.hpp.

Contains coordinates of the request points in the image. They are not in int but in float so they can be further interpolated.

Definition at line 26 of file RealMonoCamera.hpp.

Definition at line 27 of file RealMonoCamera.hpp.

Definition at line 21 of file RealMonoCamera.hpp.

boost::shared_ptr<tf::TransformListener> virtual_camera::RealMonoCamera::transformListener [private]

Definition at line 30 of file RealMonoCamera.hpp.

tf::StampedTransform virtual_camera::RealMonoCamera::usedTransform [private]

Definition at line 20 of file RealMonoCamera.hpp.


The documentation for this class was generated from the following files:
 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