Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
PmdcameraDriverNode Class Reference

IRI ROS Specific Driver Class. More...

#include <pmdcamera_driver_node.h>

Inheritance diagram for PmdcameraDriverNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 PmdcameraDriverNode (ros::NodeHandle &nh)
 constructor
 ~PmdcameraDriverNode ()
 Destructor.

Protected Member Functions

void addNodeDiagnostics (void)
 node add diagnostics
void addNodeOpenedTests (void)
 open status driver tests
void addNodeRunningTests (void)
 run status driver tests
void addNodeStoppedTests (void)
 stop status driver tests
void mainNodeThread (void)
 main node thread
void reconfigureNodeHook (int level)
 specific node dynamic reconfigure

Private Member Functions

void assembleAmplitudeImage (float *amplitude)
void assembleDepthImage (float *distance)
void assembleFlagsImage (float *flags)
void assembleIntensityImage (float *intensity)
void assemblePcl2Amp (const float *const coord_3D, const float *const amplitude)
void assemblePcl2Int (const float *const coord_3D, const float *const intensity)
 fills the pointcloud2 with the 3D image data
void assemblePcl2RangeImage (const float *const coord_3D, const float *const range, const float *const amp)
void findMaxAmplitude (const float *amplitude)
void findMaxDepth (const float *distance)
void findMaxIntensity (const float *intensity)
void postNodeOpenHook (void)
 post open hook

Private Attributes

sensor_msgs::CameraInfo camera_info_
 Camera info data.
camera_info_manager::CameraInfoManagercamera_info_manager_
 Camera info manager objects.
std::string camera_info_url_
std::string camera_name_
ros::Publisher cloud_raw_publisher_
int height_
sensor_msgs::Image Image_amp_msg_
image_transport::CameraPublisher image_amp_publisher_
sensor_msgs::Image Image_depth_msg_
image_transport::CameraPublisher image_depth_publisher_
sensor_msgs::Image Image_flags_msg_
image_transport::CameraPublisher image_flags_publisher_
sensor_msgs::Image Image_int_msg_
image_transport::CameraPublisher image_raw_publisher_
 ROS publishers.
image_transport::ImageTransportit_
float max_amplitude_
float max_depth_
float max_intensity_
sensor_msgs::PointCloud2 pcl2_amp_msg_
sensor_msgs::PointCloud2 pcl2_int_msg_
sensor_msgs::PointCloud2 pcl2_range_msg_
ros::Publisher pcl_amp_raw_publisher_
ros::Publisher pcl_int_raw_publisher_
ros::Publisher pcl_range_raw_publisher_
sensor_msgs::PointCloud PointCloud_msg_
int real_height_
int real_width_
int width_

Detailed Description

IRI ROS Specific Driver Class.

This class inherits from the IRI Core class IriBaseNodeDriver<IriBaseDriver>, to provide an execution thread to the driver object. A complete framework with utilites to test the node functionallity or to add diagnostics to specific situations is also given. The inherit template design form allows complete access to any IriBaseDriver object implementation.

As mentioned, tests in the different driver states can be performed through class methods such as addNodeOpenedTests() or addNodeRunningTests(). Tests common to all nodes may be also executed in the pattern class IriBaseNodeDriver. Similarly to the tests, diagnostics can easyly be added. See ROS Wiki for more details: http://www.ros.org/wiki/diagnostics/ (Tutorials: Creating a Diagnostic Analyzer) http://www.ros.org/wiki/self_test/ (Example: Self Test)

Definition at line 74 of file pmdcamera_driver_node.h.


Constructor & Destructor Documentation

constructor

This constructor mainly creates and initializes the PmdcameraDriverNode topics through the given public_node_handle object. IriBaseNodeDriver attributes may be also modified to suit node specifications.

All kind of ROS topics (publishers, subscribers, servers or clients) can be easyly generated with the scripts in the iri_ros_scripts package. Refer to ROS and IRI Wiki pages for more details:

