Public Member Functions | List of all members
MulticopterDynamicsSim Class Reference

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...
 

Detailed Description

Multicopter dynamics simulator class.

Definition at line 20 of file multicopterDynamicsSim.hpp.

Constructor & Destructor Documentation

◆ MulticopterDynamicsSim() [1/2]

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.

Parameters
numCopterNumber of motors (e.g. 4 for a quadcopter)
thrustCoefficientMotors thrust coefficient
torqueCoefficientMotors torque coefficient
minMotorSpeedMotors minimum rotation speed
maxMotorSpeedMotors maximum rotation speed
motorTimeConstantMotors time constant
motorRotationalInertiaMotors rotational mass moment of inertia (including propeller)
vehicleMassVehicle mass
vehicleInertiaVehicle inertia matrix
aeroMomentCoefficientVehicle aerodynamic moment coefficient matrix
dragCoefficientVehicle drag coefficient
momentProcessNoiseAutoCorrelationVehicle dynamics stochastic moment process noise auto correlation
forceProcessNoiseAutoCorrelationVehicle dynamics stochastic force process noise auto correlation
gravityGravity vector in world-fixed reference frame

Definition at line 29 of file multicopterDynamicsSim.cpp.

◆ MulticopterDynamicsSim() [2/2]

MulticopterDynamicsSim::MulticopterDynamicsSim ( int  numCopter)

Brief constructor for a new Multicopter Dynamics Sim object; vehicle properties must still be set seperately.

Parameters
numCopterNumber of motors (e.g. 4 for a quadcopter)

Definition at line 82 of file multicopterDynamicsSim.cpp.

Member Function Documentation

◆ getAeroMoment()

Eigen::Vector3d MulticopterDynamicsSim::getAeroMoment ( const Eigen::Vector3d &  angularVelocity)
private

Get aerodynamic moment in vehicle-fixed reference frame.

Parameters
angularVelocityVehicle angular velocity
Returns
Eigen::Vector3d Aerodynamic moment vector

Definition at line 406 of file multicopterDynamicsSim.cpp.

◆ getAngularVelocityDerivative()

Eigen::Vector3d MulticopterDynamicsSim::getAngularVelocityDerivative ( const std::vector< double > &  motorSpeed,
const std::vector< double > &  motorAcceleration,
const Eigen::Vector3d &  angularVelocity,
const Eigen::Vector3d &  stochMoment 
)
private

Get vehicle angular acceleration in vehicle-fixed reference frame.

Parameters
motorSpeedVector of motor speeds
motorAccelerationVector of motor accelerations
angularVelocityVehicle angular velocity
stochMomentStochastic moment vector
Returns
Eigen::Vector3d Angular acceleration

Definition at line 712 of file multicopterDynamicsSim.cpp.

◆ getAttitudeDerivative()

Eigen::Vector4d MulticopterDynamicsSim::getAttitudeDerivative ( const Eigen::Quaterniond &  attitude,
const Eigen::Vector3d &  angularVelocity 
)
private

Get attitude quaternion time-derivative.

Parameters
attitudeVehicle attitude
angularVelocityVehicle angular velocity in vehicle-fixed reference frame
Returns
Eigen::Vector4d Attitude derivative

Definition at line 695 of file multicopterDynamicsSim.cpp.

◆ getControlMoment()

Eigen::Vector3d MulticopterDynamicsSim::getControlMoment ( const std::vector< double > &  motorSpeed,
const std::vector< double > &  motorAcceleration 
)
private

Get control moment in vehicle-fixed reference frame.

Parameters
motorSpeedVector of motor speeds
motorAccelerationVector of motor accelerations
Returns
Eigen::Vector3d Moment vector

Definition at line 383 of file multicopterDynamicsSim.cpp.

◆ getDragForce()

Eigen::Vector3d MulticopterDynamicsSim::getDragForce ( const Eigen::Vector3d &  velocity)
private

Get drag force in world-fixed reference frame.

Parameters
velocityVehicle velocity in world-fixed reference frame
Returns
Eigen::Vector3d Drag force vector

Definition at line 416 of file multicopterDynamicsSim.cpp.

◆ getIMUMeasurement()

