@@ -25,6 +25,7 @@ def factory(
25
25
[Dict [str , Array ], Array , Array ],
26
26
Tuple [Array , Array , Array , Array , Array , Array ],
27
27
],
28
+ Dict [str , Callable ],
28
29
]:
29
30
"""
30
31
Create jax functions from file containing symbolic expressions.
@@ -38,6 +39,7 @@ def factory(
38
39
B_xi: strain basis matrix of shape (3 * num_segments, n_q)
39
40
forward_kinematics_fn: function that returns the p vector of shape (3, n_q) with the positions
40
41
dynamical_matrices_fn: function that returns the B, C, G, K, D, and alpha matrices
42
+ auxiliary_fns: dictionary with auxiliary functions
41
43
"""
42
44
# load saved symbolic data
43
45
sym_exps = dill .load (open (str (filepath ), "rb" ))
@@ -249,5 +251,85 @@ def dynamical_matrices_fn(
249
251
alpha = B_xi .T @ jnp .identity (n_xi ) @ B_xi
250
252
251
253
return B , C , G , K , D , alpha
254
+
252
255
253
- return B_xi , forward_kinematics_fn , dynamical_matrices_fn
256
+ def kinetic_energy_fn (params : Dict [str , Array ], q : Array , q_d : Array ) -> Array :
257
+ """
258
+ Compute the kinetic energy of the system.
259
+ Args:
260
+ params: Dictionary of robot parameters
261
+ q: generalized coordinates of shape (n_q, )
262
+ q_d: generalized velocities of shape (n_q, )
263
+ Returns:
264
+ T: kinetic energy of shape ()
265
+ """
266
+ B , C , G , K , D , alpha = dynamical_matrices_fn (params , q = q , q_d = q_d )
267
+
268
+ # kinetic energy
269
+ T = (0.5 * q_d .T @ B @ q_d ).squeeze ()
270
+
271
+ return T
272
+
273
+
274
+ def potential_energy_fn (params : Dict [str , Array ], q : Array , eps : float = 1e4 * global_eps ) -> Array :
275
+ """
276
+ Compute the potential energy of the system.
277
+ Args:
278
+ params: Dictionary of robot parameters
279
+ q: generalized coordinates of shape (n_q, )
280
+ eps: small number to avoid singularities (e.g., division by zero)
281
+ Returns:
282
+ U: potential energy of shape ()
283
+ """
284
+ # map the configuration to the strains
285
+ xi = xi_eq + B_xi @ q
286
+ # add a small number to the bending strain to avoid singularities
287
+ xi_epsed = apply_eps_to_bend_strains (xi , eps )
288
+
289
+ # cross-sectional area and second moment of area
290
+ A = jnp .pi * params ["r" ] ** 2
291
+ Ib = A ** 2 / (4 * jnp .pi )
292
+
293
+ # elastic and shear modulus
294
+ E , G = params ["E" ], params ["G" ]
295
+ # stiffness matrix of shape (num_segments, 3, 3)
296
+ S = compute_stiffness_matrix_for_all_segments_fn (A , Ib , E , G )
297
+ # we define the elastic matrix of shape (n_xi, n_xi) as K(xi) = K @ xi where K is equal to
298
+ K = blk_diag (S )
299
+ # elastic energy
300
+ U_K = (xi - xi_eq ).T @ K @ (xi - xi_eq ) # evaluate K(xi) = K @ xi
301
+
302
+ # gravitational potential energy
303
+ U_G = sp .Matrix ([[0 ]])
304
+ params_for_lambdify = select_params_for_lambdify (params )
305
+ U_G = G_lambda (* params_for_lambdify , * xi_epsed ).squeeze () @ xi_epsed
306
+
307
+ # total potential energy
308
+ U = (U_G + U_K ).squeeze ()
309
+
310
+ return U
311
+
312
+ def energy_fn (params : Dict [str , Array ], q : Array , q_d : Array ) -> Array :
313
+ """
314
+ Compute the total energy of the system.
315
+ Args:
316
+ params: Dictionary of robot parameters
317
+ q: generalized coordinates of shape (n_q, )
318
+ q_d: generalized velocities of shape (n_q, )
319
+ Returns:
320
+ E: total energy of shape ()
321
+ """
322
+ T = kinetic_energy_fn (params , q_d )
323
+ U = potential_energy_fn (params , q )
324
+ E = T + U
325
+
326
+ return E
327
+
328
+ auxiliary_fns = {
329
+ "apply_eps_to_bend_strains" : apply_eps_to_bend_strains ,
330
+ "kinetic_energy_fn" : kinetic_energy_fn ,
331
+ "potential_energy_fn" : potential_energy_fn ,
332
+ "energy_fn" : energy_fn ,
333
+ }
334
+
335
+ return B_xi , forward_kinematics_fn , dynamical_matrices_fn , auxiliary_fns
0 commit comments