@@ -149,59 +149,56 @@ def symbolic(mass: float, J: NDArray, dt: float) -> SymbolicModel:
149
149
Returns:
150
150
The CasADi symbolic model of the environment.
151
151
"""
152
- # Define states.
152
+ # # Define states.
153
153
z = MX .sym ("z" )
154
154
z_dot = MX .sym ("z_dot" )
155
-
156
- # Set up the dynamics model for a 3D quadrotor.
155
+ g = GRAVITY
156
+ # # Set up the dynamics model for a 3D quadrotor.
157
157
nx , nu = 12 , 4
158
- Ixx , Iyy , Izz = J .diagonal ()
159
- J = cs .blockcat ([[Ixx , 0.0 , 0.0 ], [0.0 , Iyy , 0.0 ], [0.0 , 0.0 , Izz ]])
160
- Jinv = cs .blockcat ([[1.0 / Ixx , 0.0 , 0.0 ], [0.0 , 1.0 / Iyy , 0.0 ], [0.0 , 0.0 , 1.0 / Izz ]])
161
- gamma = KM / KF
162
- # System state variables
163
- x , y = MX .sym ("x" ), MX .sym ("y" )
164
- x_dot , y_dot = MX .sym ("x_dot" ), MX .sym ("y_dot" )
165
- phi , theta , psi = MX .sym ("phi" ), MX .sym ("theta" ), MX .sym ("psi" )
166
- p , q , r = MX .sym ("p" ), MX .sym ("q" ), MX .sym ("r" )
167
- # Rotation matrix transforming a vector in the body frame to the world frame. PyBullet Euler
168
- # angles use the SDFormat for rotation matrices.
169
- Rob = csRotXYZ (phi , theta , psi )
170
- # Define state variables.
171
- X = cs .vertcat (x , x_dot , y , y_dot , z , z_dot , phi , theta , psi , p , q , r )
172
- # Define inputs.
173
- f1 , f2 , f3 , f4 = MX .sym ("f1" ), MX .sym ("f2" ), MX .sym ("f3" ), MX .sym ("f4" )
174
- U = cs .vertcat (f1 , f2 , f3 , f4 )
175
-
176
- # From Ch. 2 of Luis, Carlos, and Jérôme Le Ny. "Design of a trajectory tracking
177
- # controller for a nanoquadcopter." arXiv preprint arXiv:1608.05786 (2016).
178
-
179
- # Defining the dynamics function.
180
- # We are using the velocity of the base wrt to the world frame expressed in the world frame.
181
- # Note that the reference expresses this in the body frame.
182
- oVdot_cg_o = Rob @ cs .vertcat (0 , 0 , f1 + f2 + f3 + f4 ) / mass - cs .vertcat (0 , 0 , GRAVITY )
183
- pos_ddot = oVdot_cg_o
184
- pos_dot = cs .vertcat (x_dot , y_dot , z_dot )
185
- # We use the spin directions (signs) from the mix matrix used in the simulation.
186
- sx , sy , sz = SIGN_MIX_MATRIX [..., 0 ], SIGN_MIX_MATRIX [..., 1 ], SIGN_MIX_MATRIX [..., 2 ]
187
- Mb = cs .vertcat (
188
- ARM_LEN / cs .sqrt (2.0 ) * (sx [0 ] * f1 + sx [1 ] * f2 + sx [2 ] * f3 + sx [3 ] * f4 ),
189
- ARM_LEN / cs .sqrt (2.0 ) * (sy [0 ] * f1 + sy [1 ] * f2 + sy [2 ] * f3 + sy [3 ] * f4 ),
190
- gamma * (sz [0 ] * f1 + sz [1 ] * f2 + sz [2 ] * f3 + sz [3 ] * f4 ),
191
- )
192
- rate_dot = Jinv @ (Mb - (cs .skew (cs .vertcat (p , q , r )) @ J @ cs .vertcat (p , q , r )))
193
- ang_dot = cs .blockcat (
194
- [
195
- [1 , cs .sin (phi ) * cs .tan (theta ), cs .cos (phi ) * cs .tan (theta )],
196
- [0 , cs .cos (phi ), - cs .sin (phi )],
197
- [0 , cs .sin (phi ) / cs .cos (theta ), cs .cos (phi ) / cs .cos (theta )],
198
- ]
199
- ) @ cs .vertcat (p , q , r )
200
- X_dot = cs .vertcat (
201
- pos_dot [0 ], pos_ddot [0 ], pos_dot [1 ], pos_ddot [1 ], pos_dot [2 ], pos_ddot [2 ], ang_dot , rate_dot
202
- )
158
+ # Define states.
159
+ x = cs .MX .sym ('x' )
160
+ x_dot = cs .MX .sym ('x_dot' )
161
+ y = cs .MX .sym ('y' )
162
+ y_dot = cs .MX .sym ('y_dot' )
163
+ phi = cs .MX .sym ('phi' ) # roll angle [rad]
164
+ phi_dot = cs .MX .sym ('phi_dot' )
165
+ theta = cs .MX .sym ('theta' ) # pitch angle [rad]
166
+ theta_dot = cs .MX .sym ('theta_dot' )
167
+ psi = cs .MX .sym ('psi' ) # yaw angle [rad]
168
+ psi_dot = cs .MX .sym ('psi_dot' )
169
+ X = cs .vertcat (x , x_dot , y , y_dot , z , z_dot , phi , theta , psi , phi_dot , theta_dot , psi_dot )
170
+ # Define input collective thrust and theta.
171
+ T = cs .MX .sym ('T_c' ) # normalized thrust [N]
172
+ R = cs .MX .sym ('R_c' ) # desired roll angle [rad]
173
+ P = cs .MX .sym ('P_c' ) # desired pitch angle [rad]
174
+ Y = cs .MX .sym ('Y_c' ) # desired yaw angle [rad]
175
+ U = cs .vertcat (T , R , P , Y )
176
+ # The thrust in PWM is converted from the normalized thrust.
177
+ # With the formulat F_desired = b_F * T + a_F
178
+ params_acc = [20.907574256269616 , 3.653687545690674 ]
179
+ params_roll_rate = [- 130.3 , - 16.33 , 119.3 ]
180
+ params_pitch_rate = [- 99.94 , - 13.3 , 84.73 ]
181
+ params_yaw_rate = [0 , 0 , 0 ]
182
+
183
+ # Define dynamics equations.
184
+ # TODO: create a parameter for the new quad model
185
+ X_dot = cs .vertcat (x_dot ,
186
+ (params_acc [0 ] * T + params_acc [1 ]) * (
187
+ cs .cos (phi ) * cs .sin (theta ) * cs .cos (psi ) + cs .sin (phi ) * cs .sin (psi )),
188
+ y_dot ,
189
+ (params_acc [0 ] * T + params_acc [1 ]) * (
190
+ cs .cos (phi ) * cs .sin (theta ) * cs .sin (psi ) - cs .sin (phi ) * cs .cos (psi )),
191
+ z_dot ,
192
+ (params_acc [0 ] * T + params_acc [1 ]) * cs .cos (phi ) * cs .cos (theta ) - g ,
193
+ phi_dot ,
194
+ theta_dot ,
195
+ psi_dot ,
196
+ params_roll_rate [0 ] * phi + params_roll_rate [1 ] * phi_dot + params_roll_rate [2 ] * R ,
197
+ params_pitch_rate [0 ] * theta + params_pitch_rate [1 ] * theta_dot + params_pitch_rate [2 ] * P ,
198
+ params_yaw_rate [0 ] * psi + params_yaw_rate [1 ] * psi_dot + params_yaw_rate [2 ] * Y )
199
+ # Define observation.
200
+ Y = cs .vertcat (x , x_dot , y , y_dot , z , z_dot , phi , theta , psi , phi_dot , theta_dot , psi_dot )
203
201
204
- Y = cs .vertcat (x , x_dot , y , y_dot , z , z_dot , phi , theta , psi , p , q , r )
205
202
206
203
# Define cost (quadratic form).
207
204
Q , R = MX .sym ("Q" , nx , nx ), MX .sym ("R" , nu , nu )
0 commit comments