diff --git a/include/lidar_lite_driver.h b/include/lidar_lite_driver.h index 67a5bd69f499013226c93d7e0b57d7acf859d8b1..b0e17a55c0ffc39caf23d262894b20060cc4efb5 100644 --- a/include/lidar_lite_driver.h +++ b/include/lidar_lite_driver.h @@ -1,5 +1,6 @@ -// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. -// Author Angel Santamaria-Navarro +// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, +// CSIC-UPC. +// Author Angel Santamaria-Navarro // All rights reserved. // // This file is part of iri-ros-pkg @@ -15,9 +16,10 @@ // // You should have received a copy of the GNU Lesser General Public License // along with this program. If not, see <http://www.gnu.org/licenses/>. -// -// IMPORTANT NOTE: This code has been generated through a script from the -// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness +// +// IMPORTANT NOTE: This code has been generated through a script from the +// iri_ros_scripts. Please do NOT delete any comments to guarantee the +// correctness // of the scripts. ROS topics can be easly add by using those scripts. Please // refer to the IRI wiki page for more information: // http://wikiri.upc.es/index.php/Robotics_Lab @@ -35,133 +37,136 @@ * \brief 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 + * 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 LidarLiteDriver class must implement all specific driver requirements to - * safetely open, close, run and stop the driver at any time. It also must + * safetely open, close, run and stop the driver at any time. It also must * guarantee an accessible interface for all driver's parameters. * * The LidarLiteConfig.cfg needs to be filled up with those parameters suitable - * to be changed dynamically by the ROS dyanmic reconfigure application. The + * 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(). * */ class LidarLiteDriver : public iri_base_driver::IriBaseDriver { - private: - // private attributes and methods - - CLidarLite* laser_ptr_; - bool params_set_; - std::string serial_; - int config_mode_; - - public: - /** - * \brief define config type - * - * Define a Config type with the LidarLiteConfig. All driver implementations - * will then use the same variable type Config. - */ - typedef iri_lidar_lite::LidarLiteConfig Config; - - /** - * \brief config variable - * - * This variable has all the driver parameters defined in the cfg config file. - * Is updated everytime function config_update() is called. - */ - Config config_; - - /** - * \brief 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. - */ - LidarLiteDriver(void); - - /** - * \brief 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. - * - * \return bool successful - */ - bool openDriver(void); - - /** - * \brief 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. - * - * \return bool successful - */ - bool closeDriver(void); - - /** - * \brief 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. - * - * \return bool successful - */ - bool startDriver(void); - - /** - * \brief 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. - * - * \return bool successful - */ - bool stopDriver(void); - - /** - * \brief 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. - * - * \param new_cfg the new driver configuration state - * - * \param level level in which the update is taken place - */ - void config_update(Config& new_cfg, uint32_t level=0); - - // here define all lidar_lite_driver interface methods to retrieve and set - // the driver parameters - - void setParams(const std::string &serial, const int &config_mode); - - int getRange(void); - - /** - * \brief Destructor - * - * This destructor is called when the object is about to be destroyed. - * - */ - ~LidarLiteDriver(void); +private: + // private attributes and methods + + CLidarLite* laser_ptr_; + bool params_set_; + std::string serial_; + int config_mode_; + +public: + /** + * \brief define config type + * + * Define a Config type with the LidarLiteConfig. All driver implementations + * will then use the same variable type Config. + */ + typedef iri_lidar_lite::LidarLiteConfig Config; + + /** + * \brief config variable + * + * This variable has all the driver parameters defined in the cfg config file. + * Is updated everytime function config_update() is called. + */ + Config config_; + + /** + * \brief 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. + */ + LidarLiteDriver(void); + + /** + * \brief 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. + * + * \return bool successful + */ + bool openDriver(void); + + /** + * \brief 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. + * + * \return bool successful + */ + bool closeDriver(void); + + /** + * \brief 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. + * + * \return bool successful + */ + bool startDriver(void); + + /** + * \brief 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. + * + * \return bool successful + */ + bool stopDriver(void); + + /** + * \brief 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. + * + * \param new_cfg the new driver configuration state + * + * \param level level in which the update is taken place + */ + void config_update(Config& new_cfg, uint32_t level = 0); + + // here define all lidar_lite_driver interface methods to retrieve and set + // the driver parameters + + void setParams(const std::string& serial, const int& config_mode); + + int getRange(void); + + /** + * \brief Destructor + * + * This destructor is called when the object is about to be destroyed. + * + */ + ~LidarLiteDriver(void); }; #endif diff --git a/include/lidar_lite_driver_node.h b/include/lidar_lite_driver_node.h index aacf55dd1166875c2719f61d97add8518e5f0deb..133353cf85a4ec69ff92a7fe56161a2ccb5a1b3d 100644 --- a/include/lidar_lite_driver_node.h +++ b/include/lidar_lite_driver_node.h @@ -1,4 +1,5 @@ -// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. +// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, +// CSIC-UPC. // Author Angel Santamaria-Navarro // All rights reserved. // @@ -15,9 +16,10 @@ // // You should have received a copy of the GNU Lesser General Public License // along with this program. If not, see <http://www.gnu.org/licenses/>. -// -// IMPORTANT NOTE: This code has been generated through a script from the -// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness +// +// IMPORTANT NOTE: This code has been generated through a script from the +// iri_ros_scripts. Please do NOT delete any comments to guarantee the +// correctness // of the scripts. ROS topics can be easly add by using those scripts. Please // refer to the IRI wiki page for more information: // http://wikiri.upc.es/index.php/Robotics_Lab @@ -25,8 +27,8 @@ #ifndef _lidar_lite_driver_node_h_ #define _lidar_lite_driver_node_h_ -#include <iri_base_driver/iri_base_driver_node.h> #include "lidar_lite_driver.h" +#include <iri_base_driver/iri_base_driver_node.h> #include <boost/thread/thread.hpp> @@ -40,155 +42,162 @@ /** * \brief 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 + * 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 + * 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. + * 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/diagnostics/ (Tutorials: Creating a Diagnostic + * Analyzer) * http://www.ros.org/wiki/self_test/ (Example: Self Test) */ -class LidarLiteDriverNode : public iri_base_driver::IriBaseNodeDriver<LidarLiteDriver> +class LidarLiteDriverNode + : public iri_base_driver::IriBaseNodeDriver<LidarLiteDriver> { - private: - - int range_seq_; // Range publisher counter. - std::string frame_id_; // publisher frame id. - - boost::thread Thread_; // Hardware reading thread. - bool RunThread_; // Enables the hardware reading thread. - void ThreadFunc(void); // Hardware reading thread function. - - // [publisher attributes] - ros::Publisher range_publisher_; - sensor_msgs::Range range_msg_; - - // [subscriber attributes] - - // [service attributes] - - // [client attributes] - - // [action server attributes] - - // [action client attributes] - - /** - * \brief 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. - */ - void postNodeOpenHook(void); - - public: - /** - * \brief constructor - * - * This constructor mainly creates and initializes the LidarLiteDriverNode 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 - * - * \param nh a reference to the node handle object to manage all ROS topics. - */ - LidarLiteDriverNode(ros::NodeHandle& nh); - - /** - * \brief Destructor - * - * This destructor is called when the object is about to be destroyed. - * - */ - ~LidarLiteDriverNode(void); - - protected: - /** - * \brief 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. - */ - void mainNodeThread(void); - - // [diagnostic functions] - - /** - * \brief 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 - */ - void addNodeDiagnostics(void); - - // [driver test functions] - - /** - * \brief 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/ - */ - void addNodeOpenedTests(void); - - /** - * \brief 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/ - */ - void addNodeStoppedTests(void); - - /** - * \brief 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/ - */ - void addNodeRunningTests(void); - - /** - * \brief specific node dynamic reconfigure - * - * This function is called reconfigureHook() - * - * \param level integer - */ - void reconfigureNodeHook(int level); - +private: + int range_seq_; // Range publisher counter. + std::string frame_id_; // publisher frame id. + + boost::thread Thread_; // Hardware reading thread. + bool RunThread_; // Enables the hardware reading thread. + void ThreadFunc(void); // Hardware reading thread function. + + // [publisher attributes] + ros::Publisher range_publisher_; + sensor_msgs::Range range_msg_; + + // [subscriber attributes] + + // [service attributes] + + // [client attributes] + + // [action server attributes] + + // [action client attributes] + + /** + * \brief 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. + */ + void postNodeOpenHook(void); + +public: + /** + * \brief constructor + * + * This constructor mainly creates and initializes the LidarLiteDriverNode + * 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 + * + * \param nh a reference to the node handle object to manage all ROS topics. + */ + LidarLiteDriverNode(ros::NodeHandle& nh); + + /** + * \brief Destructor + * + * This destructor is called when the object is about to be destroyed. + * + */ + ~LidarLiteDriverNode(void); + +protected: + /** + * \brief 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. + */ + void mainNodeThread(void); + + // [diagnostic functions] + + /** + * \brief 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 + */ + void addNodeDiagnostics(void); + + // [driver test functions] + + /** + * \brief 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/ + */ + void addNodeOpenedTests(void); + + /** + * \brief 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/ + */ + void addNodeStoppedTests(void); + + /** + * \brief 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/ + */ + void addNodeRunningTests(void); + + /** + * \brief specific node dynamic reconfigure + * + * This function is called reconfigureHook() + * + * \param level integer + */ + void reconfigureNodeHook(int level); }; #endif diff --git a/src/lidar_lite_driver.cpp b/src/lidar_lite_driver.cpp index 7296454f21d6368721c23f0c704eeb756c9e1d10..a137c01d1d29c1a4a8ab7fc1291961c97b348fe8 100644 --- a/src/lidar_lite_driver.cpp +++ b/src/lidar_lite_driver.cpp @@ -7,60 +7,57 @@ LidarLiteDriver::LidarLiteDriver(void) this->config_mode_ = 0; } -bool LidarLiteDriver::openDriver(void) +bool +LidarLiteDriver::openDriver(void) { - this->laser_ptr_ = new CLidarLite(this->serial_,this->config_mode_); - - try - { + this->laser_ptr_ = new CLidarLite(this->serial_, this->config_mode_); + + try { this->laser_ptr_->open(); - } - catch(CLidarLiteException &e) - { + } catch (CLidarLiteException& e) { std::cout << e.what() << std::endl; } return true; } -bool LidarLiteDriver::closeDriver(void) +bool +LidarLiteDriver::closeDriver(void) { - try - { + try { this->laser_ptr_->close(); - } - catch(CLidarLiteException &e) - { + } catch (CLidarLiteException& e) { std::cout << e.what() << std::endl; } - if(this->laser_ptr_ != NULL) - { + if (this->laser_ptr_ != NULL) { this->laser_ptr_ = NULL; delete this->laser_ptr_; - } + } return true; } -bool LidarLiteDriver::startDriver(void) +bool +LidarLiteDriver::startDriver(void) { return true; } -bool LidarLiteDriver::stopDriver(void) +bool +LidarLiteDriver::stopDriver(void) { return true; } -void LidarLiteDriver::config_update(Config& new_cfg, uint32_t level) +void +LidarLiteDriver::config_update(Config& new_cfg, uint32_t level) { this->lock(); - + // depending on current state // update driver with new_cfg data - switch(this->getState()) - { + switch (this->getState()) { case LidarLiteDriver::CLOSED: break; @@ -71,12 +68,9 @@ void LidarLiteDriver::config_update(Config& new_cfg, uint32_t level) this->config_mode_ = new_cfg.Config_mode; - try - { + try { this->laser_ptr_->set_new_config(this->config_mode_); - } - catch(CLidarLiteException &e) - { + } catch (CLidarLiteException& e) { std::cout << e.what() << std::endl; } @@ -84,27 +78,26 @@ void LidarLiteDriver::config_update(Config& new_cfg, uint32_t level) } // save the current configuration - this->config_=new_cfg; + this->config_ = new_cfg; this->unlock(); } -void LidarLiteDriver::setParams(const std::string &serial, const int &config_mode) +void +LidarLiteDriver::setParams(const std::string& serial, const int& config_mode) { this->serial_ = serial; this->config_mode_ = config_mode; } -int LidarLiteDriver::getRange(void) +int +LidarLiteDriver::getRange(void) { int range; - try - { + try { range = this->laser_ptr_->get_range(true); - } - catch(CLidarLiteException &e) - { + } catch (CLidarLiteException& e) { std::cout << e.what() << std::endl; } @@ -113,9 +106,8 @@ int LidarLiteDriver::getRange(void) LidarLiteDriver::~LidarLiteDriver(void) { - if(this->laser_ptr_ != NULL) - { + if (this->laser_ptr_ != NULL) { this->laser_ptr_ = NULL; delete this->laser_ptr_; - } + } } diff --git a/src/lidar_lite_driver_node.cpp b/src/lidar_lite_driver_node.cpp index 552b61372cda33091150aa05356a95f1967b9a8f..79ef6b4ef01feb75d375df49b537d7092d65bccc 100644 --- a/src/lidar_lite_driver_node.cpp +++ b/src/lidar_lite_driver_node.cpp @@ -2,67 +2,69 @@ #include <ctime> - -LidarLiteDriverNode::LidarLiteDriverNode(ros::NodeHandle &nh) : - iri_base_driver::IriBaseNodeDriver<LidarLiteDriver>(nh), - RunThread_(true), - Thread_(boost::bind(&LidarLiteDriverNode::ThreadFunc, this)) +LidarLiteDriverNode::LidarLiteDriverNode(ros::NodeHandle& nh) + : iri_base_driver::IriBaseNodeDriver<LidarLiteDriver>(nh) + , RunThread_(true) + , Thread_(boost::bind(&LidarLiteDriverNode::ThreadFunc, this)) { // this->loop_rate_ = 1000; // [Hz] // Read from launch file std::string serial; int config_mode; - this->public_node_handle_.param<std::string>("serial_num", serial, "A700evSl"); + this->public_node_handle_.param<std::string>("serial_num", serial, + "A700evSl"); this->public_node_handle_.param<int>("config_mode", config_mode, 0); - this->public_node_handle_.param<std::string>("frame_id", this->frame_id_, "lidar_lite"); + this->public_node_handle_.param<std::string>("frame_id", this->frame_id_, + "lidar_lite"); // Set device parameters - this->driver_.setParams(serial,config_mode); + this->driver_.setParams(serial, config_mode); // [init publishers] - this->range_publisher_ = this->public_node_handle_.advertise<sensor_msgs::Range>("range", 100); - this->range_seq_ = 0; + this->range_publisher_ = + this->public_node_handle_.advertise<sensor_msgs::Range>("range", 100); + this->range_seq_ = 0; // [init subscribers] - + // [init services] - + // [init clients] - + // [init action servers] - + // [init action clients] } -void LidarLiteDriverNode::ThreadFunc(void) +void +LidarLiteDriverNode::ThreadFunc(void) { - while(this->RunThread_) - { - if (this->driver_.getState() == LidarLiteDriver::RUNNING) - { + while (this->RunThread_) { + if (this->driver_.getState() == LidarLiteDriver::RUNNING) { // Get measurement this->driver_.lock(); int range = this->driver_.getRange(); this->driver_.unlock(); - + // Publish ROS message this->range_msg_.header.seq = this->range_seq_; this->range_msg_.header.stamp = ros::Time::now(); - this->range_msg_.header.frame_id = this->frame_id_; + this->range_msg_.header.frame_id = this->frame_id_; this->range_msg_.field_of_view = 0.1; this->range_msg_.min_range = 0; this->range_msg_.max_range = 40; this->range_msg_.range = range; this->range_publisher_.publish(this->range_msg_); - + // Increment range publisher counter. ++this->range_seq_; } } } -void LidarLiteDriverNode::mainNodeThread(void) +void +LidarLiteDriverNode::mainNodeThread(void) { /* code */ } @@ -75,27 +77,33 @@ void LidarLiteDriverNode::mainNodeThread(void) /* [action requests] */ -void LidarLiteDriverNode::postNodeOpenHook(void) +void +LidarLiteDriverNode::postNodeOpenHook(void) { } -void LidarLiteDriverNode::addNodeDiagnostics(void) +void +LidarLiteDriverNode::addNodeDiagnostics(void) { } -void LidarLiteDriverNode::addNodeOpenedTests(void) +void +LidarLiteDriverNode::addNodeOpenedTests(void) { } -void LidarLiteDriverNode::addNodeStoppedTests(void) +void +LidarLiteDriverNode::addNodeStoppedTests(void) { } -void LidarLiteDriverNode::addNodeRunningTests(void) +void +LidarLiteDriverNode::addNodeRunningTests(void) { } -void LidarLiteDriverNode::reconfigureNodeHook(int level) +void +LidarLiteDriverNode::reconfigureNodeHook(int level) { } @@ -107,7 +115,9 @@ LidarLiteDriverNode::~LidarLiteDriverNode(void) } /* main function */ -int main(int argc,char *argv[]) +int +main(int argc, char* argv[]) { - return driver_base::main<LidarLiteDriverNode>(argc, argv, "lidar_lite_driver_node"); + return driver_base::main<LidarLiteDriverNode>(argc, argv, + "lidar_lite_driver_node"); }