quadrotor_aerodynamics.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 <hector_quadrotor_controller/quadrotor_aerodynamics.h>
00030 #include <gazebo/common/Events.hh>
00031 #include <gazebo/physics/physics.hh>
00032 
00033 extern "C" {
00034   #include "quadrotorDrag/quadrotorDrag.h"
00035   #include "quadrotorDrag/quadrotorDrag_initialize.h"
00036 }
00037 
00038 #include <boost/array.hpp>
00039 
00040 namespace gazebo {
00041 
00042 using namespace common;
00043 using namespace math;
00044 
00045 template <typename T> static inline T checknan(const T& value, const std::string& text = "") {
00046   if (!(value == value)) {
00047     if (!text.empty()) std::cerr << text << " contains **!?* Nan values!" << std::endl;
00048     return T();
00049   }
00050   return value;
00051 }
00052 
00053 // extern void quadrotorDrag(const real_T uin[6], const DragParameters parameter, real_T dt, real_T y[6]);
00054 struct GazeboQuadrotorAerodynamics::DragModel {
00055   DragParameters parameters_;
00056   boost::array<real_T,6> u;
00057   boost::array<real_T,6> y;
00058 };
00059 
00060 GazeboQuadrotorAerodynamics::GazeboQuadrotorAerodynamics()
00061 {
00062   // initialize drag model
00063   quadrotorDrag_initialize();
00064   drag_model_ = new DragModel;
00065 }
00066 
00068 // Destructor
00069 GazeboQuadrotorAerodynamics::~GazeboQuadrotorAerodynamics()
00070 {
00071   event::Events::DisconnectWorldUpdateStart(updateConnection);
00072   node_handle_->shutdown();
00073   callback_queue_thread_.join();
00074   delete node_handle_;
00075 
00076   delete drag_model_;
00077 }
00078 
00080 // Load the controller
00081 void GazeboQuadrotorAerodynamics::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00082 {
00083   world = _model->GetWorld();
00084   link = _model->GetLink();
00085 
00086   // load parameters
00087   if (!_sdf->HasElement("robotNamespace"))
00088     namespace_.clear();
00089   else
00090     namespace_ = _sdf->GetElement("robotNamespace")->GetValueString() + "/";
00091 
00092   if (!_sdf->HasElement("paramNamespace"))
00093     param_namespace_ = "~/quadrotor_aerodynamics/";
00094   else
00095     param_namespace_ = _sdf->GetElement("paramNamespace")->GetValueString() + "/";
00096 
00097   if (!_sdf->HasElement("windTopicName"))
00098     wind_topic_ = "wind";
00099   else
00100     wind_topic_ = _sdf->GetElement("windTopicName")->GetValueString();
00101 
00102   // start ros node
00103   if (!ros::isInitialized())
00104   {
00105     int argc = 0;
00106     char **argv = NULL;
00107     ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00108   }
00109 
00110   node_handle_ = new ros::NodeHandle(namespace_);
00111 
00112   // subscribe command
00113   if (!wind_topic_.empty())
00114   {
00115     ros::SubscribeOptions ops = ros::SubscribeOptions::create<geometry_msgs::Vector3>(
00116       wind_topic_, 1,
00117       boost::bind(&GazeboQuadrotorAerodynamics::WindCallback, this, _1),
00118       ros::VoidPtr(), &callback_queue_);
00119     wind_subscriber_ = node_handle_->subscribe(ops);
00120   }
00121 
00122   callback_queue_thread_ = boost::thread( boost::bind( &GazeboQuadrotorAerodynamics::QueueThread,this ) );
00123 
00124   // get model parameters
00125   ros::NodeHandle param(param_namespace_);
00126   param.getParam("C_wxy", drag_model_->parameters_.C_wxy);
00127   param.getParam("C_wz",  drag_model_->parameters_.C_wz);
00128   param.getParam("C_mxy", drag_model_->parameters_.C_mxy);
00129   param.getParam("C_mz",  drag_model_->parameters_.C_mz);
00130 
00131   std::cout << "Loaded the following quadrotor drag model parameters from namespace " << param.getNamespace() << ":" << std::endl;
00132   std::cout << "C_wxy = " << drag_model_->parameters_.C_wxy << std::endl;
00133   std::cout << "C_wz = "  << drag_model_->parameters_.C_wz << std::endl;
00134   std::cout << "C_mxy = " << drag_model_->parameters_.C_mxy << std::endl;
00135   std::cout << "C_mz = "  << drag_model_->parameters_.C_mz << std::endl;
00136 
00137   // New Mechanism for Updating every World Cycle
00138   // Listen to the update event. This event is broadcast every
00139   // simulation iteration.
00140   updateConnection = event::Events::ConnectWorldUpdateStart(
00141       boost::bind(&GazeboQuadrotorAerodynamics::Update, this));
00142 }
00143 
00145 // Callbacks
00146 void GazeboQuadrotorAerodynamics::WindCallback(const geometry_msgs::Vector3ConstPtr& wind)
00147 {
00148   boost::mutex::scoped_lock lock(wind_mutex_);
00149   wind_ = *wind;
00150 }
00151 
00153 // Update the controller
00154 void GazeboQuadrotorAerodynamics::Update()
00155 {
00156   Vector3 force(0.0, 0.0, 0.0), torque(0.0, 0.0, 0.0);
00157   boost::mutex::scoped_lock lock(wind_mutex_);
00158 
00159   // Get simulator time
00160   Time current_time = world->GetSimTime();
00161   Time dt = current_time - last_time_;
00162   last_time_ = current_time;
00163   if (dt <= 0.0) return;
00164 
00165   // Get new commands/state
00166   // callback_queue_.callAvailable();
00167 
00168   // fill input vector u for drag model
00169   velocity = link->GetRelativeLinearVel();
00170   rate = link->GetRelativeAngularVel();
00171   drag_model_->u[0] =  (velocity.x - wind_.x);
00172   drag_model_->u[1] = -(velocity.y - wind_.y);
00173   drag_model_->u[2] = -(velocity.z - wind_.z);
00174   drag_model_->u[3] =  rate.x;
00175   drag_model_->u[4] = -rate.y;
00176   drag_model_->u[5] = -rate.z;
00177 
00178 //  std::cout << "u = [ ";
00179 //  for(std::size_t i = 0; i < drag_model_->u.size(); ++i)
00180 //    std::cout << drag_model_->u[i] << " ";
00181 //  std::cout << "]" << std::endl;
00182 
00183   checknan(drag_model_->u, "drag model input");
00184 
00185   // update drag model
00186   quadrotorDrag(drag_model_->u.data(), drag_model_->parameters_, dt.Double(), drag_model_->y.data());
00187   force  = force  - checknan(Vector3(drag_model_->y[0], -drag_model_->y[1], -drag_model_->y[2]), "drag model force");
00188   torque = torque - checknan(Vector3(drag_model_->y[3], -drag_model_->y[4], -drag_model_->y[5]), "drag model torque");
00189 
00190   // set force and torque in gazebo
00191   link->AddRelativeForce(force);
00192   link->AddRelativeTorque(torque - link->GetInertial()->GetCoG().GetCrossProd(force));
00193 }
00194 
00196 // Reset the controller
00197 void GazeboQuadrotorAerodynamics::Reset()
00198 {
00199 }
00200 
00202 // custom callback queue thread
00203 void GazeboQuadrotorAerodynamics::QueueThread()
00204 {
00205   static const double timeout = 0.01;
00206 
00207   while (node_handle_->ok())
00208   {
00209     callback_queue_.callAvailable(ros::WallDuration(timeout));
00210   }
00211 }
00212 
00213 // Register this plugin with the simulator
00214 GZ_REGISTER_MODEL_PLUGIN(GazeboQuadrotorAerodynamics)
00215 
00216 } // namespace gazebo
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


hector_quadrotor_controller
Author(s): Johannes Meyer and Alexander Sendobry
autogenerated on Mon Jul 15 2013 16:57:22