void MulticopterDynamicsSim::getIMUMeasurement ( Eigen::Vector3d &  accOutput,
Eigen::Vector3d &  gyroOutput 
)

Get IMU measurement.

Parameters
accOutputOuput accelerometer measurement
gyroOutputOuput gyroscope measurement

Definition at line 426 of file multicopterDynamicsSim.cpp.

◆ getMotorSpeedDerivative()

void MulticopterDynamicsSim::getMotorSpeedDerivative ( std::vector< double > &  motorSpeedDer,
const std::vector< double > &  motorSpeed,
const std::vector< double > &  motorSpeedCommand 
)
private

Get motor acceleration.

Parameters
motorSpeedDerOutput vector of accelerationa
motorSpeedMotor speeds vector
motorSpeedCommandMotor commanded speeds vector

Definition at line 666 of file multicopterDynamicsSim.cpp.

◆ getMotorsSpeed()

const std::vector< double > & MulticopterDynamicsSim::getMotorsSpeed ( ) const

Definition at line 332 of file multicopterDynamicsSim.cpp.

◆ getThrust()

Eigen::Vector3d MulticopterDynamicsSim::getThrust ( const std::vector< double > &  motorSpeed)
private

Get thrust in vehicle-fixed reference frame.

Parameters
motorSpeedVector containing motor speeds
Returns
Eigen::Vector3d Thrust vector

Definition at line 366 of file multicopterDynamicsSim.cpp.

◆ getTotalForce()

Eigen::Vector3d MulticopterDynamicsSim::getTotalForce ( void  )
private

Get total force acting on vehicle, including gravity force.

Returns
Eigen::Vector3d Total force in vehicle-fixed reference frame

Definition at line 355 of file multicopterDynamicsSim.cpp.

◆ getVehicleAngularVelocity()

Eigen::Vector3d MulticopterDynamicsSim::getVehicleAngularVelocity ( void  )

Get vehicle angular velocity.

Returns
Eigen::Vector3d Angular velocity in vehicle-fixed reference frame

Definition at line 328 of file multicopterDynamicsSim.cpp.

◆ getVehicleAttitude()

Eigen::Quaterniond MulticopterDynamicsSim::getVehicleAttitude ( void  )

Get vehicle attitude.

Returns
Eigen::Quaterniond Vehicle attitude quaternion

Definition at line 310 of file multicopterDynamicsSim.cpp.

◆ getVehiclePosition()

Eigen::Vector3d MulticopterDynamicsSim::getVehiclePosition ( void  )

Get vehicle position.

Returns
Eigen::Vector3d Position in world-fixed reference frame

Definition at line 301 of file multicopterDynamicsSim.cpp.

◆ getVehicleSpecificForce()

Eigen::Vector3d MulticopterDynamicsSim::getVehicleSpecificForce ( void  )
private

Get total specific force acting on vehicle, excluding gravity force.

Returns
Eigen::Vector3d Specific force in vehicle-fixed reference frame

Definition at line 341 of file multicopterDynamicsSim.cpp.

◆ getVehicleState()

void MulticopterDynamicsSim::getVehicleState ( Eigen::Vector3d &  position,
Eigen::Vector3d &  velocity,
Eigen::Vector3d &  angularVelocity,
Eigen::Quaterniond &  attitude,
std::vector< double > &  motorSpeed 
)

Get vehicle state.

Parameters
positionPosition in world-fixed reference frame output
velocityVelocity in world-fixed reference frame output
angularVelocityAngular velocity in vehicle-fixed reference frame output
attitudeVehilce attitude quaternion output
motorSpeedVector with motor speeds for all motors output

Definition at line 284 of file multicopterDynamicsSim.cpp.

◆ getVehicleVelocity()

Eigen::Vector3d MulticopterDynamicsSim::getVehicleVelocity ( void  )

Get vehicle velocity.

Returns
Eigen::Vector3d Velocity in world-fixed reference frame

Definition at line 319 of file multicopterDynamicsSim.cpp.

◆ getVelocityDerivative()

Eigen::Vector3d MulticopterDynamicsSim::getVelocityDerivative ( const Eigen::Quaterniond &  attitude,
const Eigen::Vector3d &  stochForce,
const Eigen::Vector3d &  velocity,
const std::vector< double > &  motorSpeed 
)
private

