Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H
00030 #define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H
00031
00032
00033 #ifdef USE_CBQ
00034 #include <ros/callback_queue.h>
00035 #include <ros/advertise_options.h>
00036 #endif
00037
00038 #include <gazebo/common/Plugin.hh>
00039
00040 #include <ros/ros.h>
00041 #include <boost/thread/mutex.hpp>
00042 #include <sensor_msgs/Imu.h>
00043 #include <std_srvs/Empty.h>
00044 #include <hector_gazebo_plugins/SetBias.h>
00045 #include <hector_gazebo_plugins/sensor_model.h>
00046 #include <hector_gazebo_plugins/update_timer.h>
00047
00048 #include <dynamic_reconfigure/server.h>
00049
00050 namespace gazebo
00051 {
00052 class GazeboRosIMU : public ModelPlugin
00053 {
00054 public:
00056 GazeboRosIMU();
00057
00059 virtual ~GazeboRosIMU();
00060
00061 protected:
00062 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00063 virtual void Reset();
00064 virtual void Update();
00065
00066 private:
00068 physics::WorldPtr world;
00069
00071 physics::LinkPtr link;
00072
00074 ros::NodeHandle* node_handle_;
00075 ros::Publisher pub_;
00076 ros::Publisher bias_pub_;
00077
00079 sensor_msgs::Imu imuMsg;
00080 sensor_msgs::Imu biasMsg;
00081
00083 std::string link_name_;
00084
00086 std::string frame_id_;
00087
00089 std::string topic_;
00090 std::string bias_topic_;
00091
00093 math::Pose offset_;
00094
00096 SensorModel3 accelModel;
00097 SensorModel3 rateModel;
00098 SensorModel yawModel;
00099
00101 boost::mutex lock;
00102
00104 math::Quaternion orientation;
00105 math::Vector3 velocity;
00106 math::Vector3 accel;
00107 math::Vector3 rate;
00108 math::Vector3 gravity;
00109
00111 double GaussianKernel(double mu,double sigma);
00112
00114 std::string namespace_;
00115
00117 bool ServiceCallback(std_srvs::Empty::Request &req,
00118 std_srvs::Empty::Response &res);
00119 ros::ServiceServer srv_;
00120 std::string serviceName;
00121
00123 bool SetAccelBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res);
00124 bool SetRateBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res);
00125 ros::ServiceServer accelBiasService;
00126 ros::ServiceServer rateBiasService;
00127
00128 #ifdef USE_CBQ
00129 ros::CallbackQueue callback_queue_;
00130 void CallbackQueueThread();
00131 boost::thread callback_queue_thread_;
00132 #endif
00133
00134 UpdateTimer updateTimer;
00135 event::ConnectionPtr updateConnection;
00136
00137 boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > dynamic_reconfigure_server_accel_, dynamic_reconfigure_server_rate_, dynamic_reconfigure_server_yaw_;
00138 };
00139 }
00140
00141 #endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H