DemoController.yaml 4.73 KB
Newer Older
1
# Mass of the crazyflie
2
mass : 30
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29

# Frequency of the controller, in hertz
control_frequency : 200

# Quadratic motor regression equation (a0, a1, a2)
motorPoly : [5.484560e-4, 1.032633e-6, 2.130295e-11]

# Boolean for whether to execute the convert into body frame function
shouldPerformConvertIntoBodyFrame : true

# Boolean indiciating whether the (x,y,z,yaw) of this agent should be published or not
shouldPublishCurrent_xyz_yaw : false

# Boolean indicating whether the (x,y,z,yaw) setpoint of this agent should adapted in
# an attempt to follow the "my_current_xyz_yaw_topic" from another agent
shouldFollowAnotherAgent : false

# The order in which agents should follow eachother
# > This parameter is a vector of integers that specifies  agent ID's
# > The order of the agent ID's is the ordering of the line formation
# > i.e., the first ID is the leader, the second ID should follow the first ID, and so on
follow_in_a_line_agentIDs : [1, 2, 3]

# Boolean indiciating whether the "Debug Message" of this agent should be published or not
shouldPublishDebugMessage : false

# Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
30
shouldDisplayDebugInfo : false
31

32

33
34
35
36
37
38
39
# A flag for which LQR controller mode to use, defined as:
# 1  -  LQR controller based on the state vector: [position,velocity,angles,angular velocity]
#       commands per motor thrusts
# 2  -  LQR controller based on the state vector: [position,velocity,angles,angular velocity]
#       commands actuators of total force and bodz torques
# 3  -  LQR controller based on the state vector: [position,velocity,angles]
# 4  -  LQR controller based on the state vector: [position,velocity]
40
lqr_controller_mode : 3
41
42
43
44
45
46
47
48
49
50
51
52


# A flag for which estimator to use, defined as:
# 1  -  Finite Different Method,
#       Takes the poisition and angles directly as measured,
#       and estimates the velocities as a finite different to the
#       previous measurement
# 2  -  Point Mass Per Dimension Method
#       Uses a 2nd order random walk estimator independently for
#       each of (x,y,z,roll,pitch,yaw)
# 3  -  Quad-rotor Model Based Method
#       Uses the model of the quad-rotor and the previous inputs
53
estimator_method : 1
54
55


56
# The LQR Controller parameters for "mode = 1"
57
58
59
60
gainMatrixMotor1                    :  [ -0.0180, 0.0180, 0.0350,-0.0110, 0.0110, 0.0260,-0.0220,-0.0220,-0.0110,-0.00024,-0.00024,-0.00045]
gainMatrixMotor2                    :  [  0.0180, 0.0180, 0.0350, 0.0110, 0.0110, 0.0260,-0.0220, 0.0220, 0.0110,-0.00024, 0.00024, 0.00045]
gainMatrixMotor3                    :  [  0.0180,-0.0180, 0.0350, 0.0110,-0.0110, 0.0260, 0.0220, 0.0220,-0.0110, 0.00024, 0.00024,-0.00045]
gainMatrixMotor4                    :  [ -0.0180,-0.0180, 0.0350,-0.0110,-0.0110, 0.0260, 0.0220,-0.0220, 0.0110, 0.00024,-0.00024, 0.00045]
61

62
# The LQR Controller parameters for "mode = 2"
63
64
65
66
gainMatrixThrust_TwelveStateVector  :  [ 0.0000, 0.0000, 0.9800, 0.0000, 0.0000, 0.25, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000]
gainMatrixRollTorque                :  [ 0.0000,-0.0017, 0.0000, 0.0000,-0.0009, 0.00, 0.0019, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000]
gainMatrixPitchTorque               :  [ 0.0017, 0.0000, 0.0000, 0.0009, 0.0000, 0.00, 0.0000, 0.0019, 0.0000, 0.0000, 0.0000, 0.0000]
gainMatrixYawTorque                 :  [ 0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.00, 0.0000, 0.0000, 0.0002, 0.0000, 0.0000, 0.0000]
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81

# The LQR Controller parameters for "mode = 3"
gainMatrixThrust_NineStateVector    :  [ 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00]
gainMatrixRollRate                  :  [ 0.00,-1.80, 0.00, 0.00,-1.38, 0.00, 5.20, 0.00, 0.00]
gainMatrixPitchRate                 :  [ 1.80, 0.00, 0.00, 1.38, 0.00, 0.00, 0.00, 5.20, 0.00]
gainMatrixYawRate                   :  [ 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30]

# The LQR Controller parameters for "mode = 4"
gainMatrixThrust_SixStateVector     :  [ 0.00, 0.00, 0.31, 0.00, 0.00, 0.14]
gainMatrixRollAngle                 :  [ 0.00,-0.20, 0.00, 0.00,-0.20, 0.00]
gainMatrixPitchAngle                :  [ 0.20, 0.00, 0.00, 0.20, 0.00, 0.00]


# The max and minimum thrust for a 16-bit command
command_sixteenbit_min : 1000
82
83
84
85
86
87
88
89
command_sixteenbit_max : 60000


# THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
# > For the (x,y,z) position
PMKF_Ahat_row1_for_positions  :  [  0.6723, 0.0034]
PMKF_Ahat_row2_for_positions  :  [-12.9648, 0.9352]
PMKF_Kinf_for_positions       :  [  0.3277,12.9648]
90
91


92
# > For the (roll,pitch,yaw) angles
93
94
95
PMKF_Ahat_row1_for_angles     :  [  0.6954, 0.0035]
PMKF_Ahat_row2_for_angles     :  [-11.0342, 0.9448]
PMKF_Kinf_for_angles          :  [  0.3046,11.0342]
96

97
98
99
#PMKF_Ahat_row1_for_angles     :  [  0.6723, 0.0034]
#PMKF_Ahat_row2_for_angles     :  [-12.9648, 0.9352]
#PMKF_Kinf_for_angles          :  [  0.3277,12.9648]