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 #include <ros/callback_queue.h> 00031 #include <ros/advertise_options.h> 00032 00033 #include "physics/physics.hh" 00034 #include "transport/TransportTypes.hh" 00035 #include "common/Time.hh" 00036 #include "common/Plugin.hh" 00037 #include "common/Events.hh" 00038 00039 #include <ros/ros.h> 00040 #include <boost/thread.hpp> 00041 #include "boost/thread/mutex.hpp" 00042 #include <nav_msgs/Odometry.h> 00043 00044 namespace gazebo 00045 { 00046 00047 class GazeboRosP3D : public ModelPlugin 00048 { 00050 public: GazeboRosP3D(); 00051 00053 public: virtual ~GazeboRosP3D(); 00054 00056 public: void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf ); 00057 00059 protected: virtual void UpdateChild(); 00060 00061 private: physics::WorldPtr world_; 00062 private: physics::ModelPtr model_; 00063 00065 private: physics::LinkPtr link_; //Gazebo Link 00066 00068 private: physics::LinkPtr reference_link_; 00069 00070 00072 private: ros::NodeHandle* rosnode_; 00073 private: ros::Publisher pub_; 00074 00076 private: nav_msgs::Odometry pose_msg_; 00077 00079 private: std::string link_name_; 00080 00082 private: std::string topic_name_; 00083 00086 private: std::string frame_name_; 00087 private: std::string tf_frame_name_; 00088 00090 private: math::Pose offset_; 00091 00093 private: boost::mutex lock; 00094 00096 private: common::Time last_time_; 00097 private: math::Vector3 last_vpos_; 00098 private: math::Vector3 last_veul_; 00099 private: math::Vector3 apos_; 00100 private: math::Vector3 aeul_; 00101 private: math::Vector3 last_frame_vpos_; 00102 private: math::Vector3 last_frame_veul_; 00103 private: math::Vector3 frame_apos_; 00104 private: math::Vector3 frame_aeul_; 00105 00106 // rate control 00107 private: double update_rate_; 00108 00110 private: double gaussian_noise_; 00111 00113 private: double GaussianKernel(double mu,double sigma); 00114 00116 private: std::string robot_namespace_; 00117 00119 private: int p3d_connect_count_; 00120 private: void P3DConnect(); 00121 private: void P3DDisconnect(); 00122 00123 private: ros::CallbackQueue p3d_queue_; 00124 private: void P3DQueueThread(); 00125 private: boost::thread callback_queue_thread_; 00126 00127 // Pointer to the update event connection 00128 private: event::ConnectionPtr update_connection_; 00129 00130 }; 00131 00133 00134 00135 00136 } 00137 00138 #endif 00139