9
9
import matplotlib .pyplot as plt
10
10
import numpy as onp
11
11
from pathlib import Path
12
- from typing import Callable , Dict , Optional , Literal
12
+ from typing import Callable , Dict , Optional , Literal , Union
13
13
14
14
import jsrm
15
15
from jsrm import ode_factory
16
- from jsrm .systems import planar_pcs , planar_pcs_num
16
+ from jsrm .systems import planar_pcs_num , planar_pcs_sym
17
17
18
18
import time
19
19
import pickle
@@ -25,21 +25,21 @@ def simulate_planar_pcs_value_eval(
25
25
num_segments : int ,
26
26
type_of_derivation : Optional [Literal ["symbolic" , "numeric" ]] = "symbolic" ,
27
27
type_of_integration : Optional [Literal ["gauss-legendre" , "gauss-kronrad" , "trapezoid" ]] = "gauss-legendre" ,
28
- param_integration : int = None ,
28
+ param_integration : Optional [ int ] = None ,
29
29
type_of_jacobian : Optional [Literal ["explicit" , "autodiff" ]] = "explicit" ,
30
- robot_params : Dict [str , Array ] = None ,
31
- strain_selector : Array = None ,
32
- q0 : Array = None ,
33
- q_d0 : Array = None ,
30
+ robot_params : Optional [ Dict [str , Array ] ] = None ,
31
+ strain_selector : Optional [ Array ] = None ,
32
+ q0 : Optional [ Array ] = None ,
33
+ q_d0 : Optional [ Array ] = None ,
34
34
t : float = 1.0 ,
35
- dt : float = None ,
35
+ dt : Optional [ float ] = None ,
36
36
bool_print : bool = True ,
37
37
bool_plot : bool = True ,
38
38
bool_save_plot : bool = False ,
39
39
bool_save_video : bool = True ,
40
40
bool_save_res : bool = False ,
41
- results_path : str = None ,
42
- results_path_extension : str = None
41
+ results_path : Optional [ Union [ str , Path ]] = None ,
42
+ results_path_extension : Optional [ str ] = None
43
43
) -> Dict :
44
44
"""
45
45
Simulate a planar PCS model. Save the video and figures.
@@ -81,7 +81,7 @@ def simulate_planar_pcs_value_eval(
81
81
Defaults to None, which will use the default path.
82
82
83
83
Returns:
84
- TODO
84
+ simulation_dict (Dict): dictionary with the simulation results.
85
85
"""
86
86
87
87
# ===================================================
@@ -253,13 +253,12 @@ def simulate_planar_pcs_value_eval(
253
253
results_path = (results_path_parent / file_name ).with_suffix (".pkl" )
254
254
255
255
if isinstance (results_path , str ) or isinstance (results_path , Path ):
256
- results_path = Path (results_path )
257
- if results_path .suffix != ".pkl" :
256
+ results_path_obj = Path (results_path )
257
+ if results_path_obj .suffix != ".pkl" :
258
258
raise ValueError (
259
- f"results_path must have the suffix .pkl, but got { results_path .suffix } "
259
+ f"results_path must have the suffix .pkl, but got { results_path_obj .suffix } "
260
260
)
261
- else :
262
- results_path = Path (results_path )
261
+ results_path = results_path_obj
263
262
else :
264
263
raise TypeError (
265
264
f"results_path must be a string, but got { type (results_path ).__name__ } "
@@ -390,7 +389,7 @@ def draw_robot(
390
389
391
390
if type_of_derivation == "symbolic" :
392
391
strain_basis , forward_kinematics_fn , dynamical_matrices_fn , auxiliary_fns = (
393
- planar_pcs .factory (sym_exp_filepath , strain_selector )
392
+ planar_pcs_sym .factory (sym_exp_filepath , strain_selector )
394
393
)
395
394
elif type_of_derivation == "numeric" :
396
395
strain_basis , forward_kinematics_fn , dynamical_matrices_fn , auxiliary_fns = (
@@ -441,7 +440,7 @@ def draw_robot(
441
440
y0 = x0 ,
442
441
max_steps = None ,
443
442
saveat = SaveAt (ts = video_ts ))
444
- diffeqsolve_fn = jit (diffeqsolve_fn )
443
+ diffeqsolve_fn = jit (diffeqsolve_fn ) # type: ignore
445
444
446
445
print ("Solving the ODE ..." )
447
446
sol = diffeqsolve_fn ()
@@ -463,7 +462,7 @@ def draw_robot(
463
462
forward_kinematics_fn_end_effector = partial (forward_kinematics_fn , robot_params , s = s_max )
464
463
465
464
print ("JIT-compiling the forward kinematics function..." )
466
- forward_kinematics_fn_end_effector = jit (forward_kinematics_fn_end_effector )
465
+ forward_kinematics_fn_end_effector = jit (forward_kinematics_fn_end_effector ) # type: ignore
467
466
forward_kinematics_fn_end_effector = vmap (forward_kinematics_fn_end_effector )
468
467
469
468
print ("Computing the end-effector position along the trajectory..." )
@@ -619,7 +618,7 @@ def draw_robot(
619
618
)
620
619
621
620
# Initialize the video
622
- fourcc = cv2 .VideoWriter_fourcc (* "mp4v" )
621
+ fourcc = cv2 .VideoWriter_fourcc (* "mp4v" ) # type: ignore
623
622
video = cv2 .VideoWriter (
624
623
str (video_path ),
625
624
fourcc ,
@@ -649,6 +648,7 @@ def draw_robot(
649
648
# ===========================
650
649
if bool_save_res :
651
650
print ("Saving the simulation results..." )
651
+ assert results_path is not None , "results_path should not be None when saving results"
652
652
with open (results_path , "wb" ) as f :
653
653
pickle .dump (simulation_dict , f )
654
654
print (f"Simulation results saved at { results_path } \n " )
@@ -665,20 +665,20 @@ def simulate_planar_pcs_time_eval(
665
665
num_segments : int ,
666
666
type_of_derivation : str = "symbolic" ,
667
667
type_of_integration : str = "gauss-legendre" ,
668
- param_integration : int = None ,
668
+ param_integration : Optional [ int ] = None ,
669
669
type_of_jacobian : str = "explicit" ,
670
- robot_params : Dict [str , Array ] = None ,
671
- strain_selector : Array = None ,
672
- q0 : Array = None ,
673
- q_d0 : Array = None ,
670
+ robot_params : Optional [ Dict [str , Array ] ] = None ,
671
+ strain_selector : Optional [ Array ] = None ,
672
+ q0 : Optional [ Array ] = None ,
673
+ q_d0 : Optional [ Array ] = None ,
674
674
t : float = 1.0 ,
675
- dt : float = None ,
675
+ dt : Optional [ float ] = None ,
676
676
bool_save_res : bool = False ,
677
- results_path : str = None ,
678
- results_path_extension : str = None ,
679
- type_time = "once" ,
680
- nb_eval : int = None ,
681
- nb_samples : int = None
677
+ results_path : Optional [ Union [ str , Path ]] = None ,
678
+ results_path_extension : Optional [ str ] = None ,
679
+ type_time : str = "once" ,
680
+ nb_eval : Optional [ int ] = None ,
681
+ nb_samples : Optional [ int ] = None
682
682
) -> Dict :
683
683
"""
684
684
Simulate a planar PCS model. Save the video and figures.
@@ -922,13 +922,12 @@ def simulate_planar_pcs_time_eval(
922
922
results_path = (results_path_parent / file_name ).with_suffix (".pkl" )
923
923
924
924
if isinstance (results_path , str ) or isinstance (results_path , Path ):
925
- results_path = Path (results_path )
926
- if results_path .suffix != ".pkl" :
925
+ results_path_obj = Path (results_path )
926
+ if results_path_obj .suffix != ".pkl" :
927
927
raise ValueError (
928
- f"results_path must have the suffix .pkl, but got { results_path .suffix } "
928
+ f"results_path must have the suffix .pkl, but got { results_path_obj .suffix } "
929
929
)
930
- else :
931
- results_path = Path (results_path )
930
+ results_path = results_path_obj
932
931
else :
933
932
raise TypeError (
934
933
f"results_path must be a string, but got { type (results_path ).__name__ } "
@@ -982,7 +981,7 @@ def simulate_planar_pcs_time_eval(
982
981
timer_start = time .time ()
983
982
if type_of_derivation == "symbolic" :
984
983
strain_basis , forward_kinematics_fn , dynamical_matrices_fn , auxiliary_fns = (
985
- planar_pcs .factory (sym_exp_filepath , strain_selector )
984
+ planar_pcs_sym .factory (sym_exp_filepath , strain_selector )
986
985
)
987
986
elif type_of_derivation == "numeric" :
988
987
strain_basis , forward_kinematics_fn , dynamical_matrices_fn , auxiliary_fns = (
@@ -1330,7 +1329,7 @@ def time_diffeqsolve_over_time():
1330
1329
1331
1330
# JIT the functions
1332
1331
print ("JIT-compiling the ODE function..." )
1333
- diffeqsolve_fn = jit (diffeqsolve_fn )
1332
+ diffeqsolve_fn = jit (diffeqsolve_fn ) # type: ignore
1334
1333
1335
1334
# First evaluation of the ODE to trigger JIT compilation
1336
1335
print ("Solving the ODE for the first time (JIT-compilation)..." )
@@ -1579,6 +1578,7 @@ def time_kinetic_energy_over_time():
1579
1578
# ===========================
1580
1579
if bool_save_res :
1581
1580
print ("Saving the simulation results..." )
1581
+ assert results_path is not None , "results_path should not be None when saving results"
1582
1582
with open (results_path , "wb" ) as f :
1583
1583
pickle .dump (simulation_dict , f )
1584
1584
print (f"Simulation results saved at { results_path } \n " )
0 commit comments