00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _hokuyo_laser3d_driver_node_h_ 00026 #define _hokuyo_laser3d_driver_node_h_ 00027 00028 #include <iri_base_driver/iri_base_driver_node.h> 00029 #include "hokuyo_laser3d_driver.h" 00030 00031 // [publisher subscriber headers] 00032 #include <sensor_msgs/PointCloud.h> 00033 #include <sensor_msgs/PointCloud2.h> 00034 #include <geometry_msgs/Point32.h> 00035 00036 // [service client headers] 00037 #include <iri_hokuyo_laser3d/Get3DScan.h> 00038 00039 // [action server client headers] 00040 00058 class HokuyoLaser3dDriverNode : public iri_base_driver::IriBaseNodeDriver<HokuyoLaser3dDriver> 00059 { 00060 private: 00061 00062 CEventServer *event_server; 00063 00064 // [publisher attributes] 00065 ros::Publisher slice_publisher_; 00066 sensor_msgs::PointCloud2 Slice_msg_; 00067 ros::Publisher cloud_publisher_; 00068 sensor_msgs::PointCloud2 Cloud_msg_; 00069 00070 // [subscriber attributes] 00071 00072 // [service attributes] 00073 ros::ServiceServer get_3d_scan_server_; 00074 bool get_3d_scanCallback(iri_hokuyo_laser3d::Get3DScan::Request &req, iri_hokuyo_laser3d::Get3DScan::Response &res); 00075 bool do_noncontinuous; 00076 00077 // [client attributes] 00078 00079 // [action server attributes] 00080 00081 // [action client attributes] 00082 00090 void postNodeOpenHook(void); 00091 00092 public: 00110 HokuyoLaser3dDriverNode(ros::NodeHandle& nh); 00111 00118 ~HokuyoLaser3dDriverNode(); 00119 00120 protected: 00133 void mainNodeThread(void); 00134 00135 // [diagnostic functions] 00136 00147 void addNodeDiagnostics(void); 00148 00149 // [driver test functions] 00150 00160 void addNodeOpenedTests(void); 00161 00171 void addNodeStoppedTests(void); 00172 00182 void addNodeRunningTests(void); 00183 00191 void reconfigureNodeHook(int level); 00192 00193 void createPointCloud2(const PointCloudTimeStamped & cld, sensor_msgs::PointCloud2 & pointcloud); 00194 00195 }; 00196 00197 #endif