Get vehicle accelertion in world-fixed reference frame.

Parameters
attitudeVehicle attitude
stochForceStochastic force vecotr
velocityVehicle velocity
motorSpeedMotor speeds vector
Returns
Eigen::Vector3d Acceleration vector

Definition at line 683 of file multicopterDynamicsSim.cpp.

◆ proceedState_ExplicitEuler()

void MulticopterDynamicsSim::proceedState_ExplicitEuler ( double  dt_secs,
const std::vector< double > &  motorSpeedCommandIn,
bool  isCmdPercent = false 
)

Proceed vehicle dynamics using Explicit Euler integration.

Parameters
dt_secsTime step
motorSpeedCommandMotor speed commands

Definition at line 443 of file multicopterDynamicsSim.cpp.

◆ proceedState_RK4()

void MulticopterDynamicsSim::proceedState_RK4 ( double  dt_secs,
const std::vector< double > &  motorSpeedCommandIn,
bool  isCmdPercent = false 
)

Proceed vehicle dynamics using 4th order Runge-Kutta integration.

Parameters
dt_secsTime step
motorSpeedCommandMotor speed commands

Definition at line 504 of file multicopterDynamicsSim.cpp.

◆ resetMotorSpeeds()

void MulticopterDynamicsSim::resetMotorSpeeds ( void  )

Set motor speed to zero for all motors.

Definition at line 225 of file multicopterDynamicsSim.cpp.

◆ setGravityVector()

void MulticopterDynamicsSim::setGravityVector ( const Eigen::Vector3d &  gravity)

Set orientation of world-fixed reference frame using gravity vector.

Parameters
gravityGravity vector in world-fixed reference frame

Definition at line 141 of file multicopterDynamicsSim.cpp.

◆ setMotorFrame()

void MulticopterDynamicsSim::setMotorFrame ( const Eigen::Isometry3d &  motorFrame,
int  motorDirection,
int  motorIndex 
)

Set orientation and position for individual motor.

Parameters
motorFrameMotor orientation and position with regard to body-fixed reference frame
motorDirectionMotor 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
motorIndexMotor index number

Definition at line 155 of file multicopterDynamicsSim.cpp.

◆ setMotorProperties() [1/2]

void MulticopterDynamicsSim::setMotorProperties ( double  thrustCoefficient,
double  torqueCoefficient,
double  motorTimeConstant,
double  minMotorSpeed,
double  maxMotorSpeed,
double  rotationalInertia 
)

Set properties for all motors.

Parameters
thrustCoefficientMotor thrust coefficient
torqueCoefficientMotor torque coefficient
motorTimeConstantMotor time constant
minMotorSpeedMinimum motor rotation speed
maxMotorSpeedMaximum motor rotation speed
rotationalInertiaMotor moment of inertia

Definition at line 191 of file multicopterDynamicsSim.cpp.

◆ setMotorProperties() [2/2]

void MulticopterDynamicsSim::setMotorProperties ( double  thrustCoefficient,
double  torqueCoefficient,
double  motorTimeConstant,
double  minMotorSpeed,
double  maxMotorSpeed,
double  rotationalInertia,
int  motorIndex 
)

Set properties for individual motor.

Parameters
thrustCoefficientMotor thrust coefficient
torqueCoefficientMotor torque coefficient
motorTimeConstantMotor time constant
minMotorSpeedMinimum motor rotation speed
maxMotorSpeedMaximum motor rotation speed
rotationalInertiaMotor moment of inertia
motorIndexMotor index number

Definition at line 171 of file multicopterDynamicsSim.cpp.

◆ setMotorSpeed() [1/2]

void MulticopterDynamicsSim::setMotorSpeed ( double  motorSpeed)

Set motor speed for all motors.

Parameters
motorSpeedMotor speed value

Definition at line 215 of file multicopterDynamicsSim.cpp.

◆ setMotorSpeed() [2/2]

void MulticopterDynamicsSim::setMotorSpeed ( double  motorSpeed,
int  motorIndex 
)

Set motor speed for individual motor.

Parameters
motorSpeedMotor speed value
motorIndexMotor index number

