$search
00001 /* 00002 * Gazebo - Outdoor Multi-Robot Simulator 00003 * Copyright (C) 2003 00004 * Nate Koenig & Andrew Howard 00005 * 00006 * This program is free software; you can redistribute it and/or modify 00007 * it under the terms of the GNU General Public License as published by 00008 * the Free Software Foundation; either version 2 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 General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00019 * 00020 */ 00021 /* 00022 * Desc: 3D position interface. 00023 * Author: Sachin Chitta and John Hsu 00024 * Date: 10 June 2008 00025 * SVN: $Id$ 00026 */ 00027 #ifndef GAZEBO_ROS_P3D_HH 00028 #define GAZEBO_ROS_P3D_HH 00029 00030 #define USE_CBQ 00031 #ifdef USE_CBQ 00032 #include <ros/callback_queue.h> 00033 #include <ros/advertise_options.h> 00034 #endif 00035 00036 #include <gazebo/Controller.hh> 00037 #include <gazebo/Entity.hh> 00038 #include <gazebo/Model.hh> 00039 #include <gazebo/Body.hh> 00040 #include <gazebo/Param.hh> 00041 #include <gazebo/Time.hh> 00042 00043 #include <ros/ros.h> 00044 #include "boost/thread/mutex.hpp" 00045 #include <nav_msgs/Odometry.h> 00046 00047 namespace gazebo 00048 { 00051 00099 class GazeboRosP3D : public Controller 00100 { 00102 public: GazeboRosP3D(Entity *parent ); 00103 00105 public: virtual ~GazeboRosP3D(); 00106 00109 protected: virtual void LoadChild(XMLConfigNode *node); 00110 00112 protected: virtual void InitChild(); 00113 00115 protected: virtual void UpdateChild(); 00116 00118 protected: virtual void FiniChild(); 00119 00121 private: Model *myParent; 00122 00124 private: Body *myBody; //Gazebo/ODE body 00125 00127 private: Body *myFrame; //Gazebo/ODE body 00128 00129 00131 private: ros::NodeHandle* rosnode_; 00132 private: ros::Publisher pub_; 00133 00135 private: nav_msgs::Odometry poseMsg; 00136 00138 private: ParamT<std::string> *bodyNameP; 00139 private: std::string bodyName; 00140 00142 private: ParamT<std::string> *topicNameP; 00143 private: std::string topicName; 00144 00147 private: ParamT<std::string> *frameNameP; 00148 private: std::string frameName; 00149 00151 private: ParamT<Vector3> *xyzOffsetsP; 00152 private: Vector3 xyzOffsets; 00153 private: ParamT<Vector3> *rpyOffsetsP; 00154 private: Vector3 rpyOffsets; 00155 00157 private: boost::mutex lock; 00158 00160 private: Time last_time; 00161 private: Vector3 last_vpos; 00162 private: Vector3 last_veul; 00163 private: Vector3 apos; 00164 private: Vector3 aeul; 00165 private: Vector3 last_frame_vpos; 00166 private: Vector3 last_frame_veul; 00167 private: Vector3 frame_apos; 00168 private: Vector3 frame_aeul; 00169 private: Pose3d initial_frame_pose; 00170 00172 private: ParamT<double> *gaussianNoiseP; 00173 private: double gaussianNoise; 00174 00176 private: double GaussianKernel(double mu,double sigma); 00177 00179 private: ParamT<std::string> *robotNamespaceP; 00180 private: std::string robotNamespace; 00181 00183 private: int p3dConnectCount; 00184 private: void P3DConnect(); 00185 private: void P3DDisconnect(); 00186 00187 #ifdef USE_CBQ 00188 private: ros::CallbackQueue p3d_queue_; 00189 private: void P3DQueueThread(); 00190 private: boost::thread callback_queue_thread_; 00191 #endif 00192 00193 }; 00194 00196 00197 00198 00199 } 00200 00201 #endif 00202