$search
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 <hector_gazebo_plugins/gazebo_ros_gps.h> 00030 00031 #include <gazebo/Sensor.hh> 00032 #include <gazebo/Global.hh> 00033 #include <gazebo/XMLConfig.hh> 00034 #include <gazebo/Simulator.hh> 00035 #include <gazebo/gazebo.h> 00036 #include <gazebo/World.hh> 00037 #include <gazebo/PhysicsEngine.hh> 00038 #include <gazebo/GazeboError.hh> 00039 #include <gazebo/ControllerFactory.hh> 00040 00041 static const double EARTH_RADIUS = 6371000.0; 00042 00043 using namespace gazebo; 00044 00045 GZ_REGISTER_DYNAMIC_CONTROLLER("hector_gazebo_ros_gps", GazeboRosGps) 00046 00047 GazeboRosGps::GazeboRosGps(Entity *parent) 00048 : Controller(parent) 00049 , position_error_model_(parameters) 00050 , velocity_error_model_(parameters, "velocity") 00051 { 00052 parent_ = dynamic_cast<Model*>(parent); 00053 if (!parent_) gzthrow("GazeboRosGps controller requires a Model as its parent"); 00054 00055 if (!ros::isInitialized()) 00056 { 00057 int argc = 0; 00058 char** argv = NULL; 00059 ros::init(argc,argv, "gazebo", ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00060 } 00061 00062 Param::Begin(¶meters); 00063 namespace_ = new ParamT<std::string>("robotNamespace", "", false); 00064 body_name_ = new ParamT<std::string>("bodyName", "", true); 00065 frame_id_ = new ParamT<std::string>("frameId", "", false); 00066 fix_topic_ = new ParamT<std::string>("topicName", "fix", false); 00067 velocity_topic_ = new ParamT<std::string>("velocityTopicName", "fix_velocity", false); 00068 00069 reference_latitude_ = new ParamT<double>("referenceLatitude", 49.9, false); 00070 reference_longitude_ = new ParamT<double>("referenceLongitude", 8.9, false); 00071 reference_heading_ = new ParamT<double>("referenceHeading", 0.0, false); 00072 reference_altitude_ = new ParamT<double>("referenceAltitude", 0.0, false); 00073 status_ = new ParamT<sensor_msgs::NavSatStatus::_status_type>("status", sensor_msgs::NavSatStatus::STATUS_FIX, false); 00074 service_ = new ParamT<sensor_msgs::NavSatStatus::_service_type>("service", sensor_msgs::NavSatStatus::SERVICE_GPS, false); 00075 Param::End(); 00076 } 00077 00079 // Destructor 00080 GazeboRosGps::~GazeboRosGps() 00081 { 00082 delete namespace_; 00083 delete body_name_; 00084 delete frame_id_; 00085 delete fix_topic_; 00086 delete velocity_topic_; 00087 delete reference_latitude_; 00088 delete reference_longitude_; 00089 delete reference_heading_; 00090 delete reference_altitude_; 00091 delete status_; 00092 delete service_; 00093 } 00094 00096 // Load the controller 00097 void GazeboRosGps::LoadChild(XMLConfigNode *node) 00098 { 00099 namespace_->Load(node); 00100 body_name_->Load(node); 00101 frame_id_->Load(node); 00102 fix_topic_->Load(node); 00103 velocity_topic_->Load(node); 00104 00105 // assert that the body by body_name_ exists 00106 body_ = dynamic_cast<Body*>(parent_->GetBody(**body_name_)); 00107 if (!body_) gzthrow("gazebo_quadrotor_simple_controller plugin error: body_name_: " << **body_name_ << "does not exist\n"); 00108 00109 reference_latitude_->Load(node); 00110 reference_longitude_->Load(node); 00111 reference_heading_->Load(node); 00112 reference_altitude_->Load(node); 00113 status_->Load(node); 00114 service_->Load(node); 00115 00116 position_error_model_.Load(node); 00117 velocity_error_model_.Load(node); 00118 00119 reference_heading_->SetValue(**reference_heading_ * M_PI/180.0); // convert to radians 00120 00121 fix_.header.frame_id = **frame_id_; 00122 fix_.status.status = **status_; 00123 fix_.status.service = **service_; 00124 velocity_.header.frame_id = **frame_id_; 00125 } 00126 00128 // Initialize the controller 00129 void GazeboRosGps::InitChild() 00130 { 00131 node_handle_ = new ros::NodeHandle(**namespace_); 00132 fix_publisher_ = node_handle_->advertise<sensor_msgs::NavSatFix>(**fix_topic_, 10); 00133 velocity_publisher_ = node_handle_->advertise<geometry_msgs::Vector3Stamped>(**velocity_topic_, 10); 00134 } 00135 00137 // Update the controller 00138 void GazeboRosGps::UpdateChild() 00139 { 00140 Time sim_time = Simulator::Instance()->GetSimTime(); 00141 double dt = (sim_time - lastUpdate).Double(); 00142 00143 Pose3d pose = body_->GetWorldPose(); 00144 00145 gazebo::Vector3 velocity = velocity_error_model_(body_->GetWorldLinearVel(), dt); 00146 position_error_model_.setCurrentDrift(position_error_model_.getCurrentDrift() + velocity_error_model_.getCurrentError() * dt); 00147 gazebo::Vector3 position = position_error_model_(pose.pos, dt); 00148 00149 fix_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec); 00150 velocity_.header.stamp = fix_.header.stamp; 00151 00152 fix_.latitude = **reference_latitude_ + ( cos(**reference_heading_) * position.x + sin(**reference_heading_) * position.y) / EARTH_RADIUS * 180.0/M_PI; 00153 fix_.longitude = **reference_longitude_ - (-sin(**reference_heading_) * position.x + cos(**reference_heading_) * position.y) / EARTH_RADIUS * 180.0/M_PI * cos(fix_.latitude); 00154 fix_.altitude = **reference_altitude_ + position.z; 00155 fix_.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN; 00156 velocity_.vector.x = cos(**reference_heading_) * velocity.x + sin(**reference_heading_) * velocity.y; 00157 velocity_.vector.y = -sin(**reference_heading_) * velocity.x + cos(**reference_heading_) * velocity.y; 00158 velocity_.vector.z = velocity.z; 00159 00160 fix_publisher_.publish(fix_); 00161 velocity_publisher_.publish(velocity_); 00162 } 00163 00165 // Finalize the controller 00166 void GazeboRosGps::FiniChild() 00167 { 00168 node_handle_->shutdown(); 00169 delete node_handle_; 00170 } 00171