#include <VirtualCameraNodelet.hpp>
Public Member Functions | |
void | loop (const ros::TimerEvent &event) |
void | newCameraCallback (AddRealCameraConstPtr cam) |
virtual void | onInit () |
Private Member Functions | |
void | addRealCamerasFromParams () |
std::string | getNameFromTopic (const std::string &topic) |
void | handleNewCameraParams (const VirtualCameraParametersPtr ¶ms) |
VirtualCameraParametersPtr | handleStartupParameters () |
void | registerCamerasFromWaitList () |
Private Attributes | |
ros::Subscriber | addCameraSubscriber |
std::list< RealCameraPtr > | addWaitList |
VirtualCameraPtr | camera |
ros::Publisher | cameraInfoPublisher |
MutexPtr | imageSyncMutex |
boost::shared_ptr < image_transport::ImageTransport > | it |
std::string | name |
ros::NodeHandle | nh |
std::vector< ros::Subscriber > | realCamInfoSubs |
RealCameraSynchronizerPtr | synchronizer |
ros::Timer | timer |
boost::shared_ptr < tf::TransformListener > | transformListener |
ros::Subscriber | virtCamParamsSubscriber |
The main class of this package. it needs to have the following parameters on the Parameter server available when the nodelet is initialized: name - name of the camera. Used in the topics it produces and frames it creates approxDistance - distance of lookat points of this camera viewportWidth - number of horizontal points viewportHeight - number of vertical points parentFrameId - id of the frame the frame of this camera is placed in posX - x position of the camera in the parent frame posY - y position of the camera in the parent frame posZ - z position of the camera in the parent frame pan - pan of the camera in degrees. Positive corresponds to looking left. tilt - tilt of the camera in degrees. Positive corresponds to looking up. horizontalFov - Field of view in horizontal direction in degrees. verticalFov - Field of view in vertical direction in degrees. frameRate - interval for updating the images in seconds. encoding - encoding of the resulting image (bgr8, mono8). model - Camera model. Possible values: pinhole, cylindric, spherical. If the value is invalid then the pinhole camera model is used. synchronize - whether to compose images only when the source timestamps are the same
Via the next parameters you initialize the virtual camera with its sources (real cameras, but can be anything that has camera like interface). The parameters are ordered in the ascending order. Index starts from 1. If the next index is not found no other sources are loaded. realCameraTopic1 - path to the topic the source publishes on. Path is relative to the nodelet manager. This name is just a mask. It can be sourceTopic1, sourceTopic2 etc.. realCameraFrame1 - (optional) Name of the corresponding tf frame to the source specified in the previous parameter. If not specified the same rules as in AddRealCamera.msg are applied.
Definition at line 67 of file VirtualCameraNodelet.hpp.
void virtual_camera::VirtualCameraNodelet::addRealCamerasFromParams | ( | ) | [private] |
Loads needed information for real cameras from parameter server.
Definition at line 38 of file VirtualCameraNodelet.cpp.
std::string virtual_camera::VirtualCameraNodelet::getNameFromTopic | ( | const std::string & | topic | ) | [private] |
Gets the camera name from the topic string.
std::string | topic |
Definition at line 70 of file VirtualCameraNodelet.cpp.
void virtual_camera::VirtualCameraNodelet::handleNewCameraParams | ( | const VirtualCameraParametersPtr & | params | ) | [private] |
Basically a hook before new virtual camera parameters arrive. Most of the job is delegated to the VirtualCamera object but there may be some work that needs to be done at this level.
Definition at line 31 of file VirtualCameraNodelet.cpp.
VirtualCameraParametersPtr virtual_camera::VirtualCameraNodelet::handleStartupParameters | ( | ) | [private] |
Creates the parameters object which is passed to the VirtualCamera. Data are obtained from the parameter server.
Definition at line 5 of file VirtualCameraNodelet.cpp.
void virtual_camera::VirtualCameraNodelet::loop | ( | const ros::TimerEvent & | event | ) |
Message loop of this nodelet
const | ros::TimerEvent& event |
Definition at line 79 of file VirtualCameraNodelet.cpp.
Callback for adding new camera via the message. Creates new RealCamera instance and registers it everywhere it is needed.
AddRealCameraConstPtr | cam |
Definition at line 94 of file VirtualCameraNodelet.cpp.
void virtual_camera::VirtualCameraNodelet::onInit | ( | ) | [virtual] |
The startup point of this nodelet
Definition at line 113 of file VirtualCameraNodelet.cpp.
void virtual_camera::VirtualCameraNodelet::registerCamerasFromWaitList | ( | ) | [private] |
Takes cameras from the addWaitList and tries to register them to the virtual camera.
Definition at line 53 of file VirtualCameraNodelet.cpp.
ros::Subscriber virtual_camera::VirtualCameraNodelet::addCameraSubscriber [private] |
Definition at line 76 of file VirtualCameraNodelet.hpp.
std::list<RealCameraPtr> virtual_camera::VirtualCameraNodelet::addWaitList [private] |
Cameras need some time to generate their tf trees and also receive camera info before they are added to the virtual camera.
Definition at line 86 of file VirtualCameraNodelet.hpp.
Definition at line 72 of file VirtualCameraNodelet.hpp.
ros::Publisher virtual_camera::VirtualCameraNodelet::cameraInfoPublisher [private] |
Definition at line 73 of file VirtualCameraNodelet.hpp.
Definition at line 79 of file VirtualCameraNodelet.hpp.
boost::shared_ptr<image_transport::ImageTransport> virtual_camera::VirtualCameraNodelet::it [private] |
Definition at line 70 of file VirtualCameraNodelet.hpp.
std::string virtual_camera::VirtualCameraNodelet::name [private] |
Definition at line 71 of file VirtualCameraNodelet.hpp.
ros::NodeHandle virtual_camera::VirtualCameraNodelet::nh [private] |
Definition at line 69 of file VirtualCameraNodelet.hpp.
std::vector<ros::Subscriber> virtual_camera::VirtualCameraNodelet::realCamInfoSubs [private] |
Definition at line 77 of file VirtualCameraNodelet.hpp.
Definition at line 78 of file VirtualCameraNodelet.hpp.
ros::Timer virtual_camera::VirtualCameraNodelet::timer [private] |
Definition at line 74 of file VirtualCameraNodelet.hpp.
boost::shared_ptr<tf::TransformListener> virtual_camera::VirtualCameraNodelet::transformListener [private] |
Definition at line 80 of file VirtualCameraNodelet.hpp.
ros::Subscriber virtual_camera::VirtualCameraNodelet::virtCamParamsSubscriber [private] |
Definition at line 75 of file VirtualCameraNodelet.hpp.