parameters.h
Go to the documentation of this file.
1 #ifndef INCLUDE_ROTORS_CONTROL_PARAMETERS_H_
2 #define INCLUDE_ROTORS_CONTROL_PARAMETERS_H_
3 
4 namespace rotors_control {
5 // Default values for the Asctec Firefly rotor configuration.
6 static constexpr double kDefaultRotor0Angle = 0.52359877559;
7 static constexpr double kDefaultRotor1Angle = 1.57079632679;
8 static constexpr double kDefaultRotor2Angle = 2.61799387799;
9 static constexpr double kDefaultRotor3Angle = -2.61799387799;
10 static constexpr double kDefaultRotor4Angle = -1.57079632679;
11 static constexpr double kDefaultRotor5Angle = -0.52359877559;
12 
13 // Default vehicle parameters for Asctec Firefly.
14 static constexpr double kDefaultMass = 1.56779;
15 static constexpr double kDefaultArmLength = 0.215;
16 static constexpr double kDefaultInertiaXx = 0.0347563;
17 static constexpr double kDefaultInertiaYy = 0.0458929;
18 static constexpr double kDefaultInertiaZz = 0.0977;
19 static constexpr double kDefaultRotorForceConstant = 8.54858e-6;
20 static constexpr double kDefaultRotorMomentConstant = 1.6e-2;
21 
22 // Default physics parameters.
23 static constexpr double kDefaultGravity = 9.81;
24 
25 struct Rotor {
27  : angle(0.0),
28  arm_length(kDefaultArmLength),
29  rotor_force_constant(kDefaultRotorForceConstant),
30  rotor_moment_constant(kDefaultRotorMomentConstant),
31  direction(1) {}
32  Rotor(double _angle, double _arm_length,
33  double _rotor_force_constant, double _rotor_moment_constant,
34  int _direction)
35  : angle(_angle),
36  arm_length(_arm_length),
37  rotor_force_constant(_rotor_force_constant),
38  rotor_moment_constant(_rotor_moment_constant),
39  direction(_direction) {}
40  double angle;
41  double arm_length;
44  int direction;
45 };
46 
49  // Rotor configuration of Asctec Firefly.
50  rotors.push_back(
51  Rotor(kDefaultRotor0Angle, kDefaultArmLength, kDefaultRotorForceConstant,
52  kDefaultRotorMomentConstant, 1));
53  rotors.push_back(
54  Rotor(kDefaultRotor1Angle, kDefaultArmLength, kDefaultRotorForceConstant,
55  kDefaultRotorMomentConstant, -1));
56  rotors.push_back(
57  Rotor(kDefaultRotor2Angle, kDefaultArmLength, kDefaultRotorForceConstant,
58  kDefaultRotorMomentConstant, 1));
59  rotors.push_back(
60  Rotor(kDefaultRotor3Angle, kDefaultArmLength, kDefaultRotorForceConstant,
61  kDefaultRotorMomentConstant, -1));
62  rotors.push_back(
63  Rotor(kDefaultRotor4Angle, kDefaultArmLength, kDefaultRotorForceConstant,
64  kDefaultRotorMomentConstant, 1));
65  rotors.push_back(
66  Rotor(kDefaultRotor5Angle, kDefaultArmLength, kDefaultRotorForceConstant,
67  kDefaultRotorMomentConstant, -1));
68  }
69  std::vector<Rotor> rotors;
70 };
71 
73  public:
74  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
76  : mass_(kDefaultMass),
77  gravity_(kDefaultGravity),
78  inertia_(Eigen::Vector3d(kDefaultInertiaXx, kDefaultInertiaYy,
79  kDefaultInertiaZz).asDiagonal()) {}
80  double mass_;
81  const double gravity_;
82  Eigen::Matrix3d inertia_;
84 };
85 
86 }
87 
88 #endif /* INCLUDE_ROTORS_CONTROL_PARAMETERS_H_ */
static constexpr double kDefaultRotorForceConstant
Definition: parameters.h:19
static constexpr double kDefaultRotor5Angle
Definition: parameters.h:11
static constexpr double kDefaultRotorMomentConstant
Definition: parameters.h:20
static constexpr double kDefaultRotor4Angle
Definition: parameters.h:10
static constexpr double kDefaultRotor3Angle
Definition: parameters.h:9
static constexpr double kDefaultArmLength
Definition: parameters.h:15
RotorConfiguration rotor_configuration_
Definition: parameters.h:83
double rotor_moment_constant
Definition: parameters.h:43
static constexpr double kDefaultRotor1Angle
Definition: parameters.h:7
Rotor(double _angle, double _arm_length, double _rotor_force_constant, double _rotor_moment_constant, int _direction)
Definition: parameters.h:32
static constexpr double kDefaultInertiaXx
Definition: parameters.h:16
static constexpr double kDefaultInertiaYy
Definition: parameters.h:17
static constexpr double kDefaultRotor0Angle
Definition: parameters.h:6
static constexpr double kDefaultRotor2Angle
Definition: parameters.h:8
std::vector< Rotor > rotors
Definition: parameters.h:69
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VehicleParameters()
Definition: parameters.h:75
static constexpr double kDefaultGravity
Definition: parameters.h:23
static constexpr double kDefaultInertiaZz
Definition: parameters.h:18
static constexpr double kDefaultMass
Definition: parameters.h:14
double rotor_force_constant
Definition: parameters.h:42


rotors_control
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:38:55