quadrotor_propulsion.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2013, 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_model/quadrotor_propulsion.h>
00030 #include <hector_quadrotor_model/helpers.h>
00031 
00032 #include <ros/node_handle.h>
00033 #include <ros/callback_queue.h>
00034 
00035 #include <boost/array.hpp>
00036 
00037 #include "matlab_helpers.h"
00038 
00039 //extern "C" {
00040 //  #include "quadrotorPropulsion/quadrotorPropulsion.h"
00041 //  #include "quadrotorPropulsion/quadrotorPropulsion_initialize.h"
00042 //}
00043 
00044 namespace hector_quadrotor_model {
00045 
00046 struct PropulsionParameters
00047 {
00048     real_T k_m;
00049     real_T k_t;
00050     real_T CT2s;
00051     real_T CT1s;
00052     real_T CT0s;
00053     real_T Psi;
00054     real_T J_M;
00055     real_T R_A;
00056     real_T alpha_m;
00057     real_T beta_m;
00058     real_T l_m;
00059 
00060     PropulsionParameters()
00061       : k_m(0.0)
00062       , k_t(0.0)
00063       , CT2s(0.0)
00064       , CT1s(0.0)
00065       , CT0s(0.0)
00066       , Psi(0.0)
00067       , J_M(std::numeric_limits<real_T>::infinity())
00068       , R_A(std::numeric_limits<real_T>::infinity())
00069       , alpha_m(0.0)
00070       , beta_m(0.0)
00071       , l_m(0.0)
00072     {}
00073 };
00074 
00075 struct QuadrotorPropulsion::PropulsionModel {
00076   PropulsionParameters parameters_;
00077   boost::array<real_T,4>  x;
00078   boost::array<real_T,4>  x_pred;
00079   boost::array<real_T,10> u;
00080   boost::array<real_T,14> y;
00081 };
00082 
00083 QuadrotorPropulsion::QuadrotorPropulsion()
00084 {
00085   // initialize propulsion model
00086   // quadrotorPropulsion_initialize();
00087   propulsion_model_ = new PropulsionModel;
00088 }
00089 
00090 QuadrotorPropulsion::~QuadrotorPropulsion()
00091 {
00092   delete propulsion_model_;
00093 }
00094 
00095 /*
00096  * quadrotorPropulsion.c
00097  *
00098  * Code generation for function 'quadrotorPropulsion'
00099  *
00100  * C source code generated on: Sun Nov  3 13:34:35 2013
00101  *
00102  */
00103 
00104 /* Include files */
00105 //#include "rt_nonfinite.h"
00106 //#include "motorspeed.h"
00107 //#include "quadrotorPropulsion.h"
00108 //#include "quadrotorPropulsion_rtwutil.h"
00109 
00110 /* Type Definitions */
00111 
00112 /* Named Constants */
00113 
00114 /* Variable Declarations */
00115 
00116 /* Variable Definitions */
00117 
00118 /* Function Declarations */
00119 
00120 /* Function Definitions */
00121 void quadrotorPropulsion(const real_T xin[4], const real_T uin[10], const
00122   PropulsionParameters parameter, real_T dt, real_T y[14], real_T xpred[4])
00123 {
00124   real_T v_1[4];
00125   int32_T i;
00126   real_T F_m[4];
00127   real_T U[4];
00128   real_T M_e[4];
00129   real_T I[4];
00130   real_T F[3];
00131   real_T b_F_m;
00132   real_T temp;
00133   real_T d0;
00134 
00135   /*  initialize vectors */
00136   for (i = 0; i < 4; i++) {
00137     xpred[i] = xin[i];
00138 
00139     /*  motorspeed */
00140     v_1[i] = 0.0;
00141   }
00142 
00143   memset(&y[0], 0, 14U * sizeof(real_T));
00144   for (i = 0; i < 4; i++) {
00145     F_m[i] = 0.0;
00146     U[i] = 0.0;
00147     M_e[i] = 0.0;
00148     I[i] = 0.0;
00149   }
00150 
00151   for (i = 0; i < 3; i++) {
00152     F[i] = 0.0;
00153   }
00154 
00155   /*  Input variables */
00156   U[0] = uin[6];
00157   U[1] = uin[7];
00158   U[2] = uin[8];
00159   U[3] = uin[9];
00160 
00161   /*  Constants */
00162   v_1[0] = -uin[2] + parameter.l_m * uin[4];
00163   v_1[1] = -uin[2] - parameter.l_m * uin[3];
00164   v_1[2] = -uin[2] - parameter.l_m * uin[4];
00165   v_1[3] = -uin[2] + parameter.l_m * uin[3];
00166 
00167   /*  calculate thrust for all 4 rotors */
00168   for (i = 0; i < 4; i++) {
00169     /*  if the flow speed at infinity is negative */
00170     if (v_1[i] < 0.0) {
00171       b_F_m = (parameter.CT2s * rt_powd_snf(v_1[i], 2.0) + parameter.CT1s *
00172                v_1[i] * xin[i]) + parameter.CT0s * rt_powd_snf(xin[i], 2.0);
00173 
00174       /*  if the flow speed at infinity is positive */
00175     } else {
00176       b_F_m = (-parameter.CT2s * rt_powd_snf(v_1[i], 2.0) + parameter.CT1s *
00177                v_1[i] * xin[i]) + parameter.CT0s * rt_powd_snf(xin[i], 2.0);
00178     }
00179 
00180     /*  sum up all rotor forces */
00181     /*  Identification of Roxxy2827-34 motor with 10x4.5 propeller */
00182     /*  temporarily used Expressions */
00183     temp = (U[i] * parameter.beta_m - parameter.Psi * xin[i]) / (2.0 *
00184       parameter.R_A);
00185     temp += sqrt(rt_powd_snf(temp, 2.0) + U[i] * parameter.alpha_m /
00186                  parameter.R_A);
00187     d0 = parameter.Psi * temp;
00188 
00189     /*  electrical torque motor 1-4 */
00190     /*  new version */
00191     /*  old version */
00192     /*  fx   = (Psi/R_A*(U-Psi*omega_m) - M_m)/J_M; */
00193     /*  A    = -(Psi^2/R_A)/J_M; */
00194     /*  B(1) =  Psi/(J_M*R_A); */
00195     /*  B(2) = -1/J_M; */
00196     /*  system outputs. Use euler solver to predict next time step */
00197     /*  predicted motor speed */
00198     /*  electric torque */
00199     /* y = [M_e I]; */
00200     /*  system jacobian */
00201     /*  A       = 1 + dt*A; */
00202     /*  input jacobian */
00203     /*  B       = A*B*dt; */
00204     M_e[i] = d0;
00205     I[i] = temp;
00206     xpred[i] = xin[i] + dt * (1.0 / parameter.J_M * (d0 - (parameter.k_t * b_F_m
00207       + parameter.k_m * xin[i])));
00208     F_m[i] = b_F_m;
00209     F[2] += b_F_m;
00210   }
00211 
00212   /*  System output, i.e. force and torque of quadrotor */
00213   y[0] = 0.0;
00214   y[1] = 0.0;
00215   y[2] = F[2];
00216 
00217   /*  torque for rotating quadrocopter around x-axis is the mechanical torque */
00218   y[3] = (F_m[3] - F_m[1]) * parameter.l_m;
00219 
00220   /*  torque for rotating quadrocopter around y-axis is the mechanical torque */
00221   y[4] = (F_m[0] - F_m[2]) * parameter.l_m;
00222 
00223   /*  torque for rotating quadrocopter around z-axis is the electrical torque */
00224   y[5] = ((-M_e[0] - M_e[2]) + M_e[1]) + M_e[3];
00225 
00226   /*  motor speeds (rad/s) */
00227   for (i = 0; i < 4; i++) {
00228     y[i + 6] = xpred[i];
00229   }
00230 
00231   /*  motor current (A) */
00232   for (i = 0; i < 4; i++) {
00233     y[i + 10] = I[i];
00234   }
00235 
00236   /*  M_e(1:4) / Psi; */
00237 }
00238 
00239 /* End of code generation (quadrotorPropulsion.c) */
00240 
00241 inline void QuadrotorPropulsion::f(const double xin[4], const double uin[10], double dt, double y[14], double xpred[4]) const
00242 {
00243   quadrotorPropulsion(xin, uin, propulsion_model_->parameters_, dt, y, xpred);
00244 }
00245 
00246 bool QuadrotorPropulsion::configure(const ros::NodeHandle &param)
00247 {
00248   // get model parameters
00249   if (!param.getParam("k_m",     propulsion_model_->parameters_.k_m)) return false;
00250   if (!param.getParam("k_t",     propulsion_model_->parameters_.k_t)) return false;
00251   if (!param.getParam("CT0s",    propulsion_model_->parameters_.CT0s)) return false;
00252   if (!param.getParam("CT1s",    propulsion_model_->parameters_.CT1s)) return false;
00253   if (!param.getParam("CT2s",    propulsion_model_->parameters_.CT2s)) return false;
00254   if (!param.getParam("J_M",     propulsion_model_->parameters_.J_M)) return false;
00255   if (!param.getParam("l_m",     propulsion_model_->parameters_.l_m)) return false;
00256   if (!param.getParam("Psi",     propulsion_model_->parameters_.Psi)) return false;
00257   if (!param.getParam("R_A",     propulsion_model_->parameters_.R_A)) return false;
00258   if (!param.getParam("alpha_m", propulsion_model_->parameters_.alpha_m)) return false;
00259   if (!param.getParam("beta_m",  propulsion_model_->parameters_.beta_m)) return false;
00260 
00261 #ifndef NDEBUG
00262   std::cout << "Loaded the following quadrotor propulsion model parameters from namespace " << param.getNamespace() << ":" << std::endl;
00263   std::cout << "k_m     = " << propulsion_model_->parameters_.k_m << std::endl;
00264   std::cout << "k_t     = " << propulsion_model_->parameters_.k_t << std::endl;
00265   std::cout << "CT2s    = " << propulsion_model_->parameters_.CT2s << std::endl;
00266   std::cout << "CT1s    = " << propulsion_model_->parameters_.CT1s << std::endl;
00267   std::cout << "CT0s    = " << propulsion_model_->parameters_.CT0s << std::endl;
00268   std::cout << "Psi     = " << propulsion_model_->parameters_.Psi << std::endl;
00269   std::cout << "J_M     = " << propulsion_model_->parameters_.J_M << std::endl;
00270   std::cout << "R_A     = " << propulsion_model_->parameters_.R_A << std::endl;
00271   std::cout << "l_m     = " << propulsion_model_->parameters_.l_m << std::endl;
00272   std::cout << "alpha_m = " << propulsion_model_->parameters_.alpha_m << std::endl;
00273   std::cout << "beta_m  = " << propulsion_model_->parameters_.beta_m << std::endl;
00274 #endif
00275 
00276   initial_voltage_ = 14.8;
00277   param.getParam("supply_voltage", initial_voltage_);
00278   reset();
00279 
00280   return true;
00281 }
00282 
00283 void QuadrotorPropulsion::reset()
00284 {
00285   boost::mutex::scoped_lock lock(mutex_);
00286 
00287   propulsion_model_->x.assign(0.0);
00288   propulsion_model_->x_pred.assign(0.0);
00289   propulsion_model_->u.assign(0.0);
00290   propulsion_model_->y.assign(0.0);
00291 
00292   wrench_ = geometry_msgs::Wrench();
00293 
00294   motor_status_ = hector_uav_msgs::MotorStatus();
00295   motor_status_.voltage.resize(4);
00296   motor_status_.frequency.resize(4);
00297   motor_status_.current.resize(4);
00298 
00299   supply_ = hector_uav_msgs::Supply();
00300   supply_.voltage.resize(1);
00301   supply_.voltage[0] = initial_voltage_;
00302 
00303   last_command_time_ = ros::Time();
00304 
00305   command_queue_ = std::queue<hector_uav_msgs::MotorPWMConstPtr>(); // .clear();
00306 }
00307 
00308 void QuadrotorPropulsion::setVoltage(const hector_uav_msgs::MotorPWM& voltage)
00309 {
00310   boost::mutex::scoped_lock lock(mutex_);
00311   last_command_time_ = voltage.header.stamp;
00312 
00313   if (motor_status_.on && voltage.pwm.size() >= 4) {
00314     propulsion_model_->u[6] = voltage.pwm[0] * supply_.voltage[0] / 255.0;
00315     propulsion_model_->u[7] = voltage.pwm[1] * supply_.voltage[0] / 255.0;
00316     propulsion_model_->u[8] = voltage.pwm[2] * supply_.voltage[0] / 255.0;
00317     propulsion_model_->u[9] = voltage.pwm[3] * supply_.voltage[0] / 255.0;
00318   } else {
00319     propulsion_model_->u[6] = 0.0;
00320     propulsion_model_->u[7] = 0.0;
00321     propulsion_model_->u[8] = 0.0;
00322     propulsion_model_->u[9] = 0.0;
00323   }
00324 }
00325 
00326 void QuadrotorPropulsion::setTwist(const geometry_msgs::Twist &twist)
00327 {
00328   boost::mutex::scoped_lock lock(mutex_);
00329   propulsion_model_->u[0] = twist.linear.x;
00330   propulsion_model_->u[1] = -twist.linear.y;
00331   propulsion_model_->u[2] = -twist.linear.z;
00332   propulsion_model_->u[3] = twist.angular.x;
00333   propulsion_model_->u[4] = -twist.angular.y;
00334   propulsion_model_->u[5] = -twist.angular.z;
00335 
00336   // We limit the input velocities to +-100. Required for numeric stability in case of collisions,
00337   // where velocities returned by Gazebo can be very high.
00338   limit(boost::iterator_range<boost::array<real_T,10>::iterator>(&(propulsion_model_->u[0]), &(propulsion_model_->u[6])), -100.0, 100.0);
00339 }
00340 
00341 void QuadrotorPropulsion::addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr& command)
00342 {
00343   hector_uav_msgs::MotorPWMPtr pwm(new hector_uav_msgs::MotorPWM);
00344   pwm->header = command->header;
00345   pwm->pwm.resize(command->voltage.size());
00346   for(std::size_t i = 0; i < command->voltage.size(); ++i) {
00347     int temp = round(command->voltage[i] / supply_.voltage[0] * 255.0);
00348     if (temp < 0)
00349       pwm->pwm[i] = 0;
00350     else if (temp > 255)
00351       pwm->pwm[i] = 255;
00352     else
00353       pwm->pwm[i] = temp;
00354   }
00355   addPWMToQueue(pwm);
00356 }
00357 
00358 void QuadrotorPropulsion::addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr& pwm)
00359 {
00360   boost::mutex::scoped_lock lock(command_queue_mutex_);
00361 
00362   if (!motor_status_.on) {
00363     ROS_WARN_NAMED("quadrotor_propulsion", "Received new motor command. Enabled motors.");
00364     engage();
00365   }
00366 
00367   ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "Received motor command valid at " << pwm->header.stamp);
00368   command_queue_.push(pwm);
00369   command_condition_.notify_all();
00370 }
00371 
00372 bool QuadrotorPropulsion::processQueue(const ros::Time &timestamp, const ros::Duration &tolerance, const ros::Duration &delay, const ros::WallDuration &wait, ros::CallbackQueue *callback_queue) {
00373   boost::mutex::scoped_lock lock(command_queue_mutex_);
00374   bool new_command = false;
00375 
00376   ros::Time min(timestamp), max(timestamp);
00377   try {
00378     min = timestamp - delay - tolerance /* - ros::Duration(dt) */;
00379   } catch (std::runtime_error &e) {}
00380 
00381   try {
00382     max = timestamp - delay + tolerance;
00383   } catch (std::runtime_error &e) {}
00384 
00385   do {
00386 
00387     while(!command_queue_.empty()) {
00388       hector_uav_msgs::MotorPWMConstPtr new_motor_voltage = command_queue_.front();
00389       ros::Time new_time = new_motor_voltage->header.stamp;
00390 
00391       if (new_time.isZero() || (new_time >= min && new_time <= max)) {
00392         setVoltage(*new_motor_voltage);
00393         command_queue_.pop();
00394         new_command = true;
00395 
00396       // new motor command is too old:
00397       } else if (new_time < min) {
00398         ROS_DEBUG_NAMED("quadrotor_propulsion", "Command received was %fs too old. Discarding.", (new_time - timestamp).toSec());
00399         command_queue_.pop();
00400 
00401       // new motor command is too new:
00402       } else {
00403         break;
00404       }
00405     }
00406 
00407     if (command_queue_.empty() && !new_command) {
00408       if (!motor_status_.on || wait.isZero()) break;
00409 
00410       ROS_DEBUG_NAMED("quadrotor_propulsion", "Waiting for command at simulation step t = %fs... last update was %fs ago", timestamp.toSec(), (timestamp - last_command_time_).toSec());
00411       if (!callback_queue) {
00412         if (command_condition_.timed_wait(lock, wait.toBoost())) continue;
00413       } else {
00414         lock.unlock();
00415         callback_queue->callAvailable(wait);
00416         lock.lock();
00417         if (!command_queue_.empty()) continue;
00418       }
00419 
00420       ROS_ERROR_NAMED("quadrotor_propulsion", "Command timed out. Disabled motors.");
00421       shutdown();
00422     }
00423 
00424   } while(false);
00425 
00426   if (new_command) {
00427       ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "Using motor command valid at t = " << last_command_time_.toSec() << "s for simulation step at t = " << timestamp.toSec() << "s (dt = " << (timestamp - last_command_time_).toSec() << "s)");
00428   }
00429 
00430   return new_command;
00431 }
00432 
00433 void QuadrotorPropulsion::update(double dt)
00434 {
00435   if (dt <= 0.0) return;
00436 
00437   ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.twist:   " << PrintVector<double>(propulsion_model_->u.begin(), propulsion_model_->u.begin() + 6));
00438   ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.voltage: " << PrintVector<double>(propulsion_model_->u.begin() + 6, propulsion_model_->u.begin() + 10));
00439   ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.x_prior: " << PrintVector<double>(propulsion_model_->x.begin(), propulsion_model_->x.end()));
00440 
00441   checknan(propulsion_model_->u, "propulsion model input");
00442   checknan(propulsion_model_->x, "propulsion model state");
00443 
00444   // update propulsion model
00445   f(propulsion_model_->x.data(), propulsion_model_->u.data(), dt, propulsion_model_->y.data(), propulsion_model_->x_pred.data());
00446   propulsion_model_->x = propulsion_model_->x_pred;
00447 
00448   ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.x_post:  " << PrintVector<double>(propulsion_model_->x.begin(), propulsion_model_->x.end()));
00449   ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.force:   " << PrintVector<double>(propulsion_model_->y.begin() + 0, propulsion_model_->y.begin() + 3) << " " <<
00450                                                  "propulsion.torque:  " << PrintVector<double>(propulsion_model_->y.begin() + 3, propulsion_model_->y.begin() + 6));
00451 
00452   checknan(propulsion_model_->y, "propulsion model output");
00453 
00454   wrench_.force.x  =  propulsion_model_->y[0];
00455   wrench_.force.y  = -propulsion_model_->y[1];
00456   wrench_.force.z  =  propulsion_model_->y[2];
00457   wrench_.torque.x =  propulsion_model_->y[3];
00458   wrench_.torque.y = -propulsion_model_->y[4];
00459   wrench_.torque.z = -propulsion_model_->y[5];
00460 
00461   motor_status_.voltage[0] = propulsion_model_->u[6];
00462   motor_status_.voltage[1] = propulsion_model_->u[7];
00463   motor_status_.voltage[2] = propulsion_model_->u[8];
00464   motor_status_.voltage[3] = propulsion_model_->u[9];
00465 
00466   motor_status_.frequency[0] = propulsion_model_->y[6];
00467   motor_status_.frequency[1] = propulsion_model_->y[7];
00468   motor_status_.frequency[2] = propulsion_model_->y[8];
00469   motor_status_.frequency[3] = propulsion_model_->y[9];
00470   motor_status_.running = motor_status_.frequency[0] > 1.0 && motor_status_.frequency[1] > 1.0 && motor_status_.frequency[2] > 1.0 && motor_status_.frequency[3] > 1.0;
00471 
00472   motor_status_.current[0] = propulsion_model_->y[10];
00473   motor_status_.current[1] = propulsion_model_->y[11];
00474   motor_status_.current[2] = propulsion_model_->y[12];
00475   motor_status_.current[3] = propulsion_model_->y[13];
00476 }
00477 
00478 void QuadrotorPropulsion::engage()
00479 {
00480   motor_status_.on = true;
00481 }
00482 
00483 void QuadrotorPropulsion::shutdown()
00484 {
00485   motor_status_.on = false;
00486 }
00487 
00488 } // namespace hector_quadrotor_model


hector_quadrotor_model
Author(s): Johannes Meyer , Alexander Sendobry
autogenerated on Sun Jul 10 2016 04:50:01