Definition at line 205 of file multicopterDynamicsSim.cpp.

◆ setVehicleInitialAttitude()

void MulticopterDynamicsSim::setVehicleInitialAttitude ( const Eigen::Quaterniond &  attitude)

Definition at line 248 of file multicopterDynamicsSim.cpp.

◆ setVehiclePosition()

void MulticopterDynamicsSim::setVehiclePosition ( const Eigen::Vector3d &  position,
const Eigen::Quaterniond &  attitude 
)

Set vehicle position and attitude.

Parameters
positionPosition in world-fixed reference frame
attitudeVehilce attitude quaternion

Definition at line 237 of file multicopterDynamicsSim.cpp.

◆ setVehicleProperties()

void MulticopterDynamicsSim::setVehicleProperties ( double  vehicleMass,
const Eigen::Matrix3d &  vehicleInertia,
const Eigen::Matrix3d &  aeroMomentCoefficient,
double  dragCoefficient,
double  momentProcessNoiseAutoCorrelation,
double  forceProcessNoiseAutoCorrelation 
)

Set vehicle properties.

Parameters
vehicleMassVehicle mass
vehicleInertiaVehicle inertia matrix
aeroMomentCoefficientVehicle aerodynamic moment coefficient matrix
dragCoefficientVehicle drag coefficient
momentProcessNoiseAutoCorrelationVehicle dynamics stochastic moment process noise auto correlation
forceProcessNoiseAutoCorrelationVehicle dynamics stochastic force process noise auto correlation

Definition at line 122 of file multicopterDynamicsSim.cpp.

◆ setVehicleState()

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.

Parameters
positionPosition in world-fixed reference frame
velocityVelocity in world-fixed reference frame
angularVelocityAngular velocity in vehicle-fixed reference frame
attitudeVehilce attitude quaternion
motorSpeedVector with motor speeds for all motors

Definition at line 261 of file multicopterDynamicsSim.cpp.

◆ vectorAffineOp()

void MulticopterDynamicsSim::vectorAffineOp ( const std::vector< double > &  vec1,
const std::vector< double > &  vec2,
std::vector< double > &  vec3,
double  val 
)
private

Element-wise affine vector calculus: vec3 = vec1 + val*vec2.

Parameters
vec1Vector addition term
vec2Vector multiplication factor
vec3Output resulting vector
valScalar multiplication factor

Definition at line 629 of file multicopterDynamicsSim.cpp.

◆ vectorBoundOp()

void MulticopterDynamicsSim::vectorBoundOp ( const std::vector< double > &  vec1,
std::vector< double > &  vec2,
const std::vector< double > &  minvec,
const std::vector< double > &  maxvec 
)
private

Element-wise vector bound operation: vec2 = max(minvalue, min(maxvalue, vec1))

Parameters
vec1Input vector
vec2Output vector
minvecVector of lower bounds
maxvecVector of upper bounds

Definition at line 642 of file multicopterDynamicsSim.cpp.

◆ vectorScalarProd()

void MulticopterDynamicsSim::vectorScalarProd ( const std::vector< double > &  vec1,
std::vector< double > &  vec2,
double  val 
)
private

Vector-scalar product: vec2 = val*vec1.

Parameters
vec1Input vector
vec2Output vector
valScalar multiplication

Definition at line 655 of file multicopterDynamicsSim.cpp.

Member Data Documentation

◆ aeroMomentCoefficient_

Eigen::Matrix3d MulticopterDynamicsSim::aeroMomentCoefficient_
private

Definition at line 103 of file multicopterDynamicsSim.hpp.

◆ angularVelocity_

Eigen::Vector3d MulticopterDynamicsSim::angularVelocity_ = Eigen::Vector3d::Zero()
private

Definition at line 125 of file multicopterDynamicsSim.hpp.

◆ attitude_

Eigen::Quaterniond MulticopterDynamicsSim::attitude_ = Eigen::Quaterniond::Identity()
private

Definition at line 126 of file multicopterDynamicsSim.hpp.

◆ default_attitude_

Eigen::Quaterniond MulticopterDynamicsSim::default_attitude_ = Eigen::Quaterniond::Identity()
private

Definition at line 127 of file multicopterDynamicsSim.hpp.

