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: IR Controller 00023 * Author: Saeed Anwar 00024 * Date: 21 Jul 2011 00025 */ 00026 00060 #ifndef GAZEBO_ROS_IR_HH 00061 #define GAZEBO_ROS_IR_HH 00062 00063 #define USE_CBQ 00064 #ifdef USE_CBQ 00065 #include <ros/callback_queue.h> 00066 #include <ros/advertise_options.h> 00067 #endif 00068 00069 #include <gazebo/Controller.hh> 00070 #include <gazebo/Param.hh> 00071 #include <gazebo/Time.hh> 00072 00073 #include <ros/ros.h> 00074 #include "boost/thread/mutex.hpp" 00075 #include <sensor_msgs/Range.h> 00076 00077 namespace gazebo 00078 { 00079 00080 class IRSensor; 00081 00085 class GazeboRosIr : public Controller 00086 { 00089 public: GazeboRosIr(Entity *parent); 00090 00092 public: virtual ~GazeboRosIr(); 00093 00097 protected: virtual void LoadChild(XMLConfigNode *node); 00098 00101 protected: virtual void InitChild(); 00102 00105 protected: virtual void UpdateChild(); 00106 00109 protected: virtual void FiniChild(); 00110 00112 private: void PutIRData(); 00113 00115 private: int irConnectCount; 00116 private: void IrConnect(); 00117 private: void IrDisconnect(); 00118 private: int deprecatedIrConnectCount; 00119 private: void DeprecatedIrConnect(); 00120 private: void DeprecatedIrDisconnect(); 00121 00123 private: IRSensor *myParent; 00124 00126 private: ros::NodeHandle* rosnode_; 00127 private: ros::Publisher pub_; 00128 private: ros::Publisher deprecated_pub_; 00129 00131 private: sensor_msgs::Range irMsg; 00132 00134 private: ParamT<std::string> *topicNameP; 00135 private: std::string topicName; 00136 private: ParamT<std::string> *deprecatedTopicNameP; 00137 private: std::string deprecatedTopicName; 00138 00140 private: ParamT<std::string> *frameNameP; 00141 private: std::string frameName; 00142 00144 private: ParamT<double> *gaussianNoiseP; 00145 private: double gaussianNoise; 00146 private: ParamT<std::string> *radiationP; 00147 private: std::string radiation; 00148 00150 private: double GaussianKernel(double mu,double sigma); 00151 00153 private: ParamT<double> *maxRangeP; 00154 private: double maxRange; 00156 private: ParamT<double> *minRangeP; 00157 private: double minRange; 00159 private: ParamT<double> *fovP; 00160 private: double fov; 00161 00163 private: boost::mutex lock; 00164 00166 private: ParamT<std::string> *robotNamespaceP; 00167 private: std::string robotNamespace; 00168 00169 private: libgazebo::IRIface *irIface; 00170 00171 00172 #ifdef USE_CBQ 00173 private: ros::CallbackQueue ir_queue_; 00174 private: void IrQueueThread(); 00175 private: boost::thread callback_queue_thread_; 00176 #endif 00177 00178 }; 00179 00181 00182 00183 } 00184 00185 #endif 00186