gazebo_ros_gps.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #include <husky_plugin/gazebo_ros_gps.h>
00030 #include <gazebo/physics/physics.hh>
00031 
00032 // WGS84 constants
00033 static const double equatorial_radius = 6378137.0;
00034 static const double flattening = 1.0/298.257223563;
00035 static const double excentrity2 = 2*flattening - flattening*flattening;
00036 
00037 // default reference position
00038 static const double DEFAULT_REFERENCE_LATITUDE  = 49.9;
00039 static const double DEFAULT_REFERENCE_LONGITUDE = 8.9;
00040 static const double DEFAULT_REFERENCE_HEADING   = 0.0;
00041 static const double DEFAULT_REFERENCE_ALTITUDE  = 0.0;
00042 
00043 namespace gazebo {
00044 
00045 GazeboRosGps::GazeboRosGps()
00046 {
00047 }
00048 
00050 // Destructor
00051 GazeboRosGps::~GazeboRosGps()
00052 {
00053   updateTimer.Disconnect(updateConnection);
00054   node_handle_->shutdown();
00055   delete node_handle_;
00056 }
00057 
00059 // Load the controller
00060 void GazeboRosGps::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00061 {
00062   world = _model->GetWorld();
00063 
00064   // load parameters
00065   if (!_sdf->HasElement("robotNamespace"))
00066     namespace_.clear();
00067   else
00068     namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
00069 
00070   if (!_sdf->HasElement("bodyName"))
00071   {
00072     link = _model->GetLink();
00073     link_name_ = link->GetName();
00074   }
00075   else {
00076     link_name_ = _sdf->GetElement("bodyName")->GetValue()->GetAsString();
00077     link = _model->GetLink(link_name_);
00078   }
00079 
00080   if (!link)
00081   {
00082     ROS_FATAL("GazeboRosGps plugin error: bodyName: %s does not exist\n", link_name_.c_str());
00083     return;
00084   }
00085 
00086   // default parameters
00087   frame_id_ = "/world";
00088   fix_topic_ = "fix";
00089   velocity_topic_ = "fix_velocity";
00090 
00091   reference_latitude_  = DEFAULT_REFERENCE_LATITUDE;
00092   reference_longitude_ = DEFAULT_REFERENCE_LONGITUDE;
00093   reference_heading_   = DEFAULT_REFERENCE_HEADING * M_PI/180.0;
00094   reference_altitude_  = DEFAULT_REFERENCE_ALTITUDE;
00095 
00096   status_ = sensor_msgs::NavSatStatus::STATUS_FIX;
00097   service_ = sensor_msgs::NavSatStatus::SERVICE_GPS;
00098 
00099   fix_.header.frame_id = frame_id_;
00100   fix_.status.status  = status_;
00101   fix_.status.service = service_;
00102   velocity_.header.frame_id = frame_id_;
00103 
00104   if (_sdf->HasElement("frameId"))
00105     frame_id_ = _sdf->GetElement("frameId")->GetValue()->GetAsString();
00106 
00107   if (_sdf->HasElement("topicName"))
00108     fix_topic_ = _sdf->GetElement("topicName")->GetValue()->GetAsString();
00109 
00110   if (_sdf->HasElement("velocityTopicName"))
00111     velocity_topic_ = _sdf->GetElement("velocityTopicName")->GetValue()->GetAsString();
00112 
00113   if (_sdf->HasElement("referenceLatitude"))
00114     _sdf->GetElement("referenceLatitude")->GetValue()->Get(reference_latitude_);
00115 
00116   if (_sdf->HasElement("referenceLongitude"))
00117     _sdf->GetElement("referenceLongitude")->GetValue()->Get(reference_longitude_);
00118 
00119   if (_sdf->HasElement("referenceHeading"))
00120     if (_sdf->GetElement("referenceHeading")->GetValue()->Get(reference_heading_))
00121       reference_heading_ *= M_PI/180.0;
00122 
00123   if (_sdf->HasElement("referenceAltitude"))
00124     _sdf->GetElement("referenceAltitude")->GetValue()->Get(reference_altitude_);
00125 
00126   if (_sdf->HasElement("status"))
00127     _sdf->GetElement("status")->GetValue()->Get(status_);
00128 
00129   if (_sdf->HasElement("service"))
00130     _sdf->GetElement("service")->GetValue()->Get(service_);
00131 
00132   fix_.header.frame_id = frame_id_;
00133   fix_.status.status  = status_;
00134   fix_.status.service = service_;
00135   velocity_.header.frame_id = frame_id_;
00136 
00137   position_error_model_.Load(_sdf);
00138   velocity_error_model_.Load(_sdf, "velocity");
00139 
00140   // calculate earth radii
00141   double temp = 1.0 / (1.0 - excentrity2 * sin(reference_latitude_ * M_PI/180.0) * sin(reference_latitude_ * M_PI/180.0));
00142   double prime_vertical_radius = equatorial_radius * sqrt(temp);
00143   radius_north_ = prime_vertical_radius * (1 - excentrity2) * temp;
00144   radius_east_  = prime_vertical_radius * cos(reference_latitude_ * M_PI/180.0);
00145 
00146   // Make sure the ROS node for Gazebo has already been initialized
00147   if (!ros::isInitialized())
00148   {
00149     ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00150       << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00151     return;
00152   }
00153 
00154   node_handle_ = new ros::NodeHandle(namespace_);
00155   fix_publisher_ = node_handle_->advertise<sensor_msgs::NavSatFix>(fix_topic_, 10);
00156   velocity_publisher_ = node_handle_->advertise<geometry_msgs::Vector3Stamped>(velocity_topic_, 10);
00157 
00158   Reset();
00159 
00160   // connect Update function
00161   updateTimer.setUpdateRate(4.0);
00162   updateTimer.Load(world, _sdf);
00163   updateConnection = updateTimer.Connect(boost::bind(&GazeboRosGps::Update, this));
00164 }
00165 
00166 void GazeboRosGps::Reset()
00167 {
00168   updateTimer.Reset();
00169   position_error_model_.reset();
00170   velocity_error_model_.reset();
00171 }
00172 
00174 // Update the controller
00175 void GazeboRosGps::Update()
00176 {
00177   common::Time sim_time = world->GetSimTime();
00178   double dt = updateTimer.getTimeSinceLastUpdate().Double();
00179 
00180   math::Pose pose = link->GetWorldPose();
00181 
00182   gazebo::math::Vector3 velocity = velocity_error_model_(link->GetWorldLinearVel(), dt);
00183   position_error_model_.setCurrentDrift(position_error_model_.getCurrentDrift() + velocity_error_model_.getCurrentError() * dt);
00184   gazebo::math::Vector3 position = position_error_model_(pose.pos, dt);
00185 
00186   fix_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec);
00187   velocity_.header.stamp = fix_.header.stamp;
00188 
00189   fix_.latitude  = reference_latitude_  + ( cos(reference_heading_) * position.x + sin(reference_heading_) * position.y) / radius_north_ * 180.0/M_PI;
00190   fix_.longitude = reference_longitude_ - (-sin(reference_heading_) * position.x + cos(reference_heading_) * position.y) / radius_east_  * 180.0/M_PI;
00191   fix_.altitude  = reference_altitude_  + position.z;
00192   fix_.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
00193   fix_.position_covariance[0] = 0.01;
00194   fix_.position_covariance[4] = 0.01;
00195   fix_.position_covariance[8] = 0.01;
00196   velocity_.vector.x =  cos(reference_heading_) * velocity.x + sin(reference_heading_) * velocity.y;
00197   velocity_.vector.y = -sin(reference_heading_) * velocity.x + cos(reference_heading_) * velocity.y;
00198   velocity_.vector.z = velocity.z;
00199 
00200   fix_publisher_.publish(fix_);
00201   velocity_publisher_.publish(velocity_);
00202 }
00203 
00204 // Register this plugin with the simulator
00205 GZ_REGISTER_MODEL_PLUGIN(GazeboRosGps)
00206 
00207 } // namespace gazebo


husky_gazebo_plugins
Author(s):
autogenerated on Wed Aug 26 2015 11:54:19