◆ dragCoefficient_

double MulticopterDynamicsSim::dragCoefficient_
private

Definition at line 102 of file multicopterDynamicsSim.hpp.

◆ forceProcessNoiseAutoCorrelation_

double MulticopterDynamicsSim::forceProcessNoiseAutoCorrelation_ = 0.
private

Definition at line 107 of file multicopterDynamicsSim.hpp.

◆ gravity_

Eigen::Vector3d MulticopterDynamicsSim::gravity_
private

Definition at line 118 of file multicopterDynamicsSim.hpp.

◆ imu_

inertialMeasurementSim MulticopterDynamicsSim::imu_ = inertialMeasurementSim(0.,0.,0.,0.)

Definition at line 71 of file multicopterDynamicsSim.hpp.

◆ maxMotorSpeed_

std::vector<double> MulticopterDynamicsSim::maxMotorSpeed_
private

Definition at line 96 of file multicopterDynamicsSim.hpp.

◆ minMotorSpeed_

std::vector<double> MulticopterDynamicsSim::minMotorSpeed_
private

Definition at line 97 of file multicopterDynamicsSim.hpp.

◆ momentProcessNoiseAutoCorrelation_

double MulticopterDynamicsSim::momentProcessNoiseAutoCorrelation_ = 0.
private

Definition at line 106 of file multicopterDynamicsSim.hpp.

◆ motorDirection_

std::vector<int> MulticopterDynamicsSim::motorDirection_
private

Definition at line 90 of file multicopterDynamicsSim.hpp.

◆ motorFrame_

std::vector<Eigen::Isometry3d> MulticopterDynamicsSim::motorFrame_
private

Definition at line 84 of file multicopterDynamicsSim.hpp.

◆ motorRotationalInertia_

std::vector<double> MulticopterDynamicsSim::motorRotationalInertia_
private

Definition at line 95 of file multicopterDynamicsSim.hpp.

◆ motorSpeed_

std::vector<double> MulticopterDynamicsSim::motorSpeed_
private

Definition at line 122 of file multicopterDynamicsSim.hpp.

◆ motorTimeConstant_

std::vector<double> MulticopterDynamicsSim::motorTimeConstant_
private

Definition at line 94 of file multicopterDynamicsSim.hpp.

◆ numCopter_

int MulticopterDynamicsSim::numCopter_
private

Definition at line 75 of file multicopterDynamicsSim.hpp.

◆ position_

Eigen::Vector3d MulticopterDynamicsSim::position_ = Eigen::Vector3d::Zero()
private

Definition at line 124 of file multicopterDynamicsSim.hpp.

◆ randomNumberGenerator_

std::default_random_engine MulticopterDynamicsSim::randomNumberGenerator_
private

Definition at line 112 of file multicopterDynamicsSim.hpp.

◆ standardNormalDistribution_

std::normal_distribution<double> MulticopterDynamicsSim::standardNormalDistribution_ = std::normal_distribution<double>(0.0,1.0)
private

Definition at line 113 of file multicopterDynamicsSim.hpp.

◆ stochForce_

Eigen::Vector3d MulticopterDynamicsSim::stochForce_ = Eigen::Vector3d::Zero()
private

Definition at line 134 of file multicopterDynamicsSim.hpp.

◆ thrustCoefficient_

std::vector<double> MulticopterDynamicsSim::thrustCoefficient_
private

Definition at line 92 of file multicopterDynamicsSim.hpp.

◆ torqueCoefficient_

std::vector<double> MulticopterDynamicsSim::torqueCoefficient_
private

Definition at line 93 of file multicopterDynamicsSim.hpp.

◆ vehicleInertia_

Eigen::Matrix3d MulticopterDynamicsSim::vehicleInertia_
private

Definition at line 105 of file multicopterDynamicsSim.hpp.

◆ vehicleMass_

double MulticopterDynamicsSim::vehicleMass_
private

Definition at line 104 of file multicopterDynamicsSim.hpp.

◆ velocity_

Eigen::Vector3d MulticopterDynamicsSim::velocity_ = Eigen::Vector3d::Zero()
private

Definition at line 123 of file multicopterDynamicsSim.hpp.


The documentation for this class was generated from the following files:


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