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 _tcm3_compass_driver_node_h_ 00026 #define _tcm3_compass_driver_node_h_ 00027 00028 #include <iri_base_driver/iri_base_driver_node.h> 00029 #include "tcm3_compass_driver.h" 00030 00031 // [publisher subscriber headers] 00032 #include <iri_common_drivers_msgs/compass3axis.h> 00033 00034 // [service client headers] 00035 00036 // [action server client headers] 00037 00055 class Tcm3CompassDriverNode : public iri_base_driver::IriBaseNodeDriver<Tcm3CompassDriver> 00056 { 00057 private: 00058 // [publisher attributes] 00059 ros::Publisher tcm3_publisher_; 00060 iri_common_drivers_msgs::compass3axis compass3axis_msg_; 00061 double heading_; 00062 double pitch_; 00063 double roll_; 00064 bool distortion_; 00065 uint data_counter_; 00066 vector <double> vheading_; 00067 vector <double> vroll_; 00068 vector <double> vpitch_; 00069 uint covariance_buffer_length_; 00070 00071 00072 void covarianceMatrix(vector <double> x, vector <double> y, vector <double> z, vector <double> & matrix); 00073 double covariance(vector <double> x, vector <double> y); 00074 00075 // [subscriber attributes] 00076 00077 // [service attributes] 00078 00079 // [client attributes] 00080 00081 // [action server attributes] 00082 00083 // [action client attributes] 00084 00092 void postNodeOpenHook(void); 00093 00094 public: 00112 Tcm3CompassDriverNode(ros::NodeHandle& nh); 00113 00120 ~Tcm3CompassDriverNode(); 00121 00122 protected: 00135 void mainNodeThread(void); 00136 00137 // [diagnostic functions] 00138 00149 void addNodeDiagnostics(void); 00150 00151 // [driver test functions] 00152 00162 void addNodeOpenedTests(void); 00163 00173 void addNodeStoppedTests(void); 00174 00184 void addNodeRunningTests(void); 00185 00193 void reconfigureNodeHook(int level); 00194 00195 }; 00196 00197 #endif