IRI ROS Specific Driver Class. More...
#include <firewire_camera_driver_node.h>
Public Member Functions | |
FirewireCameraDriverNode (ros::NodeHandle &nh) | |
constructor | |
FirewireCameraDriverNode (ros::NodeHandle &nh) | |
constructor | |
~FirewireCameraDriverNode () | |
Destructor. | |
~FirewireCameraDriverNode () | |
Destructor. | |
Protected Member Functions | |
void | addNodeDiagnostics (void) |
node add diagnostics | |
void | addNodeDiagnostics (void) |
node add diagnostics | |
void | addNodeOpenedTests (void) |
open status driver tests | |
void | addNodeOpenedTests (void) |
open status driver tests | |
void | addNodeRunningTests (void) |
run status driver tests | |
void | addNodeRunningTests (void) |
run status driver tests | |
void | addNodeStoppedTests (void) |
stop status driver tests | |
void | addNodeStoppedTests (void) |
stop status driver tests | |
void | check_configuration (diagnostic_updater::DiagnosticStatusWrapper &stat) |
void | check_configuration (diagnostic_updater::DiagnosticStatusWrapper &stat) |
void | mainNodeThread (void) |
main node thread | |
void | mainNodeThread (void) |
main node thread | |
void | reconfigureNodeHook (int level) |
specific node dynamic reconfigure | |
void | reconfigureNodeHook (int level) |
specific node dynamic reconfigure | |
Private Member Functions | |
void | postNodeOpenHook (void) |
post open hook | |
void | postNodeOpenHook (void) |
post open hook | |
Private Attributes | |
image_transport::CameraPublisher | camera_image_publisher_ |
camera_info_manager::CameraInfoManager | camera_manager |
double | desired_framerate |
diagnostic_updater::HeaderlessTopicDiagnostic * | diagnosed_camera_image |
CEventServer * | event_server |
sensor_msgs::Image | Image_msg_ |
sensor_msgs::ImagePtr | Image_msg_ |
image_transport::ImageTransport * | it |
boost::shared_ptr < image_transport::ImageTransport > | it |
std::string | new_frame_event |
std::string | tf_prefix_ |
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 65 of file firewire_camera_driver_node.h.
constructor
This constructor mainly creates and initializes the FirewireCameraDriverNode 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
nh | a reference to the node handle object to manage all ROS topics. |
Definition at line 3 of file firewire_camera_driver_node.cpp.
Destructor.
This destructor is called when the object is about to be destroyed.
Definition at line 188 of file firewire_camera_driver_node.cpp.
constructor
This constructor mainly creates and initializes the FirewireCameraDriverNode 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
nh | a reference to the node handle object to manage all ROS topics. |
Destructor.
This destructor is called when the object is about to be destroyed.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
Definition at line 160 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
Definition at line 165 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
Definition at line 173 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
Definition at line 169 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
void FirewireCameraDriverNode::check_configuration | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected] |
Definition at line 116 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::check_configuration | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected] |
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
Definition at line 45 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
Definition at line 156 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::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< FirewireCameraDriver >.
void FirewireCameraDriverNode::reconfigureNodeHook | ( | int | level | ) | [protected, virtual] |
specific node dynamic reconfigure
This function is called reconfigureHook()
level | integer |
Implements iri_base_driver::IriBaseNodeDriver< FirewireCameraDriver >.
Definition at line 177 of file firewire_camera_driver_node.cpp.
void FirewireCameraDriverNode::reconfigureNodeHook | ( | int | level | ) | [protected, virtual] |
specific node dynamic reconfigure
This function is called reconfigureHook()
level | integer |
Implements iri_base_driver::IriBaseNodeDriver< FirewireCameraDriver >.
Definition at line 70 of file firewire_camera_driver_node.h.
Definition at line 72 of file firewire_camera_driver_node.h.
double FirewireCameraDriverNode::desired_framerate [private] |
Definition at line 86 of file firewire_camera_driver_node.h.
diagnostic_updater::HeaderlessTopicDiagnostic * FirewireCameraDriverNode::diagnosed_camera_image [private] |
Definition at line 73 of file firewire_camera_driver_node.h.
CEventServer * FirewireCameraDriverNode::event_server [private] |
Definition at line 87 of file firewire_camera_driver_node.h.
sensor_msgs::Image FirewireCameraDriverNode::Image_msg_ [private] |
Definition at line 71 of file firewire_camera_driver_node.h.
sensor_msgs::ImagePtr FirewireCameraDriverNode::Image_msg_ [private] |
Definition at line 74 of file firewire_camera_driver_nodelet.h.
Definition at line 69 of file firewire_camera_driver_node.h.
boost::shared_ptr<image_transport::ImageTransport> FirewireCameraDriverNode::it [private] |
Definition at line 73 of file firewire_camera_driver_nodelet.h.
std::string FirewireCameraDriverNode::new_frame_event [private] |
Definition at line 88 of file firewire_camera_driver_node.h.
std::string FirewireCameraDriverNode::tf_prefix_ [private] |
Definition at line 89 of file firewire_camera_driver_node.h.