Go to the documentation of this file.
8 #ifndef MULTICOPTERDYNAMICSSIM_H
9 #define MULTICOPTERDYNAMICSSIM_H
11 #include <Eigen/Dense>
12 #include <Eigen/Geometry>
23 double minMotorSpeed,
double maxMotorSpeed,
24 double motorTimeConstant,
double motorRotationalInertia,
26 const Eigen::Matrix3d & vehicleInertia,
27 const Eigen::Matrix3d & aeroMomentCoefficient,
28 double dragCoefficient,
29 double momentProcessNoiseAutoCorrelation,
30 double forceProcessNoiseAutoCorrelation,
31 const Eigen::Vector3d & gravity);
34 const Eigen::Matrix3d & aeroMomentCoefficient,
35 double dragCoefficient,
36 double momentProcessNoiseAutoCorrelation,
37 double forceProcessNoiseAutoCorrelation);
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);
47 void setVehiclePosition(
const Eigen::Vector3d & position,
const Eigen::Quaterniond & attitude);
50 const Eigen::Vector3d & velocity,
51 const Eigen::Vector3d & angularVelocity,
52 const Eigen::Quaterniond & attitude,
53 const std::vector<double> & motorSpeed);
55 Eigen::Vector3d & velocity,
56 Eigen::Vector3d & angularVelocity,
57 Eigen::Quaterniond & attitude,
58 std::vector<double> & motorSpeed);
66 void proceedState_RK4(
double dt_secs,
const std::vector<double> & motorSpeedCommand,
bool isCmdPercent =
false);
68 void getIMUMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput);
126 Eigen::Quaterniond
attitude_ = Eigen::Quaterniond::Identity();
136 Eigen::Vector3d
getThrust(
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);
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);
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);
161 #endif // MULTICOPTERDYNAMICSSIM_H
Eigen::Vector3d stochForce_
double momentProcessNoiseAutoCorrelation_
std::vector< double > thrustCoefficient_
std::vector< int > motorDirection_
void vectorScalarProd(const std::vector< double > &vec1, std::vector< double > &vec2, double val)
Vector-scalar product: vec2 = val*vec1.
double forceProcessNoiseAutoCorrelation_
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.
Eigen::Matrix3d aeroMomentCoefficient_
Multicopter dynamics simulator class.
std::vector< double > maxMotorSpeed_
void proceedState_RK4(double dt_secs, const std::vector< double > &motorSpeedCommand, bool isCmdPercent=false)
Proceed vehicle dynamics using 4th order Runge-Kutta integration.
Eigen::Vector3d getTotalForce(void)
Get total force acting on vehicle, including gravity force.
Inertial measurement unit (IMU) simulator class header file.
Eigen::Matrix3d vehicleInertia_
std::vector< Eigen::Isometry3d > motorFrame_
void setVehicleInitialAttitude(const Eigen::Quaterniond &attitude)
std::vector< double > torqueCoefficient_
void setVehicleProperties(double vehicleMass, const Eigen::Matrix3d &vehicleInertia, const Eigen::Matrix3d &aeroMomentCoefficient, double dragCoefficient, double momentProcessNoiseAutoCorrelation, double forceProcessNoiseAutoCorrelation)
Set vehicle properties.
std::normal_distribution< double > standardNormalDistribution_
void getMotorSpeedDerivative(std::vector< double > &motorSpeedDer, const std::vector< double > &motorSpeed, const std::vector< double > &motorSpeedCommand)
Get motor acceleration.
std::default_random_engine randomNumberGenerator_
std::vector< double > minMotorSpeed_
void setMotorSpeed(double motorSpeed, int motorIndex)
Set motor speed for individual motor.
void proceedState_ExplicitEuler(double dt_secs, const std::vector< double > &motorSpeedCommand, bool isCmdPercent=false)
Proceed vehicle dynamics using Explicit Euler integration.
Eigen::Vector3d getThrust(const std::vector< double > &motorSpeed)
Get thrust in vehicle-fixed reference frame.
void getVehicleState(Eigen::Vector3d &position, Eigen::Vector3d &velocity, Eigen::Vector3d &angularVelocity, Eigen::Quaterniond &attitude, std::vector< double > &motorSpeed)
Get vehicle state.
Eigen::Vector3d getControlMoment(const std::vector< double > &motorSpeed, const std::vector< double > &motorAcceleration)
Get control moment in vehicle-fixed reference frame.
std::vector< double > motorTimeConstant_
void setGravityVector(const Eigen::Vector3d &gravity)
Set orientation of world-fixed reference frame using gravity vector.
Eigen::Vector3d getDragForce(const Eigen::Vector3d &velocity)
Get drag force in world-fixed reference frame.
Eigen::Vector3d position_
Eigen::Vector4d getAttitudeDerivative(const Eigen::Quaterniond &attitude, const Eigen::Vector3d &angularVelocity)
Get attitude quaternion time-derivative.
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.
Eigen::Quaterniond attitude_
void setMotorProperties(double thrustCoefficient, double torqueCoefficient, double motorTimeConstant, double minMotorSpeed, double maxMotorSpeed, double rotationalInertia, int motorIndex)
Set properties for individual motor.
std::vector< double > motorRotationalInertia_
void setVehiclePosition(const Eigen::Vector3d &position, const Eigen::Quaterniond &attitude)
Set vehicle position and attitude.
Eigen::Vector3d getVehicleSpecificForce(void)
Get total specific force acting on vehicle, excluding gravity force.
void getIMUMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput)
Get IMU measurement.
std::vector< double > motorSpeed_
Eigen::Quaterniond getVehicleAttitude(void)
Get vehicle attitude.
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.
void setMotorFrame(const Eigen::Isometry3d &motorFrame, int motorDirection, int motorIndex)
Set orientation and position for individual motor.
Eigen::Vector3d getVehicleVelocity(void)
Get vehicle velocity.
void resetMotorSpeeds(void)
Set motor speed to zero for all motors.
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.
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))
Eigen::Vector3d velocity_
Eigen::Vector3d getAeroMoment(const Eigen::Vector3d &angularVelocity)
Get aerodynamic moment in vehicle-fixed reference frame.
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.
const std::vector< double > & getMotorsSpeed() const
Eigen::Vector3d getVehiclePosition(void)
Get vehicle position.
Eigen::Vector3d getVehicleAngularVelocity(void)
Get vehicle angular velocity.
Inertial measurement unit (IMU) simulator class.
inertialMeasurementSim imu_
Eigen::Vector3d angularVelocity_
Eigen::Quaterniond default_attitude_
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35