#include <GeneralVirtualCamera.hpp>
Public Member Functions | |
bool | addRealCamera (const RealCameraPtr &realCamera) |
GeneralVirtualCamera (const std::string &name, const VirtualCameraParametersPtr ¶ms) | |
sensor_msgs::ImageConstPtr | generateImage () |
sensor_msgs::CameraInfoConstPtr | getCameraInfo () |
double | getFrameRate () |
std::string | getName () |
bool | removeRealCamera (const RealCameraPtr &realCamera) |
void | updateVirtualCameraParameters (const VirtualCameraParametersPtr ¶ms) |
Private Member Functions | |
void | broadcast () |
cv_bridge::CvImagePtr | createEmptyImage () |
void | updateCachesIfNeeded () |
void | updateCameraInfo () |
void | updateCameraModel (const std::string &indentifier) |
void | updateExternalParameters (const VirtualCameraParametersPtr ¶ms) |
void | updateInternalParameters (const VirtualCameraParametersPtr ¶ms) |
Private Attributes | |
tf::TransformBroadcaster | broadcaster |
ImageComposerPtr | composer |
bool | composerCacheFlag |
std::vector< double > | Dci |
double | hFovRad |
bool | isValidCameraInfo |
boost::array< double, 9 > | Kci |
boost::array< double, 9 > | Kci0 |
CameraModelPtr | model |
std::string | name |
VirtualCameraParametersPtr | parameters |
boost::array< double, 12 > | Pci |
boost::array< double, 12 > | Pci0 |
TableV3Ptr | pointCloud |
boost::array< double, 9 > | Rci |
boost::array< double, 9 > | Rci0 |
RealCameraPtrListPtr | realCameras |
int | seqId |
tf::Transform | transform |
bool | updatePointCloudFlag |
double | vFovRad |
The implementation of the VirtualCamera interface. The camera model is determined in runtime.
Definition at line 30 of file GeneralVirtualCamera.hpp.
virtual_camera::GeneralVirtualCamera::GeneralVirtualCamera | ( | const std::string & | name, |
const VirtualCameraParametersPtr & | params | ||
) |
const | std::string & name Camera name has to be unique id in the tf tree. The frame of this camera will have this name. |
const | VirtualCameraParametersPtr & params initialization parameters |
Definition at line 8 of file GeneralVirtualCamera.cpp.
bool virtual_camera::GeneralVirtualCamera::addRealCamera | ( | const RealCameraPtr & | realCamera | ) | [virtual] |
Adds new RealCamera to the set this camera gets information from.
const | RealCameraPtr & realCamera |
Implements virtual_camera::VirtualCamera.
Definition at line 55 of file GeneralVirtualCamera.cpp.
void virtual_camera::GeneralVirtualCamera::broadcast | ( | ) | [private] |
Definition at line 173 of file GeneralVirtualCamera.cpp.
cv_bridge::CvImagePtr virtual_camera::GeneralVirtualCamera::createEmptyImage | ( | ) | [private] |
Definition at line 135 of file GeneralVirtualCamera.cpp.
sensor_msgs::ImageConstPtr virtual_camera::GeneralVirtualCamera::generateImage | ( | ) | [virtual] |
Creates new image from this camera right at the time this function is called. Thanks to caching a lot of information is calculated only if the positions of this cameras frame and the real cameras frames change.
Implements virtual_camera::VirtualCamera.
Definition at line 45 of file GeneralVirtualCamera.cpp.
sensor_msgs::CameraInfoConstPtr virtual_camera::GeneralVirtualCamera::getCameraInfo | ( | ) | [virtual] |
Gets the cameras CameraInfo which contains the fundamental information about the camera.
Implements virtual_camera::Camera.
Definition at line 30 of file GeneralVirtualCamera.cpp.
double virtual_camera::GeneralVirtualCamera::getFrameRate | ( | ) | [virtual] |
Gets the frame rate of this camera in Hz. Know that it's just a number this camera got from some kind of setter. The camera itself doesn't implement any loop and therefore doesn't generate any images automatically. You can use this number to implement this loop.
Implements virtual_camera::VirtualCamera.
Definition at line 84 of file GeneralVirtualCamera.cpp.
std::string virtual_camera::GeneralVirtualCamera::getName | ( | ) | [virtual] |
Implements virtual_camera::Camera.
Definition at line 89 of file GeneralVirtualCamera.cpp.
bool virtual_camera::GeneralVirtualCamera::removeRealCamera | ( | const RealCameraPtr & | realCamera | ) | [virtual] |
Removes RealCamera from the set this camera gets information from.
const | RealCameraPtr & realCamera |
Implements virtual_camera::VirtualCamera.
Definition at line 70 of file GeneralVirtualCamera.cpp.
void virtual_camera::GeneralVirtualCamera::updateCachesIfNeeded | ( | ) | [private] |
Definition at line 154 of file GeneralVirtualCamera.cpp.
void virtual_camera::GeneralVirtualCamera::updateCameraInfo | ( | ) | [private] |
Definition at line 179 of file GeneralVirtualCamera.cpp.
void virtual_camera::GeneralVirtualCamera::updateCameraModel | ( | const std::string & | indentifier | ) | [private] |
Definition at line 117 of file GeneralVirtualCamera.cpp.
void virtual_camera::GeneralVirtualCamera::updateExternalParameters | ( | const VirtualCameraParametersPtr & | params | ) | [private] |
Definition at line 97 of file GeneralVirtualCamera.cpp.
void virtual_camera::GeneralVirtualCamera::updateInternalParameters | ( | const VirtualCameraParametersPtr & | params | ) | [private] |
Definition at line 106 of file GeneralVirtualCamera.cpp.
void virtual_camera::GeneralVirtualCamera::updateVirtualCameraParameters | ( | const VirtualCameraParametersPtr & | params | ) | [virtual] |
Immediately updates the parameters of the virtual camera using the message object.
const | VirtualCameraParametersPtr & params |
Implements virtual_camera::VirtualCamera.
Definition at line 76 of file GeneralVirtualCamera.cpp.
tf::TransformBroadcaster virtual_camera::GeneralVirtualCamera::broadcaster [private] |
Definition at line 37 of file GeneralVirtualCamera.hpp.
Definition at line 39 of file GeneralVirtualCamera.hpp.
bool virtual_camera::GeneralVirtualCamera::composerCacheFlag [private] |
Set to true if composer needs to update cache in the generateImage
Definition at line 51 of file GeneralVirtualCamera.hpp.
std::vector<double> virtual_camera::GeneralVirtualCamera::Dci [private] |
Definition at line 35 of file GeneralVirtualCamera.hpp.
double virtual_camera::GeneralVirtualCamera::hFovRad [private] |
Horizontal FOV in radians
Definition at line 46 of file GeneralVirtualCamera.hpp.
bool virtual_camera::GeneralVirtualCamera::isValidCameraInfo [private] |
Definition at line 36 of file GeneralVirtualCamera.hpp.
boost::array<double, 9> virtual_camera::GeneralVirtualCamera::Kci [private] |
Definition at line 33 of file GeneralVirtualCamera.hpp.
boost::array<double, 9> virtual_camera::GeneralVirtualCamera::Kci0 [private] |
Definition at line 33 of file GeneralVirtualCamera.hpp.
Definition at line 40 of file GeneralVirtualCamera.hpp.
std::string virtual_camera::GeneralVirtualCamera::name [private] |
Definition at line 44 of file GeneralVirtualCamera.hpp.
Definition at line 43 of file GeneralVirtualCamera.hpp.
boost::array<double, 12> virtual_camera::GeneralVirtualCamera::Pci [private] |
Definition at line 34 of file GeneralVirtualCamera.hpp.
boost::array<double, 12> virtual_camera::GeneralVirtualCamera::Pci0 [private] |
Definition at line 34 of file GeneralVirtualCamera.hpp.
Definition at line 41 of file GeneralVirtualCamera.hpp.
boost::array<double, 9> virtual_camera::GeneralVirtualCamera::Rci [private] |
Definition at line 32 of file GeneralVirtualCamera.hpp.
boost::array<double, 9> virtual_camera::GeneralVirtualCamera::Rci0 [private] |
Definition at line 32 of file GeneralVirtualCamera.hpp.
Definition at line 42 of file GeneralVirtualCamera.hpp.
int virtual_camera::GeneralVirtualCamera::seqId [private] |
Definition at line 49 of file GeneralVirtualCamera.hpp.
tf::Transform virtual_camera::GeneralVirtualCamera::transform [private] |
Definition at line 38 of file GeneralVirtualCamera.hpp.
bool virtual_camera::GeneralVirtualCamera::updatePointCloudFlag [private] |
Set to true if the point cache needs to be updated in the generateImage
Definition at line 53 of file GeneralVirtualCamera.hpp.
double virtual_camera::GeneralVirtualCamera::vFovRad [private] |
Vertical FOV in radians
Definition at line 48 of file GeneralVirtualCamera.hpp.