$search
00001 //================================================================================================= 00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 // This code is based on the original gazebo_ros_imu plugin by Sachin Chitta and John Hsu: 00029 /* 00030 * Gazebo - Outdoor Multi-Robot Simulator 00031 * Copyright (C) 2003 00032 * Nate Koenig & Andrew Howard 00033 * 00034 * This program is free software; you can redistribute it and/or modify 00035 * it under the terms of the GNU General Public License as published by 00036 * the Free Software Foundation; either version 2 of the License, or 00037 * (at your option) any later version. 00038 * 00039 * This program is distributed in the hope that it will be useful, 00040 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00041 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00042 * GNU General Public License for more details. 00043 * 00044 * You should have received a copy of the GNU General Public License 00045 * along with this program; if not, write to the Free Software 00046 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00047 * 00048 */ 00049 /* 00050 * Desc: 3D position interface. 00051 * Author: Sachin Chitta and John Hsu 00052 * Date: 10 June 2008 00053 * SVN: $Id$ 00054 */ 00055 //================================================================================================= 00056 00057 00058 #ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H 00059 #define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H 00060 00061 #define USE_CBQ 00062 #ifdef USE_CBQ 00063 #include <ros/callback_queue.h> 00064 #include <ros/advertise_options.h> 00065 #endif 00066 00067 #include <gazebo/Controller.hh> 00068 #include <gazebo/Entity.hh> 00069 #include <gazebo/Model.hh> 00070 #include <gazebo/Body.hh> 00071 #include <gazebo/Param.hh> 00072 #include <gazebo/Time.hh> 00073 00074 #include <ros/ros.h> 00075 #include "boost/thread/mutex.hpp" 00076 #include <sensor_msgs/Imu.h> 00077 #include <std_srvs/Empty.h> 00078 #include <hector_gazebo_plugins/SetBias.h> 00079 #include <hector_gazebo_plugins/sensor_model.h> 00080 00081 namespace gazebo 00082 { 00083 class GazeboRosIMU : public Controller 00084 { 00086 public: GazeboRosIMU(Entity *parent ); 00087 00089 public: virtual ~GazeboRosIMU(); 00090 00093 protected: virtual void LoadChild(XMLConfigNode *node); 00094 00096 protected: virtual void InitChild(); 00097 00099 protected: virtual void UpdateChild(); 00100 00102 protected: virtual void FiniChild(); 00103 00105 private: Model *myParent; 00106 00108 private: Body *myBody; //Gazebo/ODE body 00109 00111 private: ros::NodeHandle* rosnode_; 00112 private: ros::Publisher pub_; 00113 00115 private: sensor_msgs::Imu imuMsg; 00116 00118 private: ParamT<std::string> *bodyNameP; 00119 private: std::string bodyName; 00120 00122 private: ParamT<std::string> *topicNameP; 00123 private: std::string topicName; 00124 00126 private: ParamT<Vector3> *rpyOffsetsP; 00127 private: ParamT<double> *gaussianNoiseP; 00128 00130 private: SensorModel3 accelModel; 00131 private: SensorModel3 rateModel; 00132 private: SensorModel headingModel; 00133 00135 private: boost::mutex lock; 00136 00138 private: Quatern orientation; 00139 private: Vector3 velocity; 00140 private: Vector3 accel; 00141 private: Vector3 rate; 00142 private: Vector3 gravity; 00143 private: Vector3 gravity_body; 00144 00146 private: double GaussianKernel(double mu,double sigma); 00147 00149 private: ParamT<std::string> *robotNamespaceP; 00150 private: std::string robotNamespace; 00151 00153 private: bool ServiceCallback(std_srvs::Empty::Request &req, 00154 std_srvs::Empty::Response &res); 00155 private: ros::ServiceServer srv_; 00156 private: ParamT<std::string> *serviceNameP; 00157 private: std::string serviceName; 00158 00160 private: bool SetAccelBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res); 00161 private: bool SetRateBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res); 00162 private: ros::ServiceServer accelBiasService; 00163 private: ros::ServiceServer rateBiasService; 00164 00165 #ifdef USE_CBQ 00166 private: ros::CallbackQueue callback_queue_; 00167 private: void CallbackQueueThread(); 00168 private: boost::thread callback_queue_thread_; 00169 #endif 00170 }; 00171 00173 00174 00175 00176 } 00177 00178 #endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H