Multicopter dynamics simulator class. More...
#include <multicopterDynamicsSim.hpp>
Public Member Functions | |
| void | getIMUMeasurement (Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput) |
| Get IMU measurement. More... | |
| const std::vector< double > & | getMotorsSpeed () const |
| Eigen::Vector3d | getVehicleAngularVelocity (void) |
| Get vehicle angular velocity. More... | |
| Eigen::Quaterniond | getVehicleAttitude (void) |
| Get vehicle attitude. More... | |
| Eigen::Vector3d | getVehiclePosition (void) |
| Get vehicle position. More... | |
| void | getVehicleState (Eigen::Vector3d &position, Eigen::Vector3d &velocity, Eigen::Vector3d &angularVelocity, Eigen::Quaterniond &attitude, std::vector< double > &motorSpeed) |
| Get vehicle state. More... | |
| Eigen::Vector3d | getVehicleVelocity (void) |
| Get vehicle velocity. More... | |
| MulticopterDynamicsSim (int numCopter) | |
| Brief constructor for a new Multicopter Dynamics Sim object; vehicle properties must still be set seperately. More... | |
| 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. More... | |
| void | proceedState_ExplicitEuler (double dt_secs, const std::vector< double > &motorSpeedCommand, bool isCmdPercent=false) |
| Proceed vehicle dynamics using Explicit Euler integration. More... | |
| void | proceedState_RK4 (double dt_secs, const std::vector< double > &motorSpeedCommand, bool isCmdPercent=false) |
| Proceed vehicle dynamics using 4th order Runge-Kutta integration. More... | |
| void | resetMotorSpeeds (void) |
| Set motor speed to zero for all motors. More... | |
| void | setGravityVector (const Eigen::Vector3d &gravity) |
| Set orientation of world-fixed reference frame using gravity vector. More... | |
| void | setMotorFrame (const Eigen::Isometry3d &motorFrame, int motorDirection, int motorIndex) |
| Set orientation and position for individual motor. More... | |
| void | setMotorProperties (double thrustCoefficient, double torqueCoefficient, double motorTimeConstant, double minMotorSpeed, double maxMotorSpeed, double rotationalInertia) |
| Set properties for all motors. More... | |
| void | setMotorProperties (double thrustCoefficient, double torqueCoefficient, double motorTimeConstant, double minMotorSpeed, double maxMotorSpeed, double rotationalInertia, int motorIndex) |
| Set properties for individual motor. More... | |
| void | setMotorSpeed (double motorSpeed) |
| Set motor speed for all motors. More... | |
| void | setMotorSpeed (double motorSpeed, int motorIndex) |
| Set motor speed for individual motor. More... | |
| void | setVehicleInitialAttitude (const Eigen::Quaterniond &attitude) |
| void | setVehiclePosition (const Eigen::Vector3d &position, const Eigen::Quaterniond &attitude) |
| Set vehicle position and attitude. More... | |
| void | setVehicleProperties (double vehicleMass, const Eigen::Matrix3d &vehicleInertia, const Eigen::Matrix3d &aeroMomentCoefficient, double dragCoefficient, double momentProcessNoiseAutoCorrelation, double forceProcessNoiseAutoCorrelation) |
| Set vehicle properties. More... | |
| 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. More... | |
Public Attributes | |
IMU simulator | |
| inertialMeasurementSim | imu_ = inertialMeasurementSim(0.,0.,0.,0.) |
Private Attributes | |
Number of rotors | |
| int | numCopter_ |
Motor properties | |
| std::vector< Eigen::Isometry3d > | motorFrame_ |
| std::vector< int > | motorDirection_ |
| std::vector< double > | thrustCoefficient_ |
| std::vector< double > | torqueCoefficient_ |
| std::vector< double > | motorTimeConstant_ |
| std::vector< double > | motorRotationalInertia_ |
| std::vector< double > | maxMotorSpeed_ |
| std::vector< double > | minMotorSpeed_ |
Vehicle properties | |
| double | dragCoefficient_ |
| Eigen::Matrix3d | aeroMomentCoefficient_ |
| double | vehicleMass_ |
| Eigen::Matrix3d | vehicleInertia_ |
| double | momentProcessNoiseAutoCorrelation_ = 0. |
| double | forceProcessNoiseAutoCorrelation_ = 0. |
Std normal RNG | |
| std::default_random_engine | randomNumberGenerator_ |
| std::normal_distribution< double > | standardNormalDistribution_ = std::normal_distribution<double>(0.0,1.0) |
Gravity vector | |
| Eigen::Vector3d | gravity_ |
Vehicle state variables | |
| std::vector< double > | motorSpeed_ |
| Eigen::Vector3d | velocity_ = Eigen::Vector3d::Zero() |
| Eigen::Vector3d | position_ = Eigen::Vector3d::Zero() |
| Eigen::Vector3d | angularVelocity_ = Eigen::Vector3d::Zero() |
| Eigen::Quaterniond | attitude_ = Eigen::Quaterniond::Identity() |
| Eigen::Quaterniond | default_attitude_ = Eigen::Quaterniond::Identity() |
Vehicle stochastic force vector | |
| Eigen::Vector3d | stochForce_ = Eigen::Vector3d::Zero() |
| Eigen::Vector3d | getThrust (const std::vector< double > &motorSpeed) |
| Get thrust in vehicle-fixed reference frame. More... | |
| Eigen::Vector3d | getControlMoment (const std::vector< double > &motorSpeed, const std::vector< double > &motorAcceleration) |
| Get control moment in vehicle-fixed reference frame. More... | |
| Eigen::Vector3d | getAeroMoment (const Eigen::Vector3d &angularVelocity) |
| Get aerodynamic moment in vehicle-fixed reference frame. More... | |
| Eigen::Vector3d | getDragForce (const Eigen::Vector3d &velocity) |
| Get drag force in world-fixed reference frame. More... | |
| Eigen::Vector3d | getVehicleSpecificForce (void) |
| Get total specific force acting on vehicle, excluding gravity force. More... | |
| Eigen::Vector3d | getTotalForce (void) |
| Get total force acting on vehicle, including gravity force. More... | |
| void | getMotorSpeedDerivative (std::vector< double > &motorSpeedDer, const std::vector< double > &motorSpeed, const std::vector< double > &motorSpeedCommand) |
| Get motor acceleration. More... | |
| 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. More... | |
| 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. More... | |
| Eigen::Vector4d | getAttitudeDerivative (const Eigen::Quaterniond &attitude, const Eigen::Vector3d &angularVelocity) |
| Get attitude quaternion time-derivative. More... | |
| 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. More... | |
| void | vectorScalarProd (const std::vector< double > &vec1, std::vector< double > &vec2, double val) |
| Vector-scalar product: vec2 = val*vec1. More... | |
| 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)) More... | |
Multicopter dynamics simulator class.
Definition at line 20 of file multicopterDynamicsSim.hpp.
| 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.
| numCopter | Number of motors (e.g. 4 for a quadcopter) |
| thrustCoefficient | Motors thrust coefficient |
| torqueCoefficient | Motors torque coefficient |
| minMotorSpeed | Motors minimum rotation speed |
| maxMotorSpeed | Motors maximum rotation speed |
| motorTimeConstant | Motors time constant |
| motorRotationalInertia | Motors rotational mass moment of inertia (including propeller) |
| vehicleMass | Vehicle mass |
| vehicleInertia | Vehicle inertia matrix |
| aeroMomentCoefficient | Vehicle aerodynamic moment coefficient matrix |
| dragCoefficient | Vehicle drag coefficient |
| momentProcessNoiseAutoCorrelation | Vehicle dynamics stochastic moment process noise auto correlation |
| forceProcessNoiseAutoCorrelation | Vehicle dynamics stochastic force process noise auto correlation |
| gravity | Gravity vector in world-fixed reference frame |
Definition at line 29 of file multicopterDynamicsSim.cpp.
| MulticopterDynamicsSim::MulticopterDynamicsSim | ( | int | numCopter | ) |
Brief constructor for a new Multicopter Dynamics Sim object; vehicle properties must still be set seperately.
| numCopter | Number of motors (e.g. 4 for a quadcopter) |
Definition at line 82 of file multicopterDynamicsSim.cpp.
|
private |
Get aerodynamic moment in vehicle-fixed reference frame.
| angularVelocity | Vehicle angular velocity |
Definition at line 406 of file multicopterDynamicsSim.cpp.
|
private |
Get vehicle angular acceleration in vehicle-fixed reference frame.
| motorSpeed | Vector of motor speeds |
| motorAcceleration | Vector of motor accelerations |
| angularVelocity | Vehicle angular velocity |
| stochMoment | Stochastic moment vector |
Definition at line 712 of file multicopterDynamicsSim.cpp.
|
private |
Get attitude quaternion time-derivative.
| attitude | Vehicle attitude |
| angularVelocity | Vehicle angular velocity in vehicle-fixed reference frame |
Definition at line 695 of file multicopterDynamicsSim.cpp.
|
private |
Get control moment in vehicle-fixed reference frame.
| motorSpeed | Vector of motor speeds |
| motorAcceleration | Vector of motor accelerations |
Definition at line 383 of file multicopterDynamicsSim.cpp.
|
private |
Get drag force in world-fixed reference frame.
| velocity | Vehicle velocity in world-fixed reference frame |
Definition at line 416 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::getIMUMeasurement | ( | Eigen::Vector3d & | accOutput, |
| Eigen::Vector3d & | gyroOutput | ||
| ) |
Get IMU measurement.
| accOutput | Ouput accelerometer measurement |
| gyroOutput | Ouput gyroscope measurement |
Definition at line 426 of file multicopterDynamicsSim.cpp.
|
private |
Get motor acceleration.
| motorSpeedDer | Output vector of accelerationa |
| motorSpeed | Motor speeds vector |
| motorSpeedCommand | Motor commanded speeds vector |
Definition at line 666 of file multicopterDynamicsSim.cpp.
| const std::vector< double > & MulticopterDynamicsSim::getMotorsSpeed | ( | ) | const |
Definition at line 332 of file multicopterDynamicsSim.cpp.
|
private |
Get thrust in vehicle-fixed reference frame.
| motorSpeed | Vector containing motor speeds |
Definition at line 366 of file multicopterDynamicsSim.cpp.
|
private |
Get total force acting on vehicle, including gravity force.
Definition at line 355 of file multicopterDynamicsSim.cpp.
| Eigen::Vector3d MulticopterDynamicsSim::getVehicleAngularVelocity | ( | void | ) |
Get vehicle angular velocity.
Definition at line 328 of file multicopterDynamicsSim.cpp.
| Eigen::Quaterniond MulticopterDynamicsSim::getVehicleAttitude | ( | void | ) |
Get vehicle attitude.
Definition at line 310 of file multicopterDynamicsSim.cpp.
| Eigen::Vector3d MulticopterDynamicsSim::getVehiclePosition | ( | void | ) |
Get vehicle position.
Definition at line 301 of file multicopterDynamicsSim.cpp.
|
private |
Get total specific force acting on vehicle, excluding gravity force.
Definition at line 341 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::getVehicleState | ( | Eigen::Vector3d & | position, |
| Eigen::Vector3d & | velocity, | ||
| Eigen::Vector3d & | angularVelocity, | ||
| Eigen::Quaterniond & | attitude, | ||
| std::vector< double > & | motorSpeed | ||
| ) |
Get vehicle state.
| position | Position in world-fixed reference frame output |
| velocity | Velocity in world-fixed reference frame output |
| angularVelocity | Angular velocity in vehicle-fixed reference frame output |
| attitude | Vehilce attitude quaternion output |
| motorSpeed | Vector with motor speeds for all motors output |
Definition at line 284 of file multicopterDynamicsSim.cpp.
| Eigen::Vector3d MulticopterDynamicsSim::getVehicleVelocity | ( | void | ) |
Get vehicle velocity.
Definition at line 319 of file multicopterDynamicsSim.cpp.
|
private |
Get vehicle accelertion in world-fixed reference frame.
| attitude | Vehicle attitude |
| stochForce | Stochastic force vecotr |
| velocity | Vehicle velocity |
| motorSpeed | Motor speeds vector |
Definition at line 683 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::proceedState_ExplicitEuler | ( | double | dt_secs, |
| const std::vector< double > & | motorSpeedCommandIn, | ||
| bool | isCmdPercent = false |
||
| ) |
Proceed vehicle dynamics using Explicit Euler integration.
| dt_secs | Time step |
| motorSpeedCommand | Motor speed commands |
Definition at line 443 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::proceedState_RK4 | ( | double | dt_secs, |
| const std::vector< double > & | motorSpeedCommandIn, | ||
| bool | isCmdPercent = false |
||
| ) |
Proceed vehicle dynamics using 4th order Runge-Kutta integration.
| dt_secs | Time step |
| motorSpeedCommand | Motor speed commands |
Definition at line 504 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::resetMotorSpeeds | ( | void | ) |
Set motor speed to zero for all motors.
Definition at line 225 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setGravityVector | ( | const Eigen::Vector3d & | gravity | ) |
Set orientation of world-fixed reference frame using gravity vector.
| gravity | Gravity vector in world-fixed reference frame |
Definition at line 141 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setMotorFrame | ( | const Eigen::Isometry3d & | motorFrame, |
| int | motorDirection, | ||
| int | motorIndex | ||
| ) |
Set orientation and position for individual motor.
| motorFrame | Motor orientation and position with regard to body-fixed reference frame |
| motorDirection | Motor rotation direction +1 if positive motor speed corresponds to positive moment around the motor frame z-axis -1 if positive motor speed corresponds to negative moment around the motor frame z-axis i.e. -1 indicates a positive motor speed corresponds to a positive rotation rate around the motor z-axis |
| motorIndex | Motor index number |
Definition at line 155 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setMotorProperties | ( | double | thrustCoefficient, |
| double | torqueCoefficient, | ||
| double | motorTimeConstant, | ||
| double | minMotorSpeed, | ||
| double | maxMotorSpeed, | ||
| double | rotationalInertia | ||
| ) |
Set properties for all motors.
| thrustCoefficient | Motor thrust coefficient |
| torqueCoefficient | Motor torque coefficient |
| motorTimeConstant | Motor time constant |
| minMotorSpeed | Minimum motor rotation speed |
| maxMotorSpeed | Maximum motor rotation speed |
| rotationalInertia | Motor moment of inertia |
Definition at line 191 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setMotorProperties | ( | double | thrustCoefficient, |
| double | torqueCoefficient, | ||
| double | motorTimeConstant, | ||
| double | minMotorSpeed, | ||
| double | maxMotorSpeed, | ||
| double | rotationalInertia, | ||
| int | motorIndex | ||
| ) |
Set properties for individual motor.
| thrustCoefficient | Motor thrust coefficient |
| torqueCoefficient | Motor torque coefficient |
| motorTimeConstant | Motor time constant |
| minMotorSpeed | Minimum motor rotation speed |
| maxMotorSpeed | Maximum motor rotation speed |
| rotationalInertia | Motor moment of inertia |
| motorIndex | Motor index number |
Definition at line 171 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setMotorSpeed | ( | double | motorSpeed | ) |
Set motor speed for all motors.
| motorSpeed | Motor speed value |
Definition at line 215 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setMotorSpeed | ( | double | motorSpeed, |
| int | motorIndex | ||
| ) |
Set motor speed for individual motor.
| motorSpeed | Motor speed value |
| motorIndex | Motor index number |
Definition at line 205 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setVehicleInitialAttitude | ( | const Eigen::Quaterniond & | attitude | ) |
Definition at line 248 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setVehiclePosition | ( | const Eigen::Vector3d & | position, |
| const Eigen::Quaterniond & | attitude | ||
| ) |
Set vehicle position and attitude.
| position | Position in world-fixed reference frame |
| attitude | Vehilce attitude quaternion |
Definition at line 237 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::setVehicleProperties | ( | double | vehicleMass, |
| const Eigen::Matrix3d & | vehicleInertia, | ||
| const Eigen::Matrix3d & | aeroMomentCoefficient, | ||
| double | dragCoefficient, | ||
| double | momentProcessNoiseAutoCorrelation, | ||
| double | forceProcessNoiseAutoCorrelation | ||
| ) |
Set vehicle properties.
| vehicleMass | Vehicle mass |
| vehicleInertia | Vehicle inertia matrix |
| aeroMomentCoefficient | Vehicle aerodynamic moment coefficient matrix |
| dragCoefficient | Vehicle drag coefficient |
| momentProcessNoiseAutoCorrelation | Vehicle dynamics stochastic moment process noise auto correlation |
| forceProcessNoiseAutoCorrelation | Vehicle dynamics stochastic force process noise auto correlation |
Definition at line 122 of file multicopterDynamicsSim.cpp.
| void MulticopterDynamicsSim::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.
| position | Position in world-fixed reference frame |
| velocity | Velocity in world-fixed reference frame |
| angularVelocity | Angular velocity in vehicle-fixed reference frame |
| attitude | Vehilce attitude quaternion |
| motorSpeed | Vector with motor speeds for all motors |
Definition at line 261 of file multicopterDynamicsSim.cpp.
|
private |
Element-wise affine vector calculus: vec3 = vec1 + val*vec2.
| vec1 | Vector addition term |
| vec2 | Vector multiplication factor |
| vec3 | Output resulting vector |
| val | Scalar multiplication factor |
Definition at line 629 of file multicopterDynamicsSim.cpp.
|
private |
Element-wise vector bound operation: vec2 = max(minvalue, min(maxvalue, vec1))
| vec1 | Input vector |
| vec2 | Output vector |
| minvec | Vector of lower bounds |
| maxvec | Vector of upper bounds |
Definition at line 642 of file multicopterDynamicsSim.cpp.
|
private |
Vector-scalar product: vec2 = val*vec1.
| vec1 | Input vector |
| vec2 | Output vector |
| val | Scalar multiplication |
Definition at line 655 of file multicopterDynamicsSim.cpp.
|
private |
Definition at line 103 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 125 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 126 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 127 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 102 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 107 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 118 of file multicopterDynamicsSim.hpp.
| inertialMeasurementSim MulticopterDynamicsSim::imu_ = inertialMeasurementSim(0.,0.,0.,0.) |
Definition at line 71 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 96 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 97 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 106 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 90 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 84 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 95 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 122 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 94 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 75 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 124 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 112 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 113 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 134 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 92 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 93 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 105 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 104 of file multicopterDynamicsSim.hpp.
|
private |
Definition at line 123 of file multicopterDynamicsSim.hpp.