http://www.ros.org/wiki/ROS/Tutorials/WritingPublisherSubscriber(c++) http://www.ros.org/wiki/ROS/Tutorials/WritingServiceClient(c++) http://wikiri.upc.es/index.php/Robotics_Lab

Parameters:
nha reference to the node handle object to manage all ROS topics.

Definition at line 5 of file pmdcamera_driver_node.cpp.

Destructor.

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

Definition at line 481 of file pmdcamera_driver_node.cpp.


Member Function Documentation

void PmdcameraDriverNode::addNodeDiagnostics ( void  ) [protected, virtual]

node add diagnostics

In this function ROS diagnostics applied to this specific node may be added. Common use diagnostics for all nodes are already called from IriBaseNodeDriver::addDiagnostics(), which also calls this function. Information of how ROS diagnostics work can be readen here: http://www.ros.org/wiki/diagnostics/ http://www.ros.org/doc/api/diagnostic_updater/html/example_8cpp-source.html

Implements iri_base_driver::IriBaseNodeDriver< PmdcameraDriver >.

Definition at line 461 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::addNodeOpenedTests ( void  ) [protected, virtual]

open status driver tests

In this function tests checking driver's functionallity when driver_base status=open can be added. Common use tests for all nodes are already called from IriBaseNodeDriver tests methods. For more details on how ROS tests work, please refer to the Self Test example in: http://www.ros.org/wiki/self_test/

Implements iri_base_driver::IriBaseNodeDriver< PmdcameraDriver >.

Definition at line 465 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::addNodeRunningTests ( void  ) [protected, virtual]

run status driver tests

In this function tests checking driver's functionallity when driver_base status=run can be added. Common use tests for all nodes are already called from IriBaseNodeDriver tests methods. For more details on how ROS tests work, please refer to the Self Test example in: http://www.ros.org/wiki/self_test/

Implements iri_base_driver::IriBaseNodeDriver< PmdcameraDriver >.

Definition at line 473 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::addNodeStoppedTests ( void  ) [protected, virtual]

stop status driver tests

In this function tests checking driver's functionallity when driver_base status=stop can be added. Common use tests for all nodes are already called from IriBaseNodeDriver tests methods. For more details on how ROS tests work, please refer to the Self Test example in: http://www.ros.org/wiki/self_test/

Implements iri_base_driver::IriBaseNodeDriver< PmdcameraDriver >.

Definition at line 469 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::assembleAmplitudeImage ( float *  amplitude) [private]

Fills the Image with the amplitude data, normalized to 0..255

Todo:
this is putting knowledge in the node, and maybe should be in the low level driver?

Definition at line 254 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::assembleDepthImage ( float *  distance) [private]

Fills the depth image with the depth data, normalized to 0..255

Todo:
this is putting knowledge in the node, and maybe should be in the low level driver?

Definition at line 266 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::assembleFlagsImage ( float *  flags) [private]

Fills the Image with the flags data

Definition at line 230 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::assembleIntensityImage ( float *  intensity) [private]

Fills the Image with the intensity data, normalized to 0..255

Todo:
this is putting knowledge in the node, and maybe should be in the low level driver?

Definition at line 242 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::assemblePcl2Amp ( const float *const  coord_3D,
const float *const  amplitude 
) [private]

Definition at line 310 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::assemblePcl2Int ( const float *const  coord_3D,
const float *const  intensity 
) [private]

fills the pointcloud2 with the 3D image data

Parameters:
coord_3Ddepth image as returned by driver->get3DImage
intensityintensity image as returned by driver->getIntensityImage

Definition at line 280 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::assemblePcl2RangeImage ( const float *const  coord_3D,
const float *const  range,
const float *const  amp 
) [private]

Definition at line 334 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::findMaxAmplitude ( const float *  amplitude) [private]

Definition at line 210 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::findMaxDepth ( const float *  distance) [private]

Definition at line 220 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::findMaxIntensity ( const float *  intensity) [private]

finds the maximum intensity value used to normalize the intensity image and point values between 0..255

Definition at line 200 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::mainNodeThread ( void  ) [protected, virtual]

