multicopterDynamicsSim.hpp
Go to the documentation of this file.
1 
8 #ifndef MULTICOPTERDYNAMICSSIM_H
9 #define MULTICOPTERDYNAMICSSIM_H
10 
11 #include <Eigen/Dense>
12 #include <Eigen/Geometry>
13 #include <vector>
15 
21  public:
22  MulticopterDynamicsSim(int numCopter, double thrustCoefficient, double torqueCoefficient,
23  double minMotorSpeed, double maxMotorSpeed,
24  double motorTimeConstant, double motorRotationalInertia,
25  double vehicleMass,
26  const Eigen::Matrix3d & vehicleInertia,
27  const Eigen::Matrix3d & aeroMomentCoefficient,
28  double dragCoefficient,
29  double momentProcessNoiseAutoCorrelation,
30  double forceProcessNoiseAutoCorrelation,
31  const Eigen::Vector3d & gravity);
32  MulticopterDynamicsSim(int numCopter);
33  void setVehicleProperties(double vehicleMass, const Eigen::Matrix3d & vehicleInertia,
34  const Eigen::Matrix3d & aeroMomentCoefficient,
35  double dragCoefficient,
36  double momentProcessNoiseAutoCorrelation,
37  double forceProcessNoiseAutoCorrelation);
38  void setGravityVector(const Eigen::Vector3d & gravity);
39  void setMotorFrame(const Eigen::Isometry3d & motorFrame, int motorDirection, int motorIndex);
40  void setMotorProperties(double thrustCoefficient, double torqueCoefficient, double motorTimeConstant,
41  double minMotorSpeed, double maxMotorSpeed, double rotationalInertia, int motorIndex);
42  void setMotorProperties(double thrustCoefficient, double torqueCoefficient, double motorTimeConstant,
43  double minMotorSpeed, double maxMotorSpeed, double rotationalInertia);
44  void setMotorSpeed(double motorSpeed, int motorIndex);
45  void setMotorSpeed(double motorSpeed);
46  void resetMotorSpeeds(void);
47  void setVehiclePosition(const Eigen::Vector3d & position,const Eigen::Quaterniond & attitude);
48  void setVehicleInitialAttitude(const Eigen::Quaterniond & attitude);
49  void setVehicleState(const Eigen::Vector3d & position,
50  const Eigen::Vector3d & velocity,
51  const Eigen::Vector3d & angularVelocity,
52  const Eigen::Quaterniond & attitude,
53  const std::vector<double> & motorSpeed);
54  void getVehicleState(Eigen::Vector3d & position,
55  Eigen::Vector3d & velocity,
56  Eigen::Vector3d & angularVelocity,
57  Eigen::Quaterniond & attitude,
58  std::vector<double> & motorSpeed);
59  Eigen::Vector3d getVehiclePosition(void);
60  Eigen::Quaterniond getVehicleAttitude(void);
61  Eigen::Vector3d getVehicleVelocity(void);
62  Eigen::Vector3d getVehicleAngularVelocity(void);
63  const std::vector<double>& getMotorsSpeed() const;
64 
65  void proceedState_ExplicitEuler(double dt_secs, const std::vector<double> & motorSpeedCommand, bool isCmdPercent = false);
66  void proceedState_RK4(double dt_secs, const std::vector<double> & motorSpeedCommand, bool isCmdPercent = false);
67 
68  void getIMUMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput);
69 
72 
73  private:
76 
78 
79 
80  // Transform from motor to vehicle (c.o.g.) frame
81  /* Motor frame must have prop spinning around z-axis such that
82  a positive motor speed corresponds to a positive thrust in
83  positive motor z-axis direction.*/
84  std::vector<Eigen::Isometry3d> motorFrame_;
85 
86  /* +1 if positive motor speed corresponds to positive moment around the motor frame z-axis
87  -1 if positive motor speed corresponds to negative moment around the motor frame z-axis
88  i.e. -1 indicates a positive motor speed corresponds to a positive rotation rate around the motor z-axis
89  */
90  std::vector<int> motorDirection_;
91 
92  std::vector<double> thrustCoefficient_; // N/(rad/s)^2
93  std::vector<double> torqueCoefficient_; // Nm/(rad/s)^2
94  std::vector<double> motorTimeConstant_; // s
95  std::vector<double> motorRotationalInertia_; // kg m^2
96  std::vector<double> maxMotorSpeed_; // rad/s
97  std::vector<double> minMotorSpeed_; // rad/s
99 
101 
102  double dragCoefficient_; // N/(m/s)
103  Eigen::Matrix3d aeroMomentCoefficient_; // Nm/(rad/s)^2
104  double vehicleMass_; // kg
105  Eigen::Matrix3d vehicleInertia_; // kg m^2
106  double momentProcessNoiseAutoCorrelation_ = 0.; // (Nm)^2s
109 
111 
112  std::default_random_engine randomNumberGenerator_;
113  std::normal_distribution<double> standardNormalDistribution_ = std::normal_distribution<double>(0.0,1.0);
115 
116  // Default reference frame is NED, but can be set by changing gravity direction
118  Eigen::Vector3d gravity_; // m/s^2
119 
121 
122  std::vector<double> motorSpeed_; // rad/s
123  Eigen::Vector3d velocity_ = Eigen::Vector3d::Zero(); // m/s
124  Eigen::Vector3d position_ = Eigen::Vector3d::Zero(); // m
125  Eigen::Vector3d angularVelocity_ = Eigen::Vector3d::Zero(); // rad/s
126  Eigen::Quaterniond attitude_ = Eigen::Quaterniond::Identity();
127  Eigen::Quaterniond default_attitude_ = Eigen::Quaterniond::Identity();
129 
130  /* Vehicle stochastic force vector (in world frame) is maintained
131  for accelerometer output, since it must include the same
132  random linear acceleration noise as used for dynamics integration*/
134  Eigen::Vector3d stochForce_ = Eigen::Vector3d::Zero(); // N
135 
136  Eigen::Vector3d getThrust(const std::vector<double> & motorSpeed);
137  Eigen::Vector3d getControlMoment(const std::vector<double> & motorSpeed,
138  const std::vector<double> & motorAcceleration);
139  Eigen::Vector3d getAeroMoment(const Eigen::Vector3d & angularVelocity);
140  Eigen::Vector3d getDragForce(const Eigen::Vector3d & velocity);
141  Eigen::Vector3d getVehicleSpecificForce(void);
142  Eigen::Vector3d getTotalForce(void);
143 
144  void getMotorSpeedDerivative(std::vector<double> & motorSpeedDer,
145  const std::vector<double> & motorSpeed,
146  const std::vector<double> & motorSpeedCommand);
147  Eigen::Vector3d getVelocityDerivative(const Eigen::Quaterniond & attitude, const Eigen::Vector3d & stochForce,
148  const Eigen::Vector3d & velocity, const std::vector<double> & motorSpeed);
149  Eigen::Vector3d getAngularVelocityDerivative(const std::vector<double> & motorSpeed,
150  const std::vector<double>& motorAcceleration,
151  const Eigen::Vector3d & angularVelocity,
152  const Eigen::Vector3d & stochMoment);
153  Eigen::Vector4d getAttitudeDerivative(const Eigen::Quaterniond & attitude, const Eigen::Vector3d & angularVelocity);
154  void vectorAffineOp(const std::vector<double> & vec1, const std::vector<double> & vec2,
155  std::vector<double> & vec3, double val);
156  void vectorScalarProd(const std::vector<double> & vec1, std::vector<double> & vec2, double val);
157  void vectorBoundOp(const std::vector<double> & vec1, std::vector<double> & vec2,
158  const std::vector<double> & minvec, const std::vector<double> & maxvec);
159 };
160 
161 #endif // MULTICOPTERDYNAMICSSIM_H
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::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
Multicopter dynamics simulator class.
Definition: multicopterDynamicsSim.hpp:20
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
inertialMeasurementSim.hpp
Inertial measurement unit (IMU) simulator class header file.
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
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
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
inertialMeasurementSim
Inertial measurement unit (IMU) simulator class.
Definition: inertialMeasurementSim.hpp:19
MulticopterDynamicsSim::imu_
inertialMeasurementSim imu_
Definition: multicopterDynamicsSim.hpp:71
MulticopterDynamicsSim::angularVelocity_
Eigen::Vector3d angularVelocity_
Definition: multicopterDynamicsSim.hpp:125
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