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

IRI ROS Specific Driver Class. More...

#include <zyonz_tof_color_driver_node.h>

Inheritance diagram for ZyonzTofColorDriverNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ZyonzTofColorDriverNode (ros::NodeHandle &nh)
 constructor
 ~ZyonzTofColorDriverNode ()
 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 image_callback (const sensor_msgs::Image::ConstPtr &msg)
void input_intens_callback (const sensor_msgs::Image::ConstPtr &msg)
void pointCloud_callback (const sensor_msgs::PointCloud2::ConstPtr &msg)
void postNodeOpenHook (void)
 post open hook
void processRgbAndDepth ()
bool saveImageCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)

Private Attributes

sensor_msgs::PointCloud2::ConstPtr cloud2_
 PointCloud2 data.
ros::Publisher cloud2_raw_publisher_
bool depth_sent_
std::string fileName
CMutex image_mutex_
ros::Subscriber image_subscriber_
CMutex input_intens_mutex_
ros::Subscriber input_intens_subscriber_
sensor_msgs::Image::ConstPtr intens_image_
bool intens_sent_
Matrix3f K_
int kernel_size_
 RGB_TOF extrinsics.
std::ofstream outFile
Matrix4f P_
 RGB intrinsics.
sensor_msgs::PointCloud2 PointCloud2_msg_
CMutex pointCloud_mutex_
ros::Subscriber pointCloud_subscriber_
sensor_msgs::Image::ConstPtr rgb_image_
 Image data.
bool rgb_sent_
bool saveFile
int saveFileCounter
CMutex saveImage_mutex_
ros::ServiceServer saveImage_server_
int zbuffer_threshold_

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 68 of file zyonz_tof_color_driver_node.h.


Constructor & Destructor Documentation

constructor

This constructor mainly creates and initializes the ZyonzTofColorDriverNode 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 11 of file zyonz_tof_color_driver_node.cpp.

Destructor.

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

Definition at line 452 of file zyonz_tof_color_driver_node.cpp.


Member Function Documentation

void ZyonzTofColorDriverNode::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< ZyonzTofColorDriver >.

Definition at line 432 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::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< ZyonzTofColorDriver >.

Definition at line 436 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::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< ZyonzTofColorDriver >.

Definition at line 444 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::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< ZyonzTofColorDriver >.

Definition at line 440 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::image_callback ( const sensor_msgs::Image::ConstPtr &  msg) [private]

Definition at line 119 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::input_intens_callback ( const sensor_msgs::Image::ConstPtr &  msg) [private]

Definition at line 101 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::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 by 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< ZyonzTofColorDriver >.

Definition at line 77 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::pointCloud_callback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [private]

Definition at line 138 of file zyonz_tof_color_driver_node.cpp.

void ZyonzTofColorDriverNode::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< ZyonzTofColorDriver >.

Definition at line 428 of file zyonz_tof_color_driver_node.cpp.

Definition at line 160 of file zyonz_tof_color_driver_node.cpp.

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

specific node dynamic reconfigure

This function is called reconfigureHook()

Parameters:
levelinteger

Implements iri_base_driver::IriBaseNodeDriver< ZyonzTofColorDriver >.

Definition at line 448 of file zyonz_tof_color_driver_node.cpp.

bool ZyonzTofColorDriverNode::saveImageCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [private]

Definition at line 377 of file zyonz_tof_color_driver_node.cpp.


Member Data Documentation

sensor_msgs::PointCloud2::ConstPtr ZyonzTofColorDriverNode::cloud2_ [private]

PointCloud2 data.

Definition at line 134 of file zyonz_tof_color_driver_node.h.

Definition at line 72 of file zyonz_tof_color_driver_node.h.

: cal sincronitzar (amb timestamps?) les dues càmeres De moment es fan servir aquests dos flags per comprovar que hi ha imatge disponible

Definition at line 115 of file zyonz_tof_color_driver_node.h.

std::string ZyonzTofColorDriverNode::fileName [private]

Definition at line 127 of file zyonz_tof_color_driver_node.h.

Definition at line 81 of file zyonz_tof_color_driver_node.h.

Definition at line 79 of file zyonz_tof_color_driver_node.h.

Definition at line 78 of file zyonz_tof_color_driver_node.h.

Definition at line 76 of file zyonz_tof_color_driver_node.h.

sensor_msgs::Image::ConstPtr ZyonzTofColorDriverNode::intens_image_ [private]

Definition at line 132 of file zyonz_tof_color_driver_node.h.

Definition at line 117 of file zyonz_tof_color_driver_node.h.

Matrix3f ZyonzTofColorDriverNode::K_ [private]

Definition at line 107 of file zyonz_tof_color_driver_node.h.

RGB_TOF extrinsics.

Definition at line 110 of file zyonz_tof_color_driver_node.h.

std::ofstream ZyonzTofColorDriverNode::outFile [private]

Definition at line 126 of file zyonz_tof_color_driver_node.h.

Matrix4f ZyonzTofColorDriverNode::P_ [private]

RGB intrinsics.

Definition at line 108 of file zyonz_tof_color_driver_node.h.

sensor_msgs::PointCloud2 ZyonzTofColorDriverNode::PointCloud2_msg_ [private]

Definition at line 73 of file zyonz_tof_color_driver_node.h.

Definition at line 85 of file zyonz_tof_color_driver_node.h.

Definition at line 83 of file zyonz_tof_color_driver_node.h.

sensor_msgs::Image::ConstPtr ZyonzTofColorDriverNode::rgb_image_ [private]

Image data.

Definition at line 131 of file zyonz_tof_color_driver_node.h.

Definition at line 116 of file zyonz_tof_color_driver_node.h.

Pel servei de salvar imatges

Definition at line 124 of file zyonz_tof_color_driver_node.h.

Definition at line 125 of file zyonz_tof_color_driver_node.h.

Definition at line 90 of file zyonz_tof_color_driver_node.h.

Definition at line 88 of file zyonz_tof_color_driver_node.h.

Definition at line 119 of file zyonz_tof_color_driver_node.h.


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


zyonz_tof_color
Author(s): Guillem Alenyà - IRI Robotics Lab
autogenerated on Fri Dec 6 2013 21:08:57