main node thread

This is the main thread node function. Code written here will be executed in every node loop while the driver is on running state. Loop frequency can be tuned my modifying loop_rate attribute.

Here data related to the process loop or to ROS topics (mainly data structs related to the MSG and SRV files) must be updated. ROS publisher objects must publish their data in this process. ROS client servers may also request data to the corresponding server topics.

Implements iri_base_driver::IriBaseNodeDriver< PmdcameraDriver >.

Definition at line 355 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::postNodeOpenHook ( void  ) [private, virtual]

post open hook

This function is called by IriBaseNodeDriver::postOpenHook(). In this function specific parameters from the driver must be added so the ROS dynamic reconfigure application can update them.

Implements iri_base_driver::IriBaseNodeDriver< PmdcameraDriver >.

Definition at line 457 of file pmdcamera_driver_node.cpp.

void PmdcameraDriverNode::reconfigureNodeHook ( int  level) [protected, virtual]

specific node dynamic reconfigure

This function is called reconfigureHook()

Parameters:
levelinteger

Implements iri_base_driver::IriBaseNodeDriver< PmdcameraDriver >.

Definition at line 477 of file pmdcamera_driver_node.cpp.


Member Data Documentation

sensor_msgs::CameraInfo PmdcameraDriverNode::camera_info_ [private]

Camera info data.

Definition at line 125 of file pmdcamera_driver_node.h.

Camera info manager objects.

Definition at line 121 of file pmdcamera_driver_node.h.

Definition at line 123 of file pmdcamera_driver_node.h.

std::string PmdcameraDriverNode::camera_name_ [private]

Definition at line 122 of file pmdcamera_driver_node.h.

Definition at line 101 of file pmdcamera_driver_node.h.

Definition at line 78 of file pmdcamera_driver_node.h.

sensor_msgs::Image PmdcameraDriverNode::Image_amp_msg_ [private]

Definition at line 96 of file pmdcamera_driver_node.h.

Definition at line 95 of file pmdcamera_driver_node.h.

sensor_msgs::Image PmdcameraDriverNode::Image_depth_msg_ [private]

Definition at line 99 of file pmdcamera_driver_node.h.

Definition at line 98 of file pmdcamera_driver_node.h.

sensor_msgs::Image PmdcameraDriverNode::Image_flags_msg_ [private]

Definition at line 93 of file pmdcamera_driver_node.h.

Definition at line 92 of file pmdcamera_driver_node.h.

sensor_msgs::Image PmdcameraDriverNode::Image_int_msg_ [private]

Definition at line 90 of file pmdcamera_driver_node.h.

ROS publishers.

Definition at line 89 of file pmdcamera_driver_node.h.

Definition at line 84 of file pmdcamera_driver_node.h.

used to normalize the intensity image to 0..255

Definition at line 80 of file pmdcamera_driver_node.h.

used to normalize the intensity image to 0..255

Definition at line 81 of file pmdcamera_driver_node.h.

used to normalize the intensity image to 0..255

Definition at line 79 of file pmdcamera_driver_node.h.

sensor_msgs::PointCloud2 PmdcameraDriverNode::pcl2_amp_msg_ [private]

Definition at line 108 of file pmdcamera_driver_node.h.

sensor_msgs::PointCloud2 PmdcameraDriverNode::pcl2_int_msg_ [private]

Definition at line 107 of file pmdcamera_driver_node.h.

sensor_msgs::PointCloud2 PmdcameraDriverNode::pcl2_range_msg_ [private]

Definition at line 109 of file pmdcamera_driver_node.h.

Definition at line 105 of file pmdcamera_driver_node.h.

Definition at line 104 of file pmdcamera_driver_node.h.

Definition at line 106 of file pmdcamera_driver_node.h.

Definition at line 102 of file pmdcamera_driver_node.h.

Definition at line 78 of file pmdcamera_driver_node.h.

Definition at line 77 of file pmdcamera_driver_node.h.

Definition at line 77 of file pmdcamera_driver_node.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