Public Types | Public Member Functions | Public Attributes | Private Attributes
PmdcameraDriver Class Reference

IRI ROS Specific Driver Class. More...

#include <pmdcamera_driver.h>

Inheritance diagram for PmdcameraDriver:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
iri_pmdcamera::PmdcameraConfig 
Config
 define config type

Public Member Functions

bool closeDriver (void)
 close driver
void config_update (const Config &new_cfg, uint32_t level=0)
 config update
bool openDriver (void)
 open driver
 PmdcameraDriver ()
 constructor
bool startDriver (void)
 start driver
bool stopDriver (void)
 stop driver
 ~PmdcameraDriver ()
 Destructor.
void readData ()
 getters from low level driver
float * get3DImage (bool &is_dense)
float * getFlagsImage ()
float * getIntensityImage ()
float * getAmplitudeImage ()
float * getRangeImage ()
float * getDepthImage ()
int getWidth ()
int getHeight ()
void setCameraType (pmd_camera::cameraType cameraType_)
void setIntegrationTime (int int_time)
void setModulationFrequency (int mod_freq)

Public Attributes

Config config_
 config variable

Private Attributes

pmd_camera::cameraType cameraType_
int int_time_
int mod_freq_
pmd_camera::PmdCamera PmdCC_

Detailed Description

IRI ROS Specific Driver Class.

This class inherits from the IRI Base class IriBaseDriver, which provides the guidelines to implement any specific driver. The IriBaseDriver class offers an easy framework to integrate functional drivers implemented in C++ with the ROS driver structure. ROS driver_base state transitions are already managed by IriBaseDriver.

The PmdcameraDriver class must implement all specific driver requirements to safetely open, close, run and stop the driver at any time. It also must guarantee an accessible interface for all driver's parameters.

The PmdcameraConfig.cfg needs to be filled up with those parameters suitable to be changed dynamically by the ROS dyanmic reconfigure application. The implementation of the CIriNode class will manage those parameters through methods like postNodeOpenHook() and reconfigureNodeHook().

Definition at line 52 of file pmdcamera_driver.h.


Member Typedef Documentation

typedef iri_pmdcamera::PmdcameraConfig PmdcameraDriver::Config

define config type

Define a Config type with the PmdcameraConfig. All driver implementations will then use the same variable type Config.

Definition at line 68 of file pmdcamera_driver.h.


Constructor & Destructor Documentation

constructor

In this constructor parameters related to the specific driver can be initalized. Those parameters can be also set in the openDriver() function. Attributes from the main node driver class IriBaseDriver such as loop_rate, may be also overload here.

Definition at line 4 of file pmdcamera_driver.cpp.

Destructor.

This destructor is called when the object is about to be destroyed.

Definition at line 76 of file pmdcamera_driver.cpp.


Member Function Documentation

bool PmdcameraDriver::closeDriver ( void  ) [virtual]

close driver

In this function, the driver must be closed. Variables related to the driver state must also be taken into account. This function is automatically called by IriBaseDriver::doClose(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 16 of file pmdcamera_driver.cpp.

void PmdcameraDriver::config_update ( const Config new_cfg,
uint32_t  level = 0 
)

config update

In this function the driver parameters must be updated with the input config variable. Then the new configuration state will be stored in the Config attribute.

Parameters:
new_cfgthe new driver configuration state
levellevel in which the update is taken place

Definition at line 50 of file pmdcamera_driver.cpp.

float * PmdcameraDriver::get3DImage ( bool is_dense)

Definition at line 95 of file pmdcamera_driver.cpp.

Definition at line 110 of file pmdcamera_driver.cpp.

Definition at line 120 of file pmdcamera_driver.cpp.

Definition at line 100 of file pmdcamera_driver.cpp.

Definition at line 130 of file pmdcamera_driver.cpp.

Definition at line 105 of file pmdcamera_driver.cpp.

Definition at line 115 of file pmdcamera_driver.cpp.

Definition at line 125 of file pmdcamera_driver.cpp.

bool PmdcameraDriver::openDriver ( void  ) [virtual]

open driver

In this function, the driver must be openned. Openning errors must be taken into account. This function is automatically called by IriBaseDriver::doOpen(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 9 of file pmdcamera_driver.cpp.

getters from low level driver

Actualize data and retreive images image is in float pointer form. Driver_node is where it is converted into ros form

Definition at line 83 of file pmdcamera_driver.cpp.

void PmdcameraDriver::setCameraType ( pmd_camera::cameraType  cameraType_)

two cameras are supported from the low level driver

Definition at line 135 of file pmdcamera_driver.cpp.

void PmdcameraDriver::setIntegrationTime ( int  int_time)

Definition at line 140 of file pmdcamera_driver.cpp.

Definition at line 145 of file pmdcamera_driver.cpp.

bool PmdcameraDriver::startDriver ( void  ) [virtual]

start driver

After this function, the driver and its thread will be started. The driver and related variables should be properly setup. This function is automatically called by IriBaseDriver::doStart(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 21 of file pmdcamera_driver.cpp.

bool PmdcameraDriver::stopDriver ( void  ) [virtual]

stop driver

After this function, the driver's thread will stop its execution. The driver and related variables should be properly setup. This function is automatically called by IriBaseDriver::doStop(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 43 of file pmdcamera_driver.cpp.


Member Data Documentation

pmd_camera::cameraType PmdcameraDriver::cameraType_ [private]

Definition at line 57 of file pmdcamera_driver.h.

config variable

This variable has all the driver parameters defined in the cfg config file. Is updated everytime function config_update() is called.

Definition at line 76 of file pmdcamera_driver.h.

Definition at line 58 of file pmdcamera_driver.h.

Definition at line 59 of file pmdcamera_driver.h.

pmd_camera::PmdCamera PmdcameraDriver::PmdCC_ [private]

Definition at line 56 of file pmdcamera_driver.h.


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


iri_pmdcamera
Author(s): Guillem Alenya - IRI Robotics Lab
autogenerated on Fri Dec 6 2013 20:10:05