#include <RealMonoCamera.hpp>
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 |
Basic implementation of the RealCamera interface
Definition at line 16 of file RealMonoCamera.hpp.
virtual_camera::RealMonoCamera::RealMonoCamera | ( | std::string | name, |
const boost::shared_ptr< tf::TransformListener > & | listener | ||
) |
std:string | name name of this camera in the system. The tf frame should be named like this and the topics too. |
const | boost::shared_ptr<tf::TransformListener> listener instance of listener for this camera can use |
Definition at line 7 of file RealMonoCamera.cpp.
void virtual_camera::RealMonoCamera::applyPlumbBobDistortion | ( | tf::Vector3 & | p | ) | [private] |
Applies distortion on the point in the camera frame. Uses the plumb bob distortion model
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.
void virtual_camera::RealMonoCamera::buildInnerCache | ( | ) | [private] |
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.
Implements virtual_camera::RealCamera.
Definition at line 73 of file RealMonoCamera.cpp.
sensor_msgs::CameraInfoConstPtr virtual_camera::RealMonoCamera::getCameraInfo | ( | ) | [virtual] |
Implements virtual_camera::RealCamera.
Definition at line 25 of file RealMonoCamera.cpp.
sensor_msgs::ImageConstPtr virtual_camera::RealMonoCamera::getImage | ( | ) | [virtual] |
Implements virtual_camera::RealCamera.
Definition at line 78 of file RealMonoCamera.cpp.
std::string virtual_camera::RealMonoCamera::getName | ( | ) | [virtual] |
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.
int | row index in the position cache |
int | col index in the position cache |
Implements virtual_camera::RealCamera.
Definition at line 83 of file RealMonoCamera.cpp.
bool virtual_camera::RealMonoCamera::isReady | ( | ) | [virtual] |
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
int | row row in the requestPoints |
int | col 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.
std::string | frame 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.
const | sensor_msgs::ImageConstPtr & image |
Implements virtual_camera::RealCamera.
Definition at line 38 of file RealMonoCamera.cpp.
bool virtual_camera::RealMonoCamera::validateCache | ( | ) | [virtual] |
Validates the cache of this camera so it is up to date.
Implements virtual_camera::RealCamera.
Definition at line 50 of file RealMonoCamera.cpp.
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.
std::string virtual_camera::RealMonoCamera::requestFrame [private] |
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.