$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 for ground truth. 00023 * Author: Sachin Chitta and John Hsu 00024 * Date: 1 June 2008 00025 * SVN info: $Id$ 00026 */ 00027 00028 #include <gazebo_plugins/gazebo_ros_imu.h> 00029 00030 #include <gazebo/Global.hh> 00031 #include <gazebo/XMLConfig.hh> 00032 #include <gazebo/HingeJoint.hh> 00033 #include <gazebo/SliderJoint.hh> 00034 #include <gazebo/Simulator.hh> 00035 #include <gazebo/gazebo.h> 00036 #include <gazebo/GazeboError.hh> 00037 #include <gazebo/ControllerFactory.hh> 00038 00039 using namespace gazebo; 00040 00041 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_imu", GazeboRosIMU); 00042 00043 00045 // Constructor 00046 GazeboRosIMU::GazeboRosIMU(Entity *parent ) 00047 : Controller(parent) 00048 { 00049 this->myParent = dynamic_cast<Model*>(this->parent); 00050 00051 if (!this->myParent) 00052 gzthrow("GazeboRosIMU controller requires a Model as its parent"); 00053 00054 Param::Begin(&this->parameters); 00055 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00056 this->bodyNameP = new ParamT<std::string>("bodyName", "", 0); 00057 this->frameNameP = new ParamT<std::string>("frameName", "", 0); // deprecated, warning if specified by user 00058 this->topicNameP = new ParamT<std::string>("topicName", "", 1); 00059 this->deprecatedTopicNameP = new ParamT<std::string>("deprecatedTopicName", "", 0); 00060 this->xyzOffsetsP = new ParamT<Vector3>("xyzOffsets", Vector3(0,0,0),0); 00061 this->rpyOffsetsP = new ParamT<Vector3>("rpyOffsets", Vector3(0,0,0),0); 00062 this->gaussianNoiseP = new ParamT<double>("gaussianNoise",0.0,0); 00063 this->serviceNameP = new ParamT<std::string>("serviceName","torso_lift_imu/calibrate", 0); 00064 Param::End(); 00065 00066 this->imuConnectCount = 0; 00067 this->deprecatedImuConnectCount = 0; 00068 } 00069 00071 // Destructor 00072 GazeboRosIMU::~GazeboRosIMU() 00073 { 00074 delete this->robotNamespaceP; 00075 delete this->bodyNameP; 00076 delete this->frameNameP; 00077 delete this->topicNameP; 00078 delete this->deprecatedTopicNameP; 00079 delete this->xyzOffsetsP; 00080 delete this->rpyOffsetsP; 00081 delete this->gaussianNoiseP; 00082 delete this->serviceNameP; 00083 delete this->rosnode_; 00084 } 00085 00087 // Load the controller 00088 void GazeboRosIMU::LoadChild(XMLConfigNode *node) 00089 { 00090 this->robotNamespaceP->Load(node); 00091 this->robotNamespace = this->robotNamespaceP->GetValue(); 00092 if (!ros::isInitialized()) 00093 { 00094 int argc = 0; 00095 char** argv = NULL; 00096 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00097 } 00098 00099 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00100 00101 this->bodyNameP->Load(node); 00102 this->bodyName = this->bodyNameP->GetValue(); 00103 00104 // assert that the body by bodyName exists 00105 if (dynamic_cast<Body*>(this->myParent->GetBody(this->bodyName)) == NULL) 00106 ROS_FATAL("gazebo_ros_imu plugin error: bodyName: %s does not exist\n",this->bodyName.c_str()); 00107 00108 this->myBody = dynamic_cast<Body*>(this->myParent->GetBody(this->bodyName)); 00109 00110 this->frameNameP->Load(node); 00111 if (this->frameNameP->GetValue() != "") 00112 ROS_WARN("Deprecating the ability to specify imu frame_id, this now defaults to the parent imu_link name. Angular velocity and linear acceleration is in local frame and orientation starts with the transform from gazebo world frame to imu_link frame. This is done to mimick hardware on PR2."); 00113 00114 this->topicNameP->Load(node); 00115 this->topicName = this->topicNameP->GetValue(); 00116 this->deprecatedTopicNameP->Load(node); 00117 this->deprecatedTopicName = this->deprecatedTopicNameP->GetValue(); 00118 00119 this->xyzOffsetsP->Load(node); 00120 this->xyzOffsets = this->xyzOffsetsP->GetValue(); 00121 this->rpyOffsetsP->Load(node); 00122 this->rpyOffsets = this->rpyOffsetsP->GetValue(); 00123 this->gaussianNoiseP->Load(node); 00124 this->gaussianNoise = this->gaussianNoiseP->GetValue(); 00125 00126 if (this->topicName != "") 00127 { 00128 #ifdef USE_CBQ 00129 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::Imu>( 00130 this->topicName,1, 00131 boost::bind( &GazeboRosIMU::IMUConnect,this), 00132 boost::bind( &GazeboRosIMU::IMUDisconnect,this), ros::VoidPtr(), &this->imu_queue_); 00133 this->pub_ = this->rosnode_->advertise(ao); 00134 #else 00135 this->pub_ = this->rosnode_->advertise<sensor_msgs::Imu>(this->topicName,10); 00136 #endif 00137 } 00138 00139 00140 if (this->deprecatedTopicName != "") 00141 { 00142 #ifdef USE_CBQ 00143 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::Imu>( 00144 this->deprecatedTopicName,1, 00145 boost::bind( &GazeboRosIMU::DeprecatedIMUConnect,this), 00146 boost::bind( &GazeboRosIMU::DeprecatedIMUDisconnect,this), ros::VoidPtr(), &this->imu_queue_); 00147 this->deprecated_pub_ = this->rosnode_->advertise(ao); 00148 #else 00149 this->deprecated_pub_ = this->rosnode_->advertise<sensor_msgs::Imu>(this->deprecatedTopicName,10); 00150 #endif 00151 } 00152 00153 // add service call version for position change 00154 this->serviceNameP->Load(node); 00155 this->serviceName = this->serviceNameP->GetValue(); 00156 // advertise services on the custom queue 00157 ros::AdvertiseServiceOptions aso = ros::AdvertiseServiceOptions::create<std_srvs::Empty>( 00158 this->serviceName,boost::bind( &GazeboRosIMU::ServiceCallback, this, _1, _2 ), ros::VoidPtr(), &this->imu_queue_); 00159 this->srv_ = this->rosnode_->advertiseService(aso); 00160 00161 } 00162 00164 // returns true always, imu is always calibrated in sim 00165 bool GazeboRosIMU::ServiceCallback(std_srvs::Empty::Request &req, 00166 std_srvs::Empty::Response &res) 00167 { 00168 return true; 00169 } 00170 00172 // Increment count 00173 void GazeboRosIMU::IMUConnect() 00174 { 00175 this->imuConnectCount++; 00176 } 00178 // Decrement count 00179 void GazeboRosIMU::IMUDisconnect() 00180 { 00181 this->imuConnectCount--; 00182 } 00183 00185 // Increment count 00186 void GazeboRosIMU::DeprecatedIMUConnect() 00187 { 00188 ROS_WARN("you are subscribing to a deprecated ROS topic %s, please change your code/launch script to use new ROS topic %s", 00189 this->deprecatedTopicName.c_str(), this->topicName.c_str()); 00190 this->deprecatedImuConnectCount++; 00191 } 00193 // Decrement count 00194 void GazeboRosIMU::DeprecatedIMUDisconnect() 00195 { 00196 this->deprecatedImuConnectCount--; 00197 } 00198 00199 00201 // Initialize the controller 00202 void GazeboRosIMU::InitChild() 00203 { 00204 this->last_time = Simulator::Instance()->GetSimTime(); 00205 //this->initial_pose = this->myBody->GetPose(); // get initial pose of the local link 00206 this->last_vpos = this->myBody->GetWorldLinearVel(); // get velocity in gazebo frame 00207 this->last_veul = this->myBody->GetWorldAngularVel(); // get velocity in gazebo frame 00208 this->apos = 0; 00209 this->aeul = 0; 00210 #ifdef USE_CBQ 00211 // start custom queue for imu 00212 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosIMU::IMUQueueThread,this ) ); 00213 #endif 00214 } 00215 00217 // Update the controller 00218 void GazeboRosIMU::UpdateChild() 00219 { 00220 if ((this->imuConnectCount > 0 && this->topicName != "") || 00221 (this->deprecatedImuConnectCount > 0 && this->deprecatedTopicName != "")) 00222 { 00223 Pose3d pose; 00224 Quatern rot; 00225 Vector3 pos; 00226 00227 // Get Pose/Orientation ///@todo: verify correctness 00228 pose = this->myBody->GetWorldPose(); // - this->myBody->GetCoMPose(); 00229 // apply xyz offsets and get position and rotation components 00230 pos = pose.pos + this->xyzOffsets; 00231 rot = pose.rot; 00232 // std::cout << " --------- GazeboRosIMU rot " << rot.x << ", " << rot.y << ", " << rot.z << ", " << rot.u << std::endl; 00233 00234 // apply rpy offsets 00235 Quatern qOffsets; 00236 qOffsets.SetFromEuler(this->rpyOffsets); 00237 rot = qOffsets*rot; 00238 rot.Normalize(); 00239 00240 gazebo::Time cur_time = Simulator::Instance()->GetSimTime(); 00241 00242 // get Rates 00243 Vector3 vpos = this->myBody->GetWorldLinearVel(); // get velocity in gazebo frame 00244 Vector3 veul = this->myBody->GetWorldAngularVel(); // get velocity in gazebo frame 00245 00246 // differentiate to get accelerations 00247 double tmp_dt = this->last_time.Double() - cur_time.Double(); 00248 if (tmp_dt != 0) 00249 { 00250 this->apos = (this->last_vpos - vpos) / tmp_dt; 00251 this->aeul = (this->last_veul - veul) / tmp_dt; 00252 this->last_vpos = vpos; 00253 this->last_veul = veul; 00254 } 00255 00256 this->lock.lock(); 00257 00258 00259 // copy data into pose message 00260 this->imuMsg.header.frame_id = this->bodyName; 00261 this->imuMsg.header.stamp.sec = cur_time.sec; 00262 this->imuMsg.header.stamp.nsec = cur_time.nsec; 00263 00264 // orientation quaternion 00265 00266 // uncomment this if we are reporting orientation in the local frame 00267 // not the case for our imu definition 00268 // // apply fixed orientation offsets of initial pose 00269 // rot = this->initial_pose.rot*rot; 00270 // rot.Normalize(); 00271 00272 this->imuMsg.orientation.x = rot.x; 00273 this->imuMsg.orientation.y = rot.y; 00274 this->imuMsg.orientation.z = rot.z; 00275 this->imuMsg.orientation.w = rot.u; 00276 00277 // pass euler angular rates 00278 Vector3 linear_velocity(veul.x + this->GaussianKernel(0,this->gaussianNoise) 00279 ,veul.y + this->GaussianKernel(0,this->gaussianNoise) 00280 ,veul.z + this->GaussianKernel(0,this->gaussianNoise)); 00281 // rotate into local frame 00282 // @todo: deal with offsets! 00283 linear_velocity = rot.RotateVector(linear_velocity); 00284 this->imuMsg.angular_velocity.x = linear_velocity.x; 00285 this->imuMsg.angular_velocity.y = linear_velocity.y; 00286 this->imuMsg.angular_velocity.z = linear_velocity.z; 00287 00288 // pass accelerations 00289 Vector3 linear_acceleration(apos.x + this->GaussianKernel(0,this->gaussianNoise) 00290 ,apos.y + this->GaussianKernel(0,this->gaussianNoise) 00291 ,apos.z + this->GaussianKernel(0,this->gaussianNoise)); 00292 // rotate into local frame 00293 // @todo: deal with offsets! 00294 linear_acceleration = rot.RotateVector(linear_acceleration); 00295 this->imuMsg.linear_acceleration.x = linear_acceleration.x; 00296 this->imuMsg.linear_acceleration.y = linear_acceleration.y; 00297 this->imuMsg.linear_acceleration.z = linear_acceleration.z; 00298 00299 // fill in covariance matrix 00302 this->imuMsg.orientation_covariance[0] = this->gaussianNoise*this->gaussianNoise; 00303 this->imuMsg.orientation_covariance[4] = this->gaussianNoise*this->gaussianNoise; 00304 this->imuMsg.orientation_covariance[8] = this->gaussianNoise*this->gaussianNoise; 00305 this->imuMsg.angular_velocity_covariance[0] = this->gaussianNoise*this->gaussianNoise; 00306 this->imuMsg.angular_velocity_covariance[4] = this->gaussianNoise*this->gaussianNoise; 00307 this->imuMsg.angular_velocity_covariance[8] = this->gaussianNoise*this->gaussianNoise; 00308 this->imuMsg.linear_acceleration_covariance[0] = this->gaussianNoise*this->gaussianNoise; 00309 this->imuMsg.linear_acceleration_covariance[4] = this->gaussianNoise*this->gaussianNoise; 00310 this->imuMsg.linear_acceleration_covariance[8] = this->gaussianNoise*this->gaussianNoise; 00311 00312 // publish to ros 00313 if (this->imuConnectCount > 0 && this->topicName != "") 00314 this->pub_.publish(this->imuMsg); 00315 00316 if (this->deprecatedImuConnectCount > 0 && this->deprecatedTopicName != "") 00317 this->deprecated_pub_.publish(this->imuMsg); 00318 00319 this->lock.unlock(); 00320 00321 // save last time stamp 00322 this->last_time = cur_time; 00323 } 00324 } 00325 00327 // Finalize the controller 00328 void GazeboRosIMU::FiniChild() 00329 { 00330 this->rosnode_->shutdown(); 00331 this->callback_queue_thread_.join(); 00332 } 00333 00335 // Utility for adding noise 00336 double GazeboRosIMU::GaussianKernel(double mu,double sigma) 00337 { 00338 // using Box-Muller transform to generate two independent standard normally disbributed normal variables 00339 // see wikipedia 00340 double U = (double)rand()/(double)RAND_MAX; // normalized uniform random variable 00341 double V = (double)rand()/(double)RAND_MAX; // normalized uniform random variable 00342 double X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V); 00343 //double Y = sqrt(-2.0 * ::log(U)) * sin( 2.0*M_PI * V); // the other indep. normal variable 00344 // we'll just use X 00345 // scale to our mu and sigma 00346 X = sigma * X + mu; 00347 return X; 00348 } 00349 00350 #ifdef USE_CBQ 00351 00352 // Put laser data to the interface 00353 void GazeboRosIMU::IMUQueueThread() 00354 { 00355 static const double timeout = 0.01; 00356 00357 while (this->rosnode_->ok()) 00358 { 00359 this->imu_queue_.callAvailable(ros::WallDuration(timeout)); 00360 } 00361 } 00362 #endif