Go to the documentation of this file.00001 #ifndef INCLUDE_ROTORS_CONTROL_PARAMETERS_H_
00002 #define INCLUDE_ROTORS_CONTROL_PARAMETERS_H_
00003
00004 namespace rotors_control {
00005
00006 static constexpr double kDefaultRotor0Angle = 0.52359877559;
00007 static constexpr double kDefaultRotor1Angle = 1.57079632679;
00008 static constexpr double kDefaultRotor2Angle = 2.61799387799;
00009 static constexpr double kDefaultRotor3Angle = -2.61799387799;
00010 static constexpr double kDefaultRotor4Angle = -1.57079632679;
00011 static constexpr double kDefaultRotor5Angle = -0.52359877559;
00012
00013
00014 static constexpr double kDefaultMass = 1.56779;
00015 static constexpr double kDefaultArmLength = 0.215;
00016 static constexpr double kDefaultInertiaXx = 0.0347563;
00017 static constexpr double kDefaultInertiaYy = 0.0458929;
00018 static constexpr double kDefaultInertiaZz = 0.0977;
00019 static constexpr double kDefaultRotorForceConstant = 8.54858e-6;
00020 static constexpr double kDefaultRotorMomentConstant = 1.6e-2;
00021
00022
00023 static constexpr double kDefaultGravity = 9.81;
00024
00025 struct Rotor {
00026 Rotor()
00027 : angle(0.0),
00028 arm_length(kDefaultArmLength),
00029 rotor_force_constant(kDefaultRotorForceConstant),
00030 rotor_moment_constant(kDefaultRotorMomentConstant),
00031 direction(1) {}
00032 Rotor(double _angle, double _arm_length,
00033 double _rotor_force_constant, double _rotor_moment_constant,
00034 int _direction)
00035 : angle(_angle),
00036 arm_length(_arm_length),
00037 rotor_force_constant(_rotor_force_constant),
00038 rotor_moment_constant(_rotor_moment_constant),
00039 direction(_direction) {}
00040 double angle;
00041 double arm_length;
00042 double rotor_force_constant;
00043 double rotor_moment_constant;
00044 int direction;
00045 };
00046
00047 struct RotorConfiguration {
00048 RotorConfiguration() {
00049
00050 rotors.push_back(
00051 Rotor(kDefaultRotor0Angle, kDefaultArmLength, kDefaultRotorForceConstant,
00052 kDefaultRotorMomentConstant, 1));
00053 rotors.push_back(
00054 Rotor(kDefaultRotor1Angle, kDefaultArmLength, kDefaultRotorForceConstant,
00055 kDefaultRotorMomentConstant, -1));
00056 rotors.push_back(
00057 Rotor(kDefaultRotor2Angle, kDefaultArmLength, kDefaultRotorForceConstant,
00058 kDefaultRotorMomentConstant, 1));
00059 rotors.push_back(
00060 Rotor(kDefaultRotor3Angle, kDefaultArmLength, kDefaultRotorForceConstant,
00061 kDefaultRotorMomentConstant, -1));
00062 rotors.push_back(
00063 Rotor(kDefaultRotor4Angle, kDefaultArmLength, kDefaultRotorForceConstant,
00064 kDefaultRotorMomentConstant, 1));
00065 rotors.push_back(
00066 Rotor(kDefaultRotor5Angle, kDefaultArmLength, kDefaultRotorForceConstant,
00067 kDefaultRotorMomentConstant, -1));
00068 }
00069 std::vector<Rotor> rotors;
00070 };
00071
00072 class VehicleParameters {
00073 public:
00074 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00075 VehicleParameters()
00076 : mass_(kDefaultMass),
00077 gravity_(kDefaultGravity),
00078 inertia_(Eigen::Vector3d(kDefaultInertiaXx, kDefaultInertiaYy,
00079 kDefaultInertiaZz).asDiagonal()) {}
00080 double mass_;
00081 const double gravity_;
00082 Eigen::Matrix3d inertia_;
00083 RotorConfiguration rotor_configuration_;
00084 };
00085
00086 }
00087
00088 #endif
rotors_control
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:38