21
21
def simulate_planar_pcs (
22
22
num_segments : int ,
23
23
type_of_derivation : str = "symbolic" ,
24
- type_of_integration : str = "gauss" ,
24
+ type_of_integration : str = "gauss-legendre " ,
25
25
param_integration : int = None ,
26
- bool_explicit : bool = True ,
26
+ type_of_jacobian : str = "explicit" ,
27
27
robot_params : Dict [str , Array ] = None ,
28
28
strain_selector : Array = None ,
29
29
q0 : Array = None ,
@@ -36,6 +36,7 @@ def simulate_planar_pcs(
36
36
bool_save_video : bool = True ,
37
37
bool_save_res : bool = False ,
38
38
results_path : str = None ,
39
+ results_path_extension : str = None
39
40
) -> Dict :
40
41
"""
41
42
Simulate a planar PCS model. Save the video and figures.
@@ -44,12 +45,12 @@ def simulate_planar_pcs(
44
45
num_segments (int): number of segments of the robot.
45
46
type_of_derivation (str, optional): type of derivation ("symbolic" or "numeric").
46
47
Defaults to "symbolic".
47
- type_of_integration (str, optional): scheme of integration ("gauss" or "trapezoid").
48
- Defaults to "gauss".
48
+ type_of_integration (str, optional): scheme of integration ("gauss-legendre", "gauss-kronrad " or "trapezoid").
49
+ Defaults to "gauss-legendre ".
49
50
param_integration (int, optional): parameter for the integration scheme (number of points for gauss or number of points for trapezoid).
50
51
Defaults to 1000 for trapezoid and 5 for gauss.
51
- bool_explicit (bool , optional): if True, use explicit expression for the jacobian, else use autodifferentiation to compute the jacobian .
52
- Defaults to True .
52
+ type_of_jacobian (str , optional): type of jacobian (" explicit" or "autodiff") .
53
+ Defaults to "explicit" .
53
54
strain_selector (Array, optional): selector for the strains as a boolean array.
54
55
Defaults to all.
55
56
robot_params (Dict[str, Array], optional): parameters of the robot.
@@ -73,6 +74,8 @@ def simulate_planar_pcs(
73
74
bool_save_res (bool, optional): if True, save the results of the simulation.
74
75
Defaults to False.
75
76
results_path (str, optional): path to save the dictionary with the simulation results. Must have the suffix .pkl.
77
+ results_path_extension (str, optional): extension to add to the results path.
78
+ Defaults to None, which will use the default path.
76
79
77
80
Returns:
78
81
Dict: simulation results
@@ -118,24 +121,24 @@ def simulate_planar_pcs(
118
121
if not isinstance (type_of_derivation , str ):
119
122
raise TypeError (f"type_of_derivation must be a string, but got { type (type_of_derivation ).__name__ } " )
120
123
if type_of_derivation == "numeric" :
121
- if type_of_integration not in ["gauss" , "trapezoid" ]:
122
- raise ValueError (
123
- f"type_of_integration must be 'gauss' or 'trapezoid', but got { type_of_integration } "
124
- )
124
+ if not isinstance (type_of_integration , str ):
125
+ raise TypeError (f"type_of_integration must be a string, but got { type (type_of_integration ).__name__ } " )
125
126
if param_integration is None :
126
- if type_of_integration == "gauss" :
127
+ if type_of_integration == "gauss-legendre " :
127
128
param_integration = 5
129
+ if type_of_integration == "gauss-kronrad" :
130
+ param_integration = 15
128
131
elif type_of_integration == "trapezoid" :
129
132
param_integration = 1000
130
133
if not isinstance (param_integration , int ):
131
134
raise TypeError (f"param_integration must be an integer, but got { type (param_integration ).__name__ } " )
132
135
if param_integration < 1 :
133
136
raise ValueError (f"param_integration must be greater than 0, but got { param_integration } " )
134
137
135
- if not isinstance ( bool_explicit , bool ) :
136
- raise TypeError ( f"bool_explicit must be a boolean, but got { type ( bool_explicit ). __name__ } " )
137
-
138
-
138
+ if type_of_jacobian not in [ "explicit" , "autodiff" ] :
139
+ raise ValueError (
140
+ f"type_of_jacobian must be 'explicit' or 'autodiff', but got { type_of_jacobian } "
141
+ )
139
142
140
143
elif type_of_derivation == "symbolic" :
141
144
# filepath to symbolic expressions
@@ -262,8 +265,15 @@ def simulate_planar_pcs(
262
265
/ f"ns-{ num_segments } " )
263
266
file_name = f"{ ('symb' if type_of_derivation == 'symbolic' else 'num' )} "
264
267
if type_of_derivation == "numeric" :
265
- file_name += f"-{ type_of_integration } -{ param_integration } -{ 'explicit' if bool_explicit else 'autodiff' } "
266
-
268
+ file_name += f"-{ type_of_integration } -{ param_integration } -{ type_of_jacobian } "
269
+
270
+ if results_path_extension is not None :
271
+ if not isinstance (results_path_extension , str ):
272
+ raise TypeError (
273
+ f"results_path_extension must be a string, but got { type (results_path_extension ).__name__ } "
274
+ )
275
+ file_name += f"-{ results_path_extension } "
276
+
267
277
results_path = (results_path_parent / file_name ).with_suffix (".pkl" )
268
278
269
279
if isinstance (results_path , str ) or isinstance (results_path , Path ):
@@ -373,7 +383,7 @@ def draw_robot(
373
383
"type_of_derivation" : type_of_derivation ,
374
384
"type_of_integration" : type_of_integration ,
375
385
"param_integration" : param_integration ,
376
- "bool_explicit " : bool_explicit ,
386
+ "type_of_jacobian " : type_of_jacobian ,
377
387
"robot_params" : robot_params ,
378
388
"strain_selector" : strain_selector ,
379
389
"q0" : q0 ,
@@ -398,6 +408,7 @@ def draw_robot(
398
408
print ("Parameter for integration:" , param_integration )
399
409
print ()
400
410
411
+ # ====================================================
401
412
# Import the planar PCS model depending on the type of derivation
402
413
print ("Importing the planar PCS model..." )
403
414
@@ -413,15 +424,16 @@ def draw_robot(
413
424
strain_selector ,
414
425
integration_type = type_of_integration ,
415
426
param_integration = param_integration ,
416
- bool_explicit = bool_explicit
427
+ jacobian_type = type_of_jacobian
417
428
)
418
429
)
419
430
timer_end = time .time ()
420
431
421
432
simulation_dict ["execution_time" ]["import_model" ] = timer_end - timer_start
422
433
423
434
print (f"Importing the planar PCS model took { timer_end - timer_start :.2e} seconds. \n " )
424
-
435
+
436
+ # ====================================================
425
437
# JIT the functions
426
438
print ("JIT-compiling the dynamical matrices function..." )
427
439
dynamical_matrices_fn = jax .jit (partial (dynamical_matrices_fn ))
@@ -431,8 +443,16 @@ def draw_robot(
431
443
432
444
timer_start = time .time ()
433
445
B , C , G , K , D , A = dynamical_matrices_fn (robot_params , q0 , jnp .zeros_like (q0 ))
446
+ B .block_until_ready () # ensure the matrices are computed
447
+ C .block_until_ready () # ensure the matrices are computed
448
+ G .block_until_ready () # ensure the matrices are computed
449
+ K .block_until_ready () # ensure the matrices are computed
450
+ D .block_until_ready () # ensure the matrices are computed
451
+ A .block_until_ready () # ensure the matrices are computed
434
452
timer_end = time .time ()
435
453
454
+ simulation_dict ["execution_time" ]["compile_dynamical_matrices" ] = timer_end - timer_start
455
+
436
456
if bool_print :
437
457
print ("B =\n " , B )
438
458
print ("C =\n " , C )
@@ -441,27 +461,33 @@ def draw_robot(
441
461
print ("D =\n " , D )
442
462
print ("A =\n " , A )
443
463
444
- simulation_dict ["execution_time" ]["compile_dynamical_matrices" ] = timer_end - timer_start
445
- simulation_dict ["results" ]["B_q0" ] = B
446
- simulation_dict ["results" ]["C_q0" ] = C
447
- simulation_dict ["results" ]["G_q0" ] = G
448
- simulation_dict ["results" ]["K_q0" ] = K
449
- simulation_dict ["results" ]["D_q0" ] = D
450
- simulation_dict ["results" ]["A_q0" ] = A
451
-
452
464
print (f"Evaluating the dynamical matrices for the first time took { timer_end - timer_start :.2e} seconds. \n " )
453
465
454
466
# Second evaluation of the dynamical matrices to capture the time of the evaluation
455
467
print ("Evaluating the dynamical matrices for the second time (JIT-evaluation)..." )
456
468
457
469
timer_start = time .time ()
458
470
B , C , G , K , D , A = dynamical_matrices_fn (robot_params , q0 , jnp .zeros_like (q0 ))
459
- timer_end = time .time ()
471
+ B .block_until_ready () # ensure the matrices are computed
472
+ C .block_until_ready () # ensure the matrices are computed
473
+ G .block_until_ready () # ensure the matrices are computed
474
+ K .block_until_ready () # ensure the matrices are computed
475
+ D .block_until_ready () # ensure the matrices are computed
476
+ A .block_until_ready () # ensure the matrices are computed
477
+ timer_end = time .time ()
460
478
461
479
simulation_dict ["execution_time" ]["evaluate_dynamical_matrices" ] = timer_end - timer_start
462
480
481
+ simulation_dict ["results" ]["B_q0" ] = B
482
+ simulation_dict ["results" ]["C_q0" ] = C
483
+ simulation_dict ["results" ]["G_q0" ] = G
484
+ simulation_dict ["results" ]["K_q0" ] = K
485
+ simulation_dict ["results" ]["D_q0" ] = D
486
+ simulation_dict ["results" ]["A_q0" ] = A
487
+
463
488
print (f"Evaluating the dynamical matrices for the second time took { timer_end - timer_start :.2e} seconds. \n " )
464
489
490
+ # ====================================================
465
491
# Parameter for the simulation
466
492
x0 = jnp .concatenate ([q0 , q_d0 ]) # initial condition
467
493
tau = jnp .zeros_like (q0 ) # torques
@@ -484,55 +510,75 @@ def draw_robot(
484
510
saveat = SaveAt (ts = video_ts ))
485
511
)
486
512
513
+ # ====================================================
487
514
# First evaluation of the ODE to trigger JIT compilation
488
515
print ("Solving the ODE for the first time (JIT-compilation)..." )
489
516
490
517
timer_start = time .time ()
491
518
sol = diffeqsolve_fn ()
519
+ sol .ys .block_until_ready () # ensure the solution is computed
492
520
timer_end = time .time ()
493
-
494
- # the evolution of the generalized coordinates
495
- q_ts = sol .ys [:, :n_dof ]
496
- # the evolution of the generalized velocities
497
- q_d_ts = sol .ys [:, n_dof :]
498
-
499
- if bool_print :
500
- print ("q_ts =\n " , q_ts )
501
- print ("q_d_ts =\n " , q_d_ts )
502
521
503
522
simulation_dict ["execution_time" ]["compile_ode" ] = timer_end - timer_start
504
- simulation_dict ["results" ]["q_ts" ] = q_ts
505
- simulation_dict ["results" ]["q_d_ts" ] = q_d_ts
506
523
507
- print (f"Solving the ODE took { timer_end - timer_start :.2e} seconds. \n " )
524
+ print (f"Solving the ODE for the first time took { timer_end - timer_start :.2e} seconds. \n " )
508
525
509
526
# Second evaluation of the ODE to capture the time of the evaluation
510
527
print ("Solving the ODE for the second time (JIT-evaluation)..." )
511
528
512
529
timer_start = time .time ()
513
530
sol = diffeqsolve_fn ()
531
+ sol .ys .block_until_ready () # ensure the solution is computed
514
532
timer_end = time .time ()
515
533
516
534
simulation_dict ["execution_time" ]["evaluate_ode" ] = timer_end - timer_start
517
535
536
+ # the evolution of the generalized coordinates
537
+ q_ts = sol .ys [:, :n_dof ].block_until_ready ()
538
+
539
+ # the evolution of the generalized velocities
540
+ q_d_ts = sol .ys [:, n_dof :].block_until_ready ()
541
+
542
+ if bool_print :
543
+ print ("q_ts =\n " , q_ts )
544
+ print ("q_d_ts =\n " , q_d_ts )
545
+
546
+ simulation_dict ["results" ]["q_ts" ] = q_ts
547
+ simulation_dict ["results" ]["q_d_ts" ] = q_d_ts
548
+
518
549
print (f"Solving the ODE for a second time took { timer_end - timer_start :.2e} seconds. \n " )
519
550
520
- # Evaluate the forward kinematics of the end-effector along the trajectory
521
- print ("Evaluating the forward kinematics of the end-effector along the trajectory..." )
551
+ # ====================================================
552
+ # First evaluation of the forward kinematics to trigger JIT compilation
553
+ print ("Evaluating the forward kinematics of the end-effector along the trajectory for the first time (JIT-compilation)..." )
522
554
523
555
timer_start = time .time ()
524
556
chi_ee_ts = vmap (forward_kinematics_fn , in_axes = (None , 0 , None ))(
525
557
robot_params , q_ts , jnp .array ([jnp .sum (robot_params ["l" ])])
526
- )
558
+ ). block_until_ready ()
527
559
timer_end = time .time ()
528
560
561
+ simulation_dict ["execution_time" ]["compile_forward_kinematics" ] = timer_end - timer_start
562
+
529
563
if bool_print :
530
564
print ("chi_ee_ts =\n " , chi_ee_ts )
531
565
566
+ print (f"Evaluating the forward kinematics for the first time took { timer_end - timer_start :.2e} seconds. \n " )
567
+
568
+ # Second evaluation of the forward kinematics to capture the time of the evaluation
569
+ print ("Evaluating the forward kinematics of the end-effector along the trajectory for a second time (JIT-evaluation)..." )
570
+
571
+ timer_start = time .time ()
572
+ chi_ee_ts = vmap (forward_kinematics_fn , in_axes = (None , 0 , None ))(
573
+ robot_params , q_ts , jnp .array ([jnp .sum (robot_params ["l" ])])
574
+ ).block_until_ready ()
575
+ timer_end = time .time ()
576
+
532
577
simulation_dict ["execution_time" ]["evaluate_forward_kinematics" ] = timer_end - timer_start
578
+
533
579
simulation_dict ["results" ]["chi_ee_ts" ] = chi_ee_ts
534
580
535
- print (f"Evaluating the forward kinematics took { timer_end - timer_start :.2e} seconds. \n " )
581
+ print (f"Evaluating the forward kinematics for a second time took { timer_end - timer_start :.2e} seconds. \n " )
536
582
537
583
#====================================================
538
584
# Plotting
@@ -610,32 +656,59 @@ def draw_robot(
610
656
plt .show ()
611
657
plt .close ()
612
658
613
- # Evaluate the energy along the trajectory
614
- print ("Evaluating the energy..." )
659
+ # ====================================================
660
+ # First evaluation of the potential energy to trigger JIT compilation
661
+ print ("Evaluating the potential energy for the first time (JIT-compilation)..." )
615
662
616
663
timer_start = time .time ()
617
- potential_energy_fn_vmapped = vmap (
618
- partial (auxiliary_fns ["potential_energy_fn" ], robot_params )
619
- )
620
- U_ts = potential_energy_fn_vmapped (q_ts )
664
+ U_ts = vmap (partial (auxiliary_fns ["potential_energy_fn" ], robot_params ))(q_ts ).block_until_ready ()
665
+ U_ts = U_ts .block_until_ready () # ensure the potential energy is computed
666
+ timer_end = time .time ()
667
+
668
+ simulation_dict ["execution_time" ]["compile_potential_energy" ] = timer_end - timer_start
669
+
670
+ print (f"Evaluating the potential energy took { timer_end - timer_start :.2e} seconds. \n " )
671
+
672
+ # Second evaluation of the potential energy to capture the time of the evaluation
673
+ print ("Evaluating the potential energy for a second time (JIT-evaluation)..." )
674
+
675
+ timer_start = time .time ()
676
+ U_ts = vmap (partial (auxiliary_fns ["potential_energy_fn" ], robot_params ))(q_ts ).block_until_ready ()
677
+ U_ts = U_ts .block_until_ready () # ensure the potential energy is computed
621
678
timer_end = time .time ()
622
679
623
680
simulation_dict ["execution_time" ]["evaluate_potential_energy" ] = timer_end - timer_start
681
+
624
682
simulation_dict ["results" ]["U_ts" ] = U_ts
625
683
626
- print ("Evaluating the potential energy took" , timer_end - timer_start , "seconds." )
684
+ print (f"Evaluating the potential energy for a second time took { timer_end - timer_start :.2e} seconds. \n " )
685
+
686
+ # ====================================================
687
+ # First evaluation of the kinetic energy to trigger JIT compilation
688
+ print ("Evaluating the kinetic energy for the first time (JIT-compilation)..." )
627
689
628
690
timer_start = time .time ()
629
- kinetic_energy_fn_vmapped = vmap (
630
- partial (auxiliary_fns ["kinetic_energy_fn" ], robot_params )
631
- )
632
- T_ts = kinetic_energy_fn_vmapped (q_ts , q_d_ts )
691
+ T_ts = vmap (partial (auxiliary_fns ["kinetic_energy_fn" ], robot_params ))(q_ts , q_d_ts ).block_until_ready ()
692
+ T_ts = T_ts .block_until_ready () # ensure the kinetic energy is computed
693
+ timer_end = time .time ()
694
+
695
+ simulation_dict ["execution_time" ]["compile_kinetic_energy" ] = timer_end - timer_start
696
+
697
+ print (f"Evaluating the kinetic energy took { timer_end - timer_start :.2e} seconds. \n " )
698
+
699
+ # Second evaluation of the kinetic energy to capture the time of the evaluation
700
+ print ("Evaluating the kinetic energy for a second time (JIT-evaluation)..." )
701
+
702
+ timer_start = time .time ()
703
+ T_ts = vmap (partial (auxiliary_fns ["kinetic_energy_fn" ], robot_params ))(q_ts , q_d_ts ).block_until_ready ()
704
+ T_ts = T_ts .block_until_ready () # ensure the kinetic energy is computed
633
705
timer_end = time .time ()
634
706
635
707
simulation_dict ["execution_time" ]["evaluate_kinetic_energy" ] = timer_end - timer_start
708
+
636
709
simulation_dict ["results" ]["T_ts" ] = T_ts
637
710
638
- print ("Evaluating the kinetic energy took" , timer_end - timer_start , " seconds. \n " )
711
+ print (f "Evaluating the kinetic energy for a second time took { timer_end - timer_start :.2e } seconds. \n " )
639
712
640
713
if bool_print :
641
714
print ("U_ts =\n " , U_ts )
@@ -669,8 +742,6 @@ def draw_robot(
669
742
if bool_save_video :
670
743
print ("Drawing the robot..." )
671
744
672
- timer_start = time .time ()
673
-
674
745
# Vectorize the forward kinematics function according to the s coordinates
675
746
print ("Vectorizing the forward kinematics function according to the number of segments..." )
676
747
batched_forward_kinematics = vmap (
@@ -701,11 +772,6 @@ def draw_robot(
701
772
# Release the video
702
773
video .release ()
703
774
704
- timer_end = time .time ()
705
-
706
- simulation_dict ["execution_time" ]["draw_robot" ] = timer_end - timer_start
707
-
708
- print (f"Drawing the robot took { timer_end - timer_start :.2e} seconds. \n " )
709
775
print (f"Video saved at { video_path } . \n " )
710
776
711
777
# ===========================================================================
@@ -729,7 +795,7 @@ def draw_robot(
729
795
simulate_res = simulate_planar_pcs (
730
796
num_segments = 1 ,
731
797
type_of_derivation = "numeric" , #"symbolic"
732
- type_of_integration = "quadgk" , #" gauss", # "quadgk", " trapezoid", "quadcc", "quadts",
798
+ type_of_integration = "gauss" , # "trapezoid"
733
799
# param_integration = 30,
734
800
strain_selector = [True , False , True ],
735
801
bool_print = True ,
0 commit comments