1 #ifndef INCLUDE_ROTORS_CONTROL_PARAMETERS_H_ 2 #define INCLUDE_ROTORS_CONTROL_PARAMETERS_H_ 32 Rotor(
double _angle,
double _arm_length,
33 double _rotor_force_constant,
double _rotor_moment_constant,
51 Rotor(kDefaultRotor0Angle, kDefaultArmLength, kDefaultRotorForceConstant,
52 kDefaultRotorMomentConstant, 1));
54 Rotor(kDefaultRotor1Angle, kDefaultArmLength, kDefaultRotorForceConstant,
55 kDefaultRotorMomentConstant, -1));
57 Rotor(kDefaultRotor2Angle, kDefaultArmLength, kDefaultRotorForceConstant,
58 kDefaultRotorMomentConstant, 1));
60 Rotor(kDefaultRotor3Angle, kDefaultArmLength, kDefaultRotorForceConstant,
61 kDefaultRotorMomentConstant, -1));
63 Rotor(kDefaultRotor4Angle, kDefaultArmLength, kDefaultRotorForceConstant,
64 kDefaultRotorMomentConstant, 1));
66 Rotor(kDefaultRotor5Angle, kDefaultArmLength, kDefaultRotorForceConstant,
67 kDefaultRotorMomentConstant, -1));
74 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
76 : mass_(kDefaultMass),
77 gravity_(kDefaultGravity),
78 inertia_(Eigen::Vector3d(kDefaultInertiaXx, kDefaultInertiaYy,
79 kDefaultInertiaZz).asDiagonal()) {}
static constexpr double kDefaultRotorForceConstant
static constexpr double kDefaultRotor5Angle
static constexpr double kDefaultRotorMomentConstant
static constexpr double kDefaultRotor4Angle
static constexpr double kDefaultRotor3Angle
static constexpr double kDefaultArmLength
RotorConfiguration rotor_configuration_
double rotor_moment_constant
static constexpr double kDefaultRotor1Angle
Rotor(double _angle, double _arm_length, double _rotor_force_constant, double _rotor_moment_constant, int _direction)
static constexpr double kDefaultInertiaXx
static constexpr double kDefaultInertiaYy
static constexpr double kDefaultRotor0Angle
static constexpr double kDefaultRotor2Angle
std::vector< Rotor > rotors
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VehicleParameters()
static constexpr double kDefaultGravity
static constexpr double kDefaultInertiaZz
static constexpr double kDefaultMass
double rotor_force_constant