multicopterDynamicsSim.cpp
Go to the documentation of this file.
1 
8 #include <iostream>
9 #include <chrono>
10 
30 double thrustCoefficient, double torqueCoefficient,
31 double minMotorSpeed, double maxMotorSpeed,
32 double motorTimeConstant, double motorRotationalInertia,
33 double vehicleMass,
34 const Eigen::Matrix3d & vehicleInertia,
35 const Eigen::Matrix3d & aeroMomentCoefficient,
36 double dragCoefficient,
37 double momentProcessNoiseAutoCorrelation,
38 double forceProcessNoiseAutoCorrelation,
39 const Eigen::Vector3d & gravity
40 )
41 : numCopter_(numCopter)
42 , motorFrame_(numCopter)
43 , motorDirection_(numCopter)
44 , motorRotationalInertia_(numCopter)
45 , thrustCoefficient_(numCopter)
46 , torqueCoefficient_(numCopter)
47 , motorSpeed_(numCopter)
48 , motorTimeConstant_(numCopter)
49 , maxMotorSpeed_(numCopter)
50 , minMotorSpeed_(numCopter)
51 {
52  randomNumberGenerator_.seed(std::chrono::system_clock::now().time_since_epoch().count());
53 
54  for (int indx = 0; indx < numCopter; indx++){
55  motorFrame_.at(indx).setIdentity();
56  thrustCoefficient_.at(indx) = thrustCoefficient;
57  torqueCoefficient_.at(indx) = torqueCoefficient;
58  motorTimeConstant_.at(indx) = motorTimeConstant;
59  motorRotationalInertia_.at(indx) = motorRotationalInertia;
60  maxMotorSpeed_.at(indx) = maxMotorSpeed;
61  minMotorSpeed_.at(indx) = minMotorSpeed;
62  motorDirection_.at(indx) = 1;
63  motorSpeed_.at(indx) = 0.;
64  }
65 
66  vehicleMass_ = vehicleMass;
67  vehicleInertia_ = vehicleInertia;
68  aeroMomentCoefficient_ = aeroMomentCoefficient;
69  dragCoefficient_ = dragCoefficient;
70  momentProcessNoiseAutoCorrelation_ = momentProcessNoiseAutoCorrelation;
71  forceProcessNoiseAutoCorrelation_ = forceProcessNoiseAutoCorrelation;
72 
73  gravity_ = gravity;
74 }
75 
83 : numCopter_(numCopter)
84 , motorFrame_(numCopter)
85 , motorDirection_(numCopter)
86 , motorRotationalInertia_(numCopter)
87 , thrustCoefficient_(numCopter)
88 , torqueCoefficient_(numCopter)
89 , motorSpeed_(numCopter)
90 , motorTimeConstant_(numCopter)
91 , maxMotorSpeed_(numCopter)
92 , minMotorSpeed_(numCopter)
93 {
94  randomNumberGenerator_.seed(std::chrono::system_clock::now().time_since_epoch().count());
95 
96  for (int indx = 0; indx < numCopter; indx++){
97  motorFrame_.at(indx).setIdentity();
98  thrustCoefficient_.at(indx) = 0.;
99  torqueCoefficient_.at(indx) = 0.;
100  motorTimeConstant_.at(indx) = 0.;
101  motorRotationalInertia_.at(indx) = 0.;
102  maxMotorSpeed_.at(indx) = 0.;
103  minMotorSpeed_.at(indx) = 0.;
104  motorDirection_.at(indx) = 1;
105  motorSpeed_.at(indx) = 0.;
106  }
107 
108  // Default is NED, but can be set by changing gravity direction
109  gravity_ << 0.,0.,9.81;
110 }
111 
123  const Eigen::Matrix3d & vehicleInertia,
124  const Eigen::Matrix3d & aeroMomentCoefficient,
125  double dragCoefficient,
126  double momentProcessNoiseAutoCorrelation,
127  double forceProcessNoiseAutoCorrelation){
128  vehicleMass_ = vehicleMass;
129  vehicleInertia_ = vehicleInertia;
130  aeroMomentCoefficient_ = aeroMomentCoefficient;
131  dragCoefficient_ = dragCoefficient;
132  momentProcessNoiseAutoCorrelation_ = momentProcessNoiseAutoCorrelation;
133  forceProcessNoiseAutoCorrelation_ = forceProcessNoiseAutoCorrelation;
134 }
135 
141 void MulticopterDynamicsSim::setGravityVector(const Eigen::Vector3d & gravity){
142  gravity_ = gravity;
143 }
144 
155 void MulticopterDynamicsSim::setMotorFrame(const Eigen::Isometry3d & motorFrame, int motorDirection, int motorIndex){
156  motorFrame_.at(motorIndex) = motorFrame;
157  motorDirection_.at(motorIndex) = motorDirection;
158 }
159 
171 void MulticopterDynamicsSim::setMotorProperties(double thrustCoefficient, double torqueCoefficient, double motorTimeConstant,
172  double minMotorSpeed, double maxMotorSpeed, double rotationalInertia, int motorIndex){
173  thrustCoefficient_.at(motorIndex) = thrustCoefficient;
174  torqueCoefficient_.at(motorIndex) = torqueCoefficient;
175  motorTimeConstant_.at(motorIndex) = motorTimeConstant;
176  maxMotorSpeed_.at(motorIndex) = maxMotorSpeed;
177  minMotorSpeed_.at(motorIndex) = minMotorSpeed;
178  motorRotationalInertia_.at(motorIndex) = rotationalInertia;
179 }
180 
191 void MulticopterDynamicsSim::setMotorProperties(double thrustCoefficient, double torqueCoefficient, double motorTimeConstant,
192  double minMotorSpeed, double maxMotorSpeed, double rotationalInertia){
193  for (int motorIndex = 0; motorIndex < numCopter_; motorIndex++){
194  setMotorProperties(thrustCoefficient, torqueCoefficient, motorTimeConstant,
195  minMotorSpeed, maxMotorSpeed, rotationalInertia, motorIndex);
196  }
197 }
198 
205 void MulticopterDynamicsSim::setMotorSpeed(double motorSpeed, int motorIndex){
206  motorSpeed_.at(motorIndex) = motorSpeed;
207 }
208 
209 
216  for (int motorIndex = 0; motorIndex < numCopter_; motorIndex++){
217  setMotorSpeed(motorSpeed, motorIndex);
218  }
219 }
220 
226  for (int indx = 0; indx < numCopter_; indx++){
227  motorSpeed_.at(indx) = 0.;
228  }
229 }
230 
237 void MulticopterDynamicsSim::setVehiclePosition(const Eigen::Vector3d & position,
238  const Eigen::Quaterniond & attitude){
239  position_ = position;
240  attitude_ = attitude;
241 
242  angularVelocity_.setZero();
243  velocity_.setZero();
244 
246 }
247 
248 void MulticopterDynamicsSim::setVehicleInitialAttitude(const Eigen::Quaterniond & attitude){
249  default_attitude_ = attitude;
250 }
251 
261 void MulticopterDynamicsSim::setVehicleState(const Eigen::Vector3d & position,
262  const Eigen::Vector3d & velocity,
263  const Eigen::Vector3d & angularVelocity,
264  const Eigen::Quaterniond & attitude,
265  const std::vector<double> & motorSpeed){
266  position_ = position;
267  velocity_ = velocity;
268  angularVelocity_ = angularVelocity;
269  attitude_ = attitude;
270  for (int indx = 0; indx < numCopter_; indx++){
271  motorSpeed_.at(indx) = motorSpeed.at(indx);
272  }
273 }
274 
284 void MulticopterDynamicsSim::getVehicleState(Eigen::Vector3d & position,
285  Eigen::Vector3d & velocity,
286  Eigen::Vector3d & angularVelocity,
287  Eigen::Quaterniond & attitude,
288  std::vector<double> & motorSpeed){
289  position = position_;
290  velocity = velocity_;
291  angularVelocity = angularVelocity_;
292  attitude = attitude_;
293  motorSpeed = motorSpeed_;
294 }
295 
302  return position_;
303 }
304 
311  return attitude_;
312 }
313 
320  return velocity_;
321 }
322 
329  return angularVelocity_;
330 }
331 
332 const std::vector<double>& MulticopterDynamicsSim::getMotorsSpeed() const{
333  return motorSpeed_;
334 }
335 
342  Eigen::Vector3d specificForce = (getThrust(motorSpeed_) +
344  / vehicleMass_;
345 
346  return specificForce;
347 }
348 
349 
357 }
358 
359 
366 Eigen::Vector3d MulticopterDynamicsSim::getThrust(const std::vector<double> & motorSpeed){
367  Eigen::Vector3d thrust = Eigen::Vector3d::Zero();
368  for (int indx = 0; indx < numCopter_; indx++){
369 
370  Eigen::Vector3d motorThrust(0.,0.,fabs(motorSpeed.at(indx))*motorSpeed.at(indx)*thrustCoefficient_.at(indx));
371  thrust += motorFrame_.at(indx).linear()*motorThrust;
372  }
373  return thrust;
374 }
375 
383 Eigen::Vector3d MulticopterDynamicsSim::getControlMoment(const std::vector<double> & motorSpeed, const std::vector<double> & motorAcceleration){
384  Eigen::Vector3d controlMoment = Eigen::Vector3d::Zero();
385 
386  for (int indx = 0; indx < numCopter_; indx++){
387  // Moment due to thrust
388  Eigen::Vector3d motorThrust(0.,0.,fabs(motorSpeed.at(indx))*motorSpeed.at(indx)*thrustCoefficient_.at(indx));
389  controlMoment += motorFrame_.at(indx).translation().cross(motorFrame_.at(indx).linear()*motorThrust);
390 
391  // Moment due to torque
392  Eigen::Vector3d motorTorque(0.,0.,motorDirection_.at(indx)*fabs(motorSpeed.at(indx))*motorSpeed.at(indx)*torqueCoefficient_.at(indx));
393  motorTorque(2) += motorDirection_.at(indx)*motorRotationalInertia_.at(indx)*motorAcceleration.at(indx);
394  controlMoment += motorFrame_.at(indx).linear()*motorTorque;
395  }
396 
397  return controlMoment;
398 }
399 
406 Eigen::Vector3d MulticopterDynamicsSim::getAeroMoment(const Eigen::Vector3d & angularVelocity){
407  return (-angularVelocity.norm()*aeroMomentCoefficient_*angularVelocity);
408 }
409 
416 Eigen::Vector3d MulticopterDynamicsSim::getDragForce(const Eigen::Vector3d & velocity){
417  return (-dragCoefficient_*velocity.norm()*velocity);
418 }
419 
426 void MulticopterDynamicsSim::getIMUMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput){
427  if( position_.z() < 0.1){
428  Eigen::Vector3d zero_force;
429  zero_force.setZero();
430  imu_.getMeasurement(accOutput, gyroOutput, zero_force, angularVelocity_);
431  accOutput = accOutput - attitude_.inverse()*gravity_;
432  }else{
433  imu_.getMeasurement(accOutput, gyroOutput, getVehicleSpecificForce(), angularVelocity_);
434  }
435 }
436 
443 void MulticopterDynamicsSim::proceedState_ExplicitEuler(double dt_secs, const std::vector<double> & motorSpeedCommandIn, bool isCmdPercent){
444  std::vector<double> motorSpeedCommand = motorSpeedCommandIn;
445  if(isCmdPercent)
446  {
447  for (size_t i = 0; i < motorSpeedCommand.size(); i++)
448  {
449  motorSpeedCommand[i] *= maxMotorSpeed_[i];
450  }
451  }
452 
453  std::vector<double> motorSpeedCommandBounded(numCopter_);
454  vectorBoundOp(motorSpeedCommand,motorSpeedCommandBounded,minMotorSpeed_,maxMotorSpeed_);
455 
456  std::vector<double> motorSpeed(motorSpeed_);
457  Eigen::Vector3d position = position_;
458  Eigen::Vector3d velocity = velocity_;
459  Eigen::Vector3d angularVelocity = angularVelocity_;
460  Eigen::Quaterniond attitude = attitude_;
461 
462  stochForce_ /= sqrt(dt_secs);
463  Eigen::Vector3d stochMoment;
467 
468  std::vector<double> motorSpeedDer(numCopter_);
469  getMotorSpeedDerivative(motorSpeedDer,motorSpeed,motorSpeedCommandBounded);
470  Eigen::Vector3d positionDer = velocity;
471  Eigen::Vector3d velocityDer = getVelocityDerivative(attitude,stochForce_,velocity,motorSpeed);
472  Eigen::Vector4d attitudeDer = getAttitudeDerivative(attitude,angularVelocity);
473  Eigen::Vector3d angularVelocityDer = getAngularVelocityDerivative(motorSpeed,motorSpeedDer,angularVelocity,stochMoment);
474 
475  vectorAffineOp(motorSpeed,motorSpeedDer,motorSpeed_,dt_secs);
477  position_ = position + positionDer*dt_secs;
478  velocity_ = velocity + velocityDer*dt_secs;
479  angularVelocity_ = angularVelocity + angularVelocityDer*dt_secs;
480  attitude_.coeffs() = attitude.coeffs() + attitudeDer*dt_secs;
481 
482  attitude_.normalize();
483 
484  if( position_.z() < 0){
485  position_[2] = 0.00;
486  velocity_ << 0.0, 0.0, 0.0;
487  angularVelocity_ << 0.0, 0.0, 0.0;
489  }
490 
494 
495  imu_.proceedBiasDynamics(dt_secs);
496 }
497 
504 void MulticopterDynamicsSim::proceedState_RK4(double dt_secs, const std::vector<double> & motorSpeedCommandIn, bool isCmdPercent){
505  std::vector<double> motorSpeedCommand = motorSpeedCommandIn;
506 
507  if(isCmdPercent)
508  {
509  for (size_t i = 0; i < motorSpeedCommand.size(); i++)
510  {
511  motorSpeedCommand[i] *= maxMotorSpeed_[i];
512  }
513  }
514  std::vector<double> motorSpeedCommandBounded(numCopter_);
515  vectorBoundOp(motorSpeedCommand,motorSpeedCommandBounded,minMotorSpeed_,maxMotorSpeed_);
516 
517  std::vector<double> motorSpeed(motorSpeed_);
518  Eigen::Vector3d position = position_;
519  Eigen::Vector3d velocity = velocity_;
520  Eigen::Vector3d angularVelocity = angularVelocity_;
521  Eigen::Quaterniond attitude = attitude_;
522 
523  stochForce_ /= sqrt(dt_secs);
524 
525  Eigen::Vector3d stochMoment;
529 
530  // k1
531  std::vector<double> motorSpeedDer(numCopter_);
532  getMotorSpeedDerivative(motorSpeedDer,motorSpeed_,motorSpeedCommandBounded);
533  Eigen::Vector3d positionDer = dt_secs*velocity_;
534  Eigen::Vector3d velocityDer = dt_secs*getVelocityDerivative(attitude_,stochForce_,velocity_,motorSpeed_);
535  Eigen::Vector4d attitudeDer = dt_secs*getAttitudeDerivative(attitude_,angularVelocity_);
536  Eigen::Vector3d angularVelocityDer = dt_secs*getAngularVelocityDerivative(motorSpeed_,motorSpeedDer,angularVelocity_,stochMoment);
537  vectorScalarProd(motorSpeedDer,motorSpeedDer,dt_secs);
538 
539  // x + 1/6*(k1)
540  vectorAffineOp(motorSpeed,motorSpeedDer,motorSpeed,(1./6.));
541  position += (1./6.)*positionDer;
542  velocity += (1./6.)*velocityDer;
543  attitude.coeffs() += (1./6.)*attitudeDer;
544  attitude.normalize();
545  angularVelocity += (1./6.)*angularVelocityDer;
546 
547  // k2
548  std::vector<double> motorSpeedIntermediate(numCopter_);
549  Eigen::Quaterniond attitudeIntermediate;
550 
551  vectorAffineOp(motorSpeed_,motorSpeedDer,motorSpeedIntermediate,0.5); // x + 0.5*(k1)
552  vectorBoundOp(motorSpeedIntermediate,motorSpeedIntermediate,minMotorSpeed_,maxMotorSpeed_);
553  attitudeIntermediate.coeffs() = attitude_.coeffs() + attitudeDer*0.5;
554  attitudeIntermediate.normalize();
555 
556  getMotorSpeedDerivative(motorSpeedDer, motorSpeedIntermediate, motorSpeedCommandBounded);
557  positionDer = dt_secs*(velocity_ + 0.5*velocityDer);
558  velocityDer = dt_secs*getVelocityDerivative(attitudeIntermediate,stochForce_,(velocity_ + 0.5*velocityDer), motorSpeedIntermediate);
559  attitudeDer = dt_secs*getAttitudeDerivative(attitudeIntermediate,(angularVelocity_ + 0.5*angularVelocityDer));
560  angularVelocityDer = dt_secs*getAngularVelocityDerivative(motorSpeedIntermediate,motorSpeedDer,(angularVelocity_ + 0.5*angularVelocityDer),stochMoment);
561  vectorScalarProd(motorSpeedDer, motorSpeedDer, dt_secs);
562 
563  // x + 1/6*(k1 + 2*k2)
564  vectorAffineOp(motorSpeed,motorSpeedDer,motorSpeed,(1./3.));
565  position += (1./3.)*positionDer;
566  velocity += (1./3.)*velocityDer;
567  attitude.coeffs() += (1./3.)*attitudeDer;
568  attitude.normalize();
569  angularVelocity += (1./3.)*angularVelocityDer;
570 
571  // k3
572  vectorAffineOp(motorSpeed_,motorSpeedDer,motorSpeedIntermediate,0.5);
573  vectorBoundOp(motorSpeedIntermediate,motorSpeedIntermediate,minMotorSpeed_,maxMotorSpeed_);
574  attitudeIntermediate.coeffs() = attitude_.coeffs() + attitudeDer*0.5;
575  attitudeIntermediate.normalize();
576 
577  getMotorSpeedDerivative(motorSpeedDer, motorSpeedIntermediate, motorSpeedCommandBounded);
578  positionDer = dt_secs*(velocity_ + 0.5*velocityDer);
579  velocityDer = dt_secs*getVelocityDerivative(attitudeIntermediate,stochForce_,(velocity_ + 0.5*velocityDer), motorSpeedIntermediate);
580  attitudeDer = dt_secs*getAttitudeDerivative(attitudeIntermediate,(angularVelocity_ + 0.5*angularVelocityDer));
581  angularVelocityDer = dt_secs*getAngularVelocityDerivative(motorSpeedIntermediate,motorSpeedDer,(angularVelocity_ + 0.5*angularVelocityDer),stochMoment);
582  vectorScalarProd(motorSpeedDer, motorSpeedDer, dt_secs);
583 
584  // x + 1/6*(k1 + 2*k2 + 2*k3)
585  vectorAffineOp(motorSpeed,motorSpeedDer,motorSpeed,(1./3.));
586  position += (1./3.)*positionDer;
587  velocity += (1./3.)*velocityDer;
588  attitude.coeffs() += (1./3.)*attitudeDer;
589  attitude.normalize();
590  angularVelocity += (1./3.)*angularVelocityDer;
591 
592  // k4
593  vectorAffineOp(motorSpeed_,motorSpeedDer,motorSpeedIntermediate,1.);
594  vectorBoundOp(motorSpeedIntermediate,motorSpeedIntermediate,minMotorSpeed_,maxMotorSpeed_);
595  attitudeIntermediate.coeffs() = attitude_.coeffs() + attitudeDer;
596  attitudeIntermediate.normalize();
597 
598  getMotorSpeedDerivative(motorSpeedDer, motorSpeedIntermediate, motorSpeedCommandBounded);
599  positionDer = dt_secs*(velocity_ + velocityDer);
600  velocityDer = dt_secs*getVelocityDerivative(attitudeIntermediate,stochForce_,(velocity_ + velocityDer), motorSpeedIntermediate);
601  attitudeDer = dt_secs*getAttitudeDerivative(attitudeIntermediate,(angularVelocity_ + angularVelocityDer));
602  angularVelocityDer = dt_secs*getAngularVelocityDerivative(motorSpeedIntermediate,motorSpeedDer,(angularVelocity_ + angularVelocityDer),stochMoment);
603  vectorScalarProd(motorSpeedDer, motorSpeedDer, dt_secs);
604 
605  // x + 1/6*(k1 + 2*k2 + 2*k3 + k4)
606  vectorAffineOp(motorSpeed,motorSpeedDer,motorSpeed_,(1./6.));
608  position_ = position + positionDer*(1./6.);
609  velocity_ = velocity + velocityDer*(1./6.);
610  attitude_.coeffs() = attitude.coeffs() + attitudeDer*(1./6.);
611  attitude_.normalize();
612  angularVelocity_ = angularVelocity + angularVelocityDer*(1./6.);
613 
617 
618  imu_.proceedBiasDynamics(dt_secs);
619 }
620 
629 void MulticopterDynamicsSim::vectorAffineOp(const std::vector<double> & vec1, const std::vector<double> & vec2,
630  std::vector<double> & vec3, double val){
631  std::transform(vec1.begin(), vec1.end(), vec2.begin(), vec3.begin(), [val](const double & vec1val, const double & vec2val)->double{return (vec1val + val*vec2val);});
632 }
633 
642 void MulticopterDynamicsSim::vectorBoundOp(const std::vector<double> & vec1, std::vector<double> & vec2,
643  const std::vector<double> & minvec, const std::vector<double> & maxvec){
644  std::transform(vec1.begin(), vec1.end(), maxvec.begin(), vec2.begin(), [](const double & vec1val, const double & maxvalue)->double{return fmin(vec1val,maxvalue);});
645  std::transform(vec2.begin(), vec2.end(), minvec.begin(), vec2.begin(), [](const double & vec2val, const double & minvalue)->double{return fmax(vec2val,minvalue);});
646 }
647 
655 void MulticopterDynamicsSim::vectorScalarProd(const std::vector<double> & vec1, std::vector<double> & vec2, double val){
656  std::transform(vec1.begin(), vec1.end(), vec2.begin(), [val](const double & vec1val){return vec1val*val;});
657 }
658 
666 void MulticopterDynamicsSim::getMotorSpeedDerivative(std::vector<double> & motorSpeedDer,
667  const std::vector<double> & motorSpeed,
668  const std::vector<double> & motorSpeedCommand){
669  for (int indx = 0; indx < numCopter_; indx++){
670  motorSpeedDer.at(indx) = (motorSpeedCommand.at(indx) - motorSpeed.at(indx))/motorTimeConstant_.at(indx);
671  }
672 }
673 
683 Eigen::Vector3d MulticopterDynamicsSim::getVelocityDerivative(const Eigen::Quaterniond & attitude, const Eigen::Vector3d & stochForce,
684  const Eigen::Vector3d & velocity, const std::vector<double> & motorSpeed){
685  return (gravity_ + (attitude*getThrust(motorSpeed) + getDragForce(velocity) + stochForce)/vehicleMass_);
686 }
687 
695 Eigen::Vector4d MulticopterDynamicsSim::getAttitudeDerivative(const Eigen::Quaterniond & attitude, const Eigen::Vector3d & angularVelocity){
696  Eigen::Quaterniond angularVelocityQuad;
697  angularVelocityQuad.w() = 0;
698  angularVelocityQuad.vec() = angularVelocity;
699 
700  return (0.5*(attitude*angularVelocityQuad).coeffs());
701 }
702 
712 Eigen::Vector3d MulticopterDynamicsSim::getAngularVelocityDerivative(const std::vector<double> & motorSpeed,
713  const std::vector<double>& motorAcceleration, const Eigen::Vector3d & angularVelocity, const Eigen::Vector3d & stochMoment){
714 
715  Eigen::Vector3d angularMomentum = vehicleInertia_*angularVelocity;
716 
717  for (int indx = 0; indx < numCopter_; indx++){
718  Eigen::Vector3d motorAngularMomentum = Eigen::Vector3d::Zero();
719 
720  motorAngularMomentum(2) = -1*motorDirection_.at(indx)*motorRotationalInertia_.at(indx)*motorSpeed.at(indx);
721 
722  angularMomentum += motorFrame_.at(indx).linear()*motorAngularMomentum;
723  }
724 
725  return (vehicleInertia_.inverse()*(getControlMoment(motorSpeed,motorAcceleration) + getAeroMoment(angularVelocity) + stochMoment
726  - angularVelocity.cross(angularMomentum)));
727 }
MulticopterDynamicsSim::stochForce_
Eigen::Vector3d stochForce_
Definition: multicopterDynamicsSim.hpp:134
MulticopterDynamicsSim::momentProcessNoiseAutoCorrelation_
double momentProcessNoiseAutoCorrelation_
Definition: multicopterDynamicsSim.hpp:106
MulticopterDynamicsSim::thrustCoefficient_
std::vector< double > thrustCoefficient_
Definition: multicopterDynamicsSim.hpp:92
MulticopterDynamicsSim::motorDirection_
std::vector< int > motorDirection_
Definition: multicopterDynamicsSim.hpp:90
MulticopterDynamicsSim::vectorScalarProd
void vectorScalarProd(const std::vector< double > &vec1, std::vector< double > &vec2, double val)
Vector-scalar product: vec2 = val*vec1.
Definition: multicopterDynamicsSim.cpp:655
MulticopterDynamicsSim::forceProcessNoiseAutoCorrelation_
double forceProcessNoiseAutoCorrelation_
Definition: multicopterDynamicsSim.hpp:107
multicopterDynamicsSim.hpp
Multicopter dynamics simulator class header file.
MulticopterDynamicsSim::getVelocityDerivative
Eigen::Vector3d getVelocityDerivative(const Eigen::Quaterniond &attitude, const Eigen::Vector3d &stochForce, const Eigen::Vector3d &velocity, const std::vector< double > &motorSpeed)
Get vehicle accelertion in world-fixed reference frame.
Definition: multicopterDynamicsSim.cpp:683
MulticopterDynamicsSim::aeroMomentCoefficient_
Eigen::Matrix3d aeroMomentCoefficient_
Definition: multicopterDynamicsSim.hpp:103
MulticopterDynamicsSim::dragCoefficient_
double dragCoefficient_
Definition: multicopterDynamicsSim.hpp:102
MulticopterDynamicsSim::maxMotorSpeed_
std::vector< double > maxMotorSpeed_
Definition: multicopterDynamicsSim.hpp:96
MulticopterDynamicsSim::proceedState_RK4
void proceedState_RK4(double dt_secs, const std::vector< double > &motorSpeedCommand, bool isCmdPercent=false)
Proceed vehicle dynamics using 4th order Runge-Kutta integration.
Definition: multicopterDynamicsSim.cpp:504
MulticopterDynamicsSim::getTotalForce
Eigen::Vector3d getTotalForce(void)
Get total force acting on vehicle, including gravity force.
Definition: multicopterDynamicsSim.cpp:355
MulticopterDynamicsSim::vehicleInertia_
Eigen::Matrix3d vehicleInertia_
Definition: multicopterDynamicsSim.hpp:105
MulticopterDynamicsSim::motorFrame_
std::vector< Eigen::Isometry3d > motorFrame_
Definition: multicopterDynamicsSim.hpp:84
MulticopterDynamicsSim::setVehicleInitialAttitude
void setVehicleInitialAttitude(const Eigen::Quaterniond &attitude)
Definition: multicopterDynamicsSim.cpp:248
MulticopterDynamicsSim::torqueCoefficient_
std::vector< double > torqueCoefficient_
Definition: multicopterDynamicsSim.hpp:93
MulticopterDynamicsSim::gravity_
Eigen::Vector3d gravity_
Definition: multicopterDynamicsSim.hpp:118
MulticopterDynamicsSim::setVehicleProperties
void setVehicleProperties(double vehicleMass, const Eigen::Matrix3d &vehicleInertia, const Eigen::Matrix3d &aeroMomentCoefficient, double dragCoefficient, double momentProcessNoiseAutoCorrelation, double forceProcessNoiseAutoCorrelation)
Set vehicle properties.
Definition: multicopterDynamicsSim.cpp:122
MulticopterDynamicsSim::standardNormalDistribution_
std::normal_distribution< double > standardNormalDistribution_
Definition: multicopterDynamicsSim.hpp:113
MulticopterDynamicsSim::getMotorSpeedDerivative
void getMotorSpeedDerivative(std::vector< double > &motorSpeedDer, const std::vector< double > &motorSpeed, const std::vector< double > &motorSpeedCommand)
Get motor acceleration.
Definition: multicopterDynamicsSim.cpp:666
MulticopterDynamicsSim::randomNumberGenerator_
std::default_random_engine randomNumberGenerator_
Definition: multicopterDynamicsSim.hpp:112
MulticopterDynamicsSim::minMotorSpeed_
std::vector< double > minMotorSpeed_
Definition: multicopterDynamicsSim.hpp:97
MulticopterDynamicsSim::setMotorSpeed
void setMotorSpeed(double motorSpeed, int motorIndex)
Set motor speed for individual motor.
Definition: multicopterDynamicsSim.cpp:205
MulticopterDynamicsSim::proceedState_ExplicitEuler
void proceedState_ExplicitEuler(double dt_secs, const std::vector< double > &motorSpeedCommand, bool isCmdPercent=false)
Proceed vehicle dynamics using Explicit Euler integration.
Definition: multicopterDynamicsSim.cpp:443
MulticopterDynamicsSim::getThrust
Eigen::Vector3d getThrust(const std::vector< double > &motorSpeed)
Get thrust in vehicle-fixed reference frame.
Definition: multicopterDynamicsSim.cpp:366
MulticopterDynamicsSim::getVehicleState
void getVehicleState(Eigen::Vector3d &position, Eigen::Vector3d &velocity, Eigen::Vector3d &angularVelocity, Eigen::Quaterniond &attitude, std::vector< double > &motorSpeed)
Get vehicle state.
Definition: multicopterDynamicsSim.cpp:284
MulticopterDynamicsSim::getControlMoment
Eigen::Vector3d getControlMoment(const std::vector< double > &motorSpeed, const std::vector< double > &motorAcceleration)
Get control moment in vehicle-fixed reference frame.
Definition: multicopterDynamicsSim.cpp:383
MulticopterDynamicsSim::vehicleMass_
double vehicleMass_
Definition: multicopterDynamicsSim.hpp:104
MulticopterDynamicsSim::motorTimeConstant_
std::vector< double > motorTimeConstant_
Definition: multicopterDynamicsSim.hpp:94
MulticopterDynamicsSim::setGravityVector
void setGravityVector(const Eigen::Vector3d &gravity)
Set orientation of world-fixed reference frame using gravity vector.
Definition: multicopterDynamicsSim.cpp:141
MulticopterDynamicsSim::getDragForce
Eigen::Vector3d getDragForce(const Eigen::Vector3d &velocity)
Get drag force in world-fixed reference frame.
Definition: multicopterDynamicsSim.cpp:416
MulticopterDynamicsSim::position_
Eigen::Vector3d position_
Definition: multicopterDynamicsSim.hpp:124
MulticopterDynamicsSim::getAttitudeDerivative
Eigen::Vector4d getAttitudeDerivative(const Eigen::Quaterniond &attitude, const Eigen::Vector3d &angularVelocity)
Get attitude quaternion time-derivative.
Definition: multicopterDynamicsSim.cpp:695
MulticopterDynamicsSim::numCopter_
int numCopter_
Definition: multicopterDynamicsSim.hpp:75
MulticopterDynamicsSim::vectorAffineOp
void vectorAffineOp(const std::vector< double > &vec1, const std::vector< double > &vec2, std::vector< double > &vec3, double val)
Element-wise affine vector calculus: vec3 = vec1 + val*vec2.
Definition: multicopterDynamicsSim.cpp:629
inertialMeasurementSim::getMeasurement
void getMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput, const Eigen::Vector3d specificForce, const Eigen::Vector3d angularVelocity)
Get IMU measurement.
Definition: inertialMeasurementSim.cpp:116
MulticopterDynamicsSim::attitude_
Eigen::Quaterniond attitude_
Definition: multicopterDynamicsSim.hpp:126
MulticopterDynamicsSim::setMotorProperties
void setMotorProperties(double thrustCoefficient, double torqueCoefficient, double motorTimeConstant, double minMotorSpeed, double maxMotorSpeed, double rotationalInertia, int motorIndex)
Set properties for individual motor.
Definition: multicopterDynamicsSim.cpp:171
MulticopterDynamicsSim::motorRotationalInertia_
std::vector< double > motorRotationalInertia_
Definition: multicopterDynamicsSim.hpp:95
MulticopterDynamicsSim::setVehiclePosition
void setVehiclePosition(const Eigen::Vector3d &position, const Eigen::Quaterniond &attitude)
Set vehicle position and attitude.
Definition: multicopterDynamicsSim.cpp:237
MulticopterDynamicsSim::getVehicleSpecificForce
Eigen::Vector3d getVehicleSpecificForce(void)
Get total specific force acting on vehicle, excluding gravity force.
Definition: multicopterDynamicsSim.cpp:341
MulticopterDynamicsSim::getIMUMeasurement
void getIMUMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput)
Get IMU measurement.
Definition: multicopterDynamicsSim.cpp:426
MulticopterDynamicsSim::motorSpeed_
std::vector< double > motorSpeed_
Definition: multicopterDynamicsSim.hpp:122
MulticopterDynamicsSim::getVehicleAttitude
Eigen::Quaterniond getVehicleAttitude(void)
Get vehicle attitude.
Definition: multicopterDynamicsSim.cpp:310
MulticopterDynamicsSim::setVehicleState
void setVehicleState(const Eigen::Vector3d &position, const Eigen::Vector3d &velocity, const Eigen::Vector3d &angularVelocity, const Eigen::Quaterniond &attitude, const std::vector< double > &motorSpeed)
Set vehicle state.
Definition: multicopterDynamicsSim.cpp:261
MulticopterDynamicsSim::setMotorFrame
void setMotorFrame(const Eigen::Isometry3d &motorFrame, int motorDirection, int motorIndex)
Set orientation and position for individual motor.
Definition: multicopterDynamicsSim.cpp:155
MulticopterDynamicsSim::getVehicleVelocity
Eigen::Vector3d getVehicleVelocity(void)
Get vehicle velocity.
Definition: multicopterDynamicsSim.cpp:319
MulticopterDynamicsSim::resetMotorSpeeds
void resetMotorSpeeds(void)
Set motor speed to zero for all motors.
Definition: multicopterDynamicsSim.cpp:225
MulticopterDynamicsSim::MulticopterDynamicsSim
MulticopterDynamicsSim(int numCopter, double thrustCoefficient, double torqueCoefficient, double minMotorSpeed, double maxMotorSpeed, double motorTimeConstant, double motorRotationalInertia, double vehicleMass, const Eigen::Matrix3d &vehicleInertia, const Eigen::Matrix3d &aeroMomentCoefficient, double dragCoefficient, double momentProcessNoiseAutoCorrelation, double forceProcessNoiseAutoCorrelation, const Eigen::Vector3d &gravity)
Construct a new Multicopter Dynamics Sim object.
Definition: multicopterDynamicsSim.cpp:29
MulticopterDynamicsSim::vectorBoundOp
void vectorBoundOp(const std::vector< double > &vec1, std::vector< double > &vec2, const std::vector< double > &minvec, const std::vector< double > &maxvec)
Element-wise vector bound operation: vec2 = max(minvalue, min(maxvalue, vec1))
Definition: multicopterDynamicsSim.cpp:642
MulticopterDynamicsSim::velocity_
Eigen::Vector3d velocity_
Definition: multicopterDynamicsSim.hpp:123
MulticopterDynamicsSim::getAeroMoment
Eigen::Vector3d getAeroMoment(const Eigen::Vector3d &angularVelocity)
Get aerodynamic moment in vehicle-fixed reference frame.
Definition: multicopterDynamicsSim.cpp:406
MulticopterDynamicsSim::getAngularVelocityDerivative
Eigen::Vector3d getAngularVelocityDerivative(const std::vector< double > &motorSpeed, const std::vector< double > &motorAcceleration, const Eigen::Vector3d &angularVelocity, const Eigen::Vector3d &stochMoment)
Get vehicle angular acceleration in vehicle-fixed reference frame.
Definition: multicopterDynamicsSim.cpp:712
time_since_epoch
double time_since_epoch()
MulticopterDynamicsSim::getMotorsSpeed
const std::vector< double > & getMotorsSpeed() const
Definition: multicopterDynamicsSim.cpp:332
MulticopterDynamicsSim::getVehiclePosition
Eigen::Vector3d getVehiclePosition(void)
Get vehicle position.
Definition: multicopterDynamicsSim.cpp:301
MulticopterDynamicsSim::getVehicleAngularVelocity
Eigen::Vector3d getVehicleAngularVelocity(void)
Get vehicle angular velocity.
Definition: multicopterDynamicsSim.cpp:328
MulticopterDynamicsSim::imu_
inertialMeasurementSim imu_
Definition: multicopterDynamicsSim.hpp:71
MulticopterDynamicsSim::angularVelocity_
Eigen::Vector3d angularVelocity_
Definition: multicopterDynamicsSim.hpp:125
inertialMeasurementSim::proceedBiasDynamics
void proceedBiasDynamics(double dt_secs)
Proceed accelerometer and gyroscope bias dynamics.
Definition: inertialMeasurementSim.cpp:140
MulticopterDynamicsSim::default_attitude_
Eigen::Quaterniond default_attitude_
Definition: multicopterDynamicsSim.hpp:127


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35