$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_quadrotor_controller/quadrotor_aerodynamics.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 extern "C" { 00042 #include "quadrotorDrag/quadrotorDrag.h" 00043 #include "quadrotorDrag/quadrotorDrag_initialize.h" 00044 } 00045 00046 #include <boost/array.hpp> 00047 00048 using namespace gazebo; 00049 00050 GZ_REGISTER_DYNAMIC_CONTROLLER("hector_gazebo_quadrotor_aerodynamics", GazeboQuadrotorAerodynamics) 00051 00052 template <typename T> static inline T checknan(const T& value, const std::string& text = "") { 00053 if (!(value == value)) { 00054 if (!text.empty()) std::cerr << text << " contains **!?* Nan values!" << std::endl; 00055 return T(); 00056 } 00057 return value; 00058 } 00059 00060 // extern void quadrotorDrag(const real_T uin[6], const DragParameters parameter, real_T dt, real_T y[6]); 00061 struct GazeboQuadrotorAerodynamics::DragModel { 00062 DragParameters parameters_; 00063 boost::array<real_T,6> u; 00064 boost::array<real_T,6> y; 00065 }; 00066 00067 GazeboQuadrotorAerodynamics::GazeboQuadrotorAerodynamics(Entity *parent) 00068 : Controller(parent) 00069 { 00070 parent_ = dynamic_cast<Model*>(parent); 00071 if (!parent_) gzthrow("GazeboQuadrotorAerodynamics controller requires a Model as its parent"); 00072 00073 if (!ros::isInitialized()) 00074 { 00075 int argc = 0; 00076 char** argv = NULL; 00077 ros::init(argc,argv, "gazebo", ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00078 } 00079 00080 Param::Begin(¶meters); 00081 namespace_ = new ParamT<std::string>("robotNamespace", "", false); 00082 param_namespace_ = new ParamT<std::string>("paramNamespace", "~/quadrotor_aerodynamics", false); 00083 body_name_ = new ParamT<std::string>("bodyName", "", true); 00084 wind_topic_ = new ParamT<std::string>("windTopicName", "wind", false); 00085 Param::End(); 00086 00087 // initialize drag model 00088 quadrotorDrag_initialize(); 00089 drag_model_ = new DragModel; 00090 } 00091 00093 // Destructor 00094 GazeboQuadrotorAerodynamics::~GazeboQuadrotorAerodynamics() 00095 { 00096 delete namespace_; 00097 delete param_namespace_; 00098 delete body_name_; 00099 delete wind_topic_; 00100 00101 delete drag_model_; 00102 } 00103 00105 // Load the controller 00106 void GazeboQuadrotorAerodynamics::LoadChild(XMLConfigNode *node) 00107 { 00108 namespace_->Load(node); 00109 param_namespace_->Load(node); 00110 body_name_->Load(node); 00111 wind_topic_->Load(node); 00112 00113 // assert that the body by body_name_ exists 00114 body_ = dynamic_cast<Body*>(parent_->GetBody(**body_name_)); 00115 if (!body_) gzthrow("gazebo_aerodynamics plugin error: body_name_: " << **body_name_ << "does not exist\n"); 00116 00117 // check update rate against world physics update rate 00118 // should be equal or higher to guarantee the wrench applied is not "diluted" 00119 if (this->updatePeriod > 0 && 00120 (gazebo::World::Instance()->GetPhysicsEngine()->GetUpdateRate() > 1.0/this->updatePeriod)) 00121 ROS_ERROR_NAMED(this->GetName(), "gazebo_aerodynamics controller update rate is less than physics update rate, wrench applied will be diluted (applied intermittently)"); 00122 00123 // get model parameters 00124 ros::NodeHandle param(**param_namespace_); 00125 param.getParam("C_wxy", drag_model_->parameters_.C_wxy); 00126 param.getParam("C_wz", drag_model_->parameters_.C_wz); 00127 param.getParam("C_mxy", drag_model_->parameters_.C_mxy); 00128 param.getParam("C_mz", drag_model_->parameters_.C_mz); 00129 00130 std::cout << "Loaded the following quadrotor drag model parameters from namespace " << param.getNamespace() << ":" << std::endl; 00131 std::cout << "C_wxy = " << drag_model_->parameters_.C_wxy << std::endl; 00132 std::cout << "C_wz = " << drag_model_->parameters_.C_wz << std::endl; 00133 std::cout << "C_mxy = " << drag_model_->parameters_.C_mxy << std::endl; 00134 std::cout << "C_mz = " << drag_model_->parameters_.C_mz << std::endl; 00135 } 00136 00138 // Initialize the controller 00139 void GazeboQuadrotorAerodynamics::InitChild() 00140 { 00141 node_handle_ = new ros::NodeHandle(**namespace_); 00142 00143 // subscribe command 00144 if (!(**wind_topic_).empty()) 00145 { 00146 ros::SubscribeOptions ops = ros::SubscribeOptions::create<geometry_msgs::Vector3>( 00147 **wind_topic_, 1, 00148 boost::bind(&GazeboQuadrotorAerodynamics::WindCallback, this, _1), 00149 ros::VoidPtr(), &callback_queue_); 00150 wind_subscriber_ = node_handle_->subscribe(ops); 00151 } 00152 00153 callback_queue_thread_ = boost::thread( boost::bind( &GazeboQuadrotorAerodynamics::QueueThread,this ) ); 00154 00155 ResetChild(); 00156 } 00157 00159 // Callbacks 00160 void GazeboQuadrotorAerodynamics::WindCallback(const geometry_msgs::Vector3ConstPtr& wind) 00161 { 00162 boost::mutex::scoped_lock lock(wind_mutex_); 00163 wind_ = *wind; 00164 } 00165 00167 // Update the controller 00168 void GazeboQuadrotorAerodynamics::UpdateChild() 00169 { 00170 Vector3 force(0.0, 0.0, 0.0), torque(0.0, 0.0, 0.0); 00171 boost::mutex::scoped_lock lock(wind_mutex_); 00172 00173 // Get simulator time 00174 Time current_time = Simulator::Instance()->GetSimTime(); 00175 double dt = current_time - lastUpdate; 00176 if (dt <= 0.0) return; 00177 00178 // Get new commands/state 00179 // callback_queue_.callAvailable(); 00180 00181 // fill input vector u for drag model 00182 velocity = body_->GetRelativeLinearVel(); 00183 rate = body_->GetRelativeAngularVel(); 00184 drag_model_->u[0] = (velocity.x - wind_.x); 00185 drag_model_->u[1] = -(velocity.y - wind_.y); 00186 drag_model_->u[2] = -(velocity.z - wind_.z); 00187 drag_model_->u[3] = rate.x; 00188 drag_model_->u[4] = -rate.y; 00189 drag_model_->u[5] = -rate.z; 00190 00191 // std::cout << "u = [ "; 00192 // for(std::size_t i = 0; i < drag_model_->u.size(); ++i) 00193 // std::cout << drag_model_->u[i] << " "; 00194 // std::cout << "]" << std::endl; 00195 00196 checknan(drag_model_->u, "drag model input"); 00197 00198 // update drag model 00199 quadrotorDrag(drag_model_->u.data(), drag_model_->parameters_, dt, drag_model_->y.data()); 00200 force = force - checknan(Vector3(drag_model_->y[0], -drag_model_->y[1], -drag_model_->y[2]), "drag model force"); 00201 torque = torque - checknan(Vector3(drag_model_->y[3], -drag_model_->y[4], -drag_model_->y[5]), "drag model torque"); 00202 00203 // set force and torque in gazebo 00204 body_->SetForce(force); 00205 body_->SetTorque(torque - body_->GetMass().GetCoG().GetCrossProd(force)); 00206 } 00207 00209 // Finalize the controller 00210 void GazeboQuadrotorAerodynamics::FiniChild() 00211 { 00212 node_handle_->shutdown(); 00213 callback_queue_thread_.join(); 00214 00215 delete node_handle_; 00216 } 00217 00219 // Reset the controller 00220 void GazeboQuadrotorAerodynamics::ResetChild() 00221 { 00222 } 00223 00225 // custom callback queue thread 00226 void GazeboQuadrotorAerodynamics::QueueThread() 00227 { 00228 static const double timeout = 0.01; 00229 00230 while (node_handle_->ok()) 00231 { 00232 callback_queue_.callAvailable(ros::WallDuration(timeout)); 00233 } 00234 }