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 #include <gazebo_plugins/gazebo_ros_imu.h>
00024
00025 namespace gazebo
00026 {
00027
00028 GZ_REGISTER_MODEL_PLUGIN(GazeboRosIMU)
00029
00030
00031
00032 GazeboRosIMU::GazeboRosIMU()
00033 {
00034 this->seed = 0;
00035 }
00036
00038
00039 GazeboRosIMU::~GazeboRosIMU()
00040 {
00041 event::Events::DisconnectWorldUpdateBegin(this->update_connection_);
00042
00043 this->rosnode_->shutdown();
00044 this->callback_queue_thread_.join();
00045 delete this->rosnode_;
00046 }
00047
00049
00050 void GazeboRosIMU::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
00051 {
00052
00053 this->world_ = _parent->GetWorld();
00054 this->sdf = _sdf;
00055
00056
00057 this->deferred_load_thread_ = boost::thread(
00058 boost::bind(&GazeboRosIMU::LoadThread, this));
00059 }
00060
00062
00063 void GazeboRosIMU::LoadThread()
00064 {
00065
00066 this->robot_namespace_ = "";
00067 if (this->sdf->HasElement("robotNamespace"))
00068 this->robot_namespace_ = this->sdf->Get<std::string>("robotNamespace") + "/";
00069
00070 if (!this->sdf->HasElement("serviceName"))
00071 {
00072 ROS_INFO("imu plugin missing <serviceName>, defaults to /default_imu");
00073 this->service_name_ = "/default_imu";
00074 }
00075 else
00076 this->service_name_ = this->sdf->Get<std::string>("serviceName");
00077
00078 if (!this->sdf->HasElement("topicName"))
00079 {
00080 ROS_INFO("imu plugin missing <topicName>, defaults to /default_imu");
00081 this->topic_name_ = "/default_imu";
00082 }
00083 else
00084 this->topic_name_ = this->sdf->Get<std::string>("topicName");
00085
00086 if (!this->sdf->HasElement("gaussianNoise"))
00087 {
00088 ROS_INFO("imu plugin missing <gaussianNoise>, defaults to 0.0");
00089 this->gaussian_noise_ = 0.0;
00090 }
00091 else
00092 this->gaussian_noise_ = this->sdf->Get<double>("gaussianNoise");
00093
00094 if (!this->sdf->HasElement("bodyName"))
00095 {
00096 ROS_FATAL("imu plugin missing <bodyName>, cannot proceed");
00097 return;
00098 }
00099 else
00100 this->link_name_ = this->sdf->Get<std::string>("bodyName");
00101
00102 if (!this->sdf->HasElement("xyzOffset"))
00103 {
00104 ROS_INFO("imu plugin missing <xyzOffset>, defaults to 0s");
00105 this->offset_.pos = math::Vector3(0, 0, 0);
00106 }
00107 else
00108 this->offset_.pos = this->sdf->Get<math::Vector3>("xyzOffset");
00109
00110 if (!this->sdf->HasElement("rpyOffset"))
00111 {
00112 ROS_INFO("imu plugin missing <rpyOffset>, defaults to 0s");
00113 this->offset_.rot = math::Vector3(0, 0, 0);
00114 }
00115 else
00116 this->offset_.rot = this->sdf->Get<math::Vector3>("rpyOffset");
00117
00118 if (!this->sdf->HasElement("updateRate"))
00119 {
00120 ROS_DEBUG("imu plugin missing <updateRate>, defaults to 0.0"
00121 " (as fast as possible)");
00122 this->update_rate_ = 0.0;
00123 }
00124 else
00125 this->update_rate_ = this->sdf->GetElement("updateRate")->Get<double>();
00126
00127
00128
00129 if (!ros::isInitialized())
00130 {
00131 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00132 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00133 return;
00134 }
00135
00136 this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00137
00138
00139 this->pmq.startServiceThread();
00140
00141
00142 this->link = boost::dynamic_pointer_cast<physics::Link>(
00143 this->world_->GetEntity(this->link_name_));
00144 if (!this->link)
00145 {
00146 ROS_FATAL("gazebo_ros_imu plugin error: bodyName: %s does not exist\n",
00147 this->link_name_.c_str());
00148 return;
00149 }
00150
00151
00152 if (this->topic_name_ != "")
00153 {
00154 this->pub_Queue = this->pmq.addPub<sensor_msgs::Imu>();
00155 this->pub_ = this->rosnode_->advertise<sensor_msgs::Imu>(
00156 this->topic_name_, 1);
00157
00158
00159 ros::AdvertiseServiceOptions aso =
00160 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00161 this->service_name_, boost::bind(&GazeboRosIMU::ServiceCallback,
00162 this, _1, _2), ros::VoidPtr(), &this->imu_queue_);
00163 this->srv_ = this->rosnode_->advertiseService(aso);
00164 }
00165
00166
00167 this->last_time_ = this->world_->GetSimTime();
00168
00169
00170 this->last_vpos_ = this->link->GetWorldLinearVel();
00171 this->last_veul_ = this->link->GetWorldAngularVel();
00172 this->apos_ = 0;
00173 this->aeul_ = 0;
00174
00175
00176 this->callback_queue_thread_ =
00177 boost::thread(boost::bind(&GazeboRosIMU::IMUQueueThread, this));
00178
00179
00180
00181
00182
00183 this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
00184 boost::bind(&GazeboRosIMU::UpdateChild, this));
00185 }
00186
00188
00189 bool GazeboRosIMU::ServiceCallback(std_srvs::Empty::Request &req,
00190 std_srvs::Empty::Response &res)
00191 {
00192 return true;
00193 }
00194
00196
00197 void GazeboRosIMU::UpdateChild()
00198 {
00199 common::Time cur_time = this->world_->GetSimTime();
00200
00201
00202 if (this->update_rate_ > 0 &&
00203 (cur_time - this->last_time_).Double() < (1.0 / this->update_rate_))
00204 return;
00205
00206 if ((this->pub_.getNumSubscribers() > 0 && this->topic_name_ != ""))
00207 {
00208 math::Pose pose;
00209 math::Quaternion rot;
00210 math::Vector3 pos;
00211
00212
00213 pose = this->link->GetWorldPose();
00214
00215 pos = pose.pos + this->offset_.pos;
00216 rot = pose.rot;
00217
00218
00219 rot = this->offset_.rot*rot;
00220 rot.Normalize();
00221
00222
00223 math::Vector3 vpos = this->link->GetWorldLinearVel();
00224 math::Vector3 veul = this->link->GetWorldAngularVel();
00225
00226
00227 double tmp_dt = this->last_time_.Double() - cur_time.Double();
00228 if (tmp_dt != 0)
00229 {
00230 this->apos_ = (this->last_vpos_ - vpos) / tmp_dt;
00231 this->aeul_ = (this->last_veul_ - veul) / tmp_dt;
00232 this->last_vpos_ = vpos;
00233 this->last_veul_ = veul;
00234 }
00235
00236
00237 this->imu_msg_.header.frame_id = this->link_name_;
00238 this->imu_msg_.header.stamp.sec = cur_time.sec;
00239 this->imu_msg_.header.stamp.nsec = cur_time.nsec;
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249 this->imu_msg_.orientation.x = rot.x;
00250 this->imu_msg_.orientation.y = rot.y;
00251 this->imu_msg_.orientation.z = rot.z;
00252 this->imu_msg_.orientation.w = rot.w;
00253
00254
00255 math::Vector3 linear_velocity(
00256 veul.x + this->GaussianKernel(0, this->gaussian_noise_),
00257 veul.y + this->GaussianKernel(0, this->gaussian_noise_),
00258 veul.z + this->GaussianKernel(0, this->gaussian_noise_));
00259
00260
00261 linear_velocity = rot.RotateVector(linear_velocity);
00262 this->imu_msg_.angular_velocity.x = linear_velocity.x;
00263 this->imu_msg_.angular_velocity.y = linear_velocity.y;
00264 this->imu_msg_.angular_velocity.z = linear_velocity.z;
00265
00266
00267 math::Vector3 linear_acceleration(
00268 apos_.x + this->GaussianKernel(0, this->gaussian_noise_),
00269 apos_.y + this->GaussianKernel(0, this->gaussian_noise_),
00270 apos_.z + this->GaussianKernel(0, this->gaussian_noise_));
00271
00272
00273 linear_acceleration = rot.RotateVector(linear_acceleration);
00274 this->imu_msg_.linear_acceleration.x = linear_acceleration.x;
00275 this->imu_msg_.linear_acceleration.y = linear_acceleration.y;
00276 this->imu_msg_.linear_acceleration.z = linear_acceleration.z;
00277
00278
00281 double gn2 = this->gaussian_noise_*this->gaussian_noise_;
00282 this->imu_msg_.orientation_covariance[0] = gn2;
00283 this->imu_msg_.orientation_covariance[4] = gn2;
00284 this->imu_msg_.orientation_covariance[8] = gn2;
00285 this->imu_msg_.angular_velocity_covariance[0] = gn2;
00286 this->imu_msg_.angular_velocity_covariance[4] = gn2;
00287 this->imu_msg_.angular_velocity_covariance[8] = gn2;
00288 this->imu_msg_.linear_acceleration_covariance[0] = gn2;
00289 this->imu_msg_.linear_acceleration_covariance[4] = gn2;
00290 this->imu_msg_.linear_acceleration_covariance[8] = gn2;
00291
00292 {
00293 boost::mutex::scoped_lock lock(this->lock_);
00294
00295 if (this->pub_.getNumSubscribers() > 0 && this->topic_name_ != "")
00296 this->pub_Queue->push(this->imu_msg_, this->pub_);
00297 }
00298
00299
00300 this->last_time_ = cur_time;
00301 }
00302 }
00303
00304
00306
00307 double GazeboRosIMU::GaussianKernel(double mu, double sigma)
00308 {
00309
00310
00311
00312
00313 double U = static_cast<double>(rand_r(&this->seed)) /
00314 static_cast<double>(RAND_MAX);
00315
00316
00317 double V = static_cast<double>(rand_r(&this->seed)) /
00318 static_cast<double>(RAND_MAX);
00319
00320 double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
00321
00322
00323
00324
00325 X = sigma * X + mu;
00326 return X;
00327 }
00328
00330
00331 void GazeboRosIMU::IMUQueueThread()
00332 {
00333 static const double timeout = 0.01;
00334
00335 while (this->rosnode_->ok())
00336 {
00337 this->imu_queue_.callAvailable(ros::WallDuration(timeout));
00338 }
00339 }
00340 }