Public Member Functions | Protected Member Functions | Protected Attributes
CameraHandler Class Reference

#include <CameraHandler.h>

Inheritance diagram for CameraHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 CameraHandler ()
bool endOfSimulation ()
unsigned int getObjectType () const
void handleSimulation ()
void synchronize ()
 ~CameraHandler ()

Protected Member Functions

void _initialize ()
void computeCameraInfo ()
bool setCameraInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res)

Protected Attributes

double _acquisitionFrequency
sensor_msgs::CameraInfo _camera_info
bool _cameraHasDepth
bool _cameraIsFloat
bool _cameraIsRGB
image_transport::ImageTransport _it
simFloat _lastPublishedImageTime
image_transport::Publisher _pubDepth
image_transport::CameraPublisher _pubIT
ros::ServiceServer _service

Detailed Description

Definition at line 11 of file CameraHandler.h.


Constructor & Destructor Documentation

Definition at line 15 of file CameraHandler.cpp.

Definition at line 24 of file CameraHandler.cpp.


Member Function Documentation

void CameraHandler::_initialize ( ) [protected, virtual]

Implements GenericObjectHandler.

Definition at line 272 of file CameraHandler.cpp.

void CameraHandler::computeCameraInfo ( ) [protected]

Helping method to compute camera information message.

Definition at line 196 of file CameraHandler.cpp.

bool CameraHandler::endOfSimulation ( ) [virtual]

Reimplemented from GenericObjectHandler.

Definition at line 355 of file CameraHandler.cpp.

unsigned int CameraHandler::getObjectType ( ) const [virtual]

Implements GenericObjectHandler.

Definition at line 27 of file CameraHandler.cpp.

void CameraHandler::handleSimulation ( ) [virtual]

Implements GenericObjectHandler.

Definition at line 37 of file CameraHandler.cpp.

bool CameraHandler::setCameraInfo ( sensor_msgs::SetCameraInfo::Request &  req,
sensor_msgs::SetCameraInfo::Response &  res 
) [protected]

Service handler for setting camera parameters from ros.

Parameters:
reqThe desired camera parameters.
resres.success is true if the parameters have been set properly, false otherwise. Some more information may be contained in res.status_message.
Returns:
Same as res.success

Definition at line 233 of file CameraHandler.cpp.

void CameraHandler::synchronize ( ) [virtual]

Reimplemented from GenericObjectHandler.

Definition at line 31 of file CameraHandler.cpp.


Member Data Documentation

Camera frequency

Definition at line 76 of file CameraHandler.h.

sensor_msgs::CameraInfo CameraHandler::_camera_info [protected]

Preconstructed msg containing camera information.

Definition at line 61 of file CameraHandler.h.

Camera has depth sensor

Definition at line 85 of file CameraHandler.h.

Camera image is published as a 32 bit float

Definition at line 90 of file CameraHandler.h.

bool CameraHandler::_cameraIsRGB [protected]

Camera is RGB or not

Definition at line 80 of file CameraHandler.h.

We create an ImageTransport instance.

Definition at line 46 of file CameraHandler.h.

Time of the last published image.

Definition at line 71 of file CameraHandler.h.

Publisher for depth maps.

Definition at line 56 of file CameraHandler.h.

Publisher for camera images.

Definition at line 51 of file CameraHandler.h.

Ros service server for setting camera parameters from ros.

Definition at line 95 of file CameraHandler.h.


The documentation for this class was generated from the following files:


camera_handler
Author(s): Riccardo Spica , Giovanni Claudio
autogenerated on Mon Apr 3 2017 04:03:44