99import matplotlib .pyplot as plt
1010import numpy as onp
1111from pathlib import Path
12- from typing import Callable , Dict , Optional , Literal
12+ from typing import Callable , Dict , Optional , Literal , Union
1313
1414import jsrm
1515from 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
1717
1818import time
1919import pickle
@@ -25,21 +25,21 @@ def simulate_planar_pcs_value_eval(
2525 num_segments : int ,
2626 type_of_derivation : Optional [Literal ["symbolic" , "numeric" ]] = "symbolic" ,
2727 type_of_integration : Optional [Literal ["gauss-legendre" , "gauss-kronrad" , "trapezoid" ]] = "gauss-legendre" ,
28- param_integration : int = None ,
28+ param_integration : Optional [ int ] = None ,
2929 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 ,
3434 t : float = 1.0 ,
35- dt : float = None ,
35+ dt : Optional [ float ] = None ,
3636 bool_print : bool = True ,
3737 bool_plot : bool = True ,
3838 bool_save_plot : bool = False ,
3939 bool_save_video : bool = True ,
4040 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
4343) -> Dict :
4444 """
4545 Simulate a planar PCS model. Save the video and figures.
@@ -81,7 +81,7 @@ def simulate_planar_pcs_value_eval(
8181 Defaults to None, which will use the default path.
8282
8383 Returns:
84- TODO
84+ simulation_dict (Dict): dictionary with the simulation results.
8585 """
8686
8787 # ===================================================
@@ -253,13 +253,12 @@ def simulate_planar_pcs_value_eval(
253253 results_path = (results_path_parent / file_name ).with_suffix (".pkl" )
254254
255255 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" :
258258 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 } "
260260 )
261- else :
262- results_path = Path (results_path )
261+ results_path = results_path_obj
263262 else :
264263 raise TypeError (
265264 f"results_path must be a string, but got { type (results_path ).__name__ } "
@@ -390,7 +389,7 @@ def draw_robot(
390389
391390 if type_of_derivation == "symbolic" :
392391 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 )
394393 )
395394 elif type_of_derivation == "numeric" :
396395 strain_basis , forward_kinematics_fn , dynamical_matrices_fn , auxiliary_fns = (
@@ -441,7 +440,7 @@ def draw_robot(
441440 y0 = x0 ,
442441 max_steps = None ,
443442 saveat = SaveAt (ts = video_ts ))
444- diffeqsolve_fn = jit (diffeqsolve_fn )
443+ diffeqsolve_fn = jit (diffeqsolve_fn ) # type: ignore
445444
446445 print ("Solving the ODE ..." )
447446 sol = diffeqsolve_fn ()
@@ -463,7 +462,7 @@ def draw_robot(
463462 forward_kinematics_fn_end_effector = partial (forward_kinematics_fn , robot_params , s = s_max )
464463
465464 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
467466 forward_kinematics_fn_end_effector = vmap (forward_kinematics_fn_end_effector )
468467
469468 print ("Computing the end-effector position along the trajectory..." )
@@ -619,7 +618,7 @@ def draw_robot(
619618 )
620619
621620 # Initialize the video
622- fourcc = cv2 .VideoWriter_fourcc (* "mp4v" )
621+ fourcc = cv2 .VideoWriter_fourcc (* "mp4v" ) # type: ignore
623622 video = cv2 .VideoWriter (
624623 str (video_path ),
625624 fourcc ,
@@ -649,6 +648,7 @@ def draw_robot(
649648 # ===========================
650649 if bool_save_res :
651650 print ("Saving the simulation results..." )
651+ assert results_path is not None , "results_path should not be None when saving results"
652652 with open (results_path , "wb" ) as f :
653653 pickle .dump (simulation_dict , f )
654654 print (f"Simulation results saved at { results_path } \n " )
@@ -665,20 +665,20 @@ def simulate_planar_pcs_time_eval(
665665 num_segments : int ,
666666 type_of_derivation : str = "symbolic" ,
667667 type_of_integration : str = "gauss-legendre" ,
668- param_integration : int = None ,
668+ param_integration : Optional [ int ] = None ,
669669 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 ,
674674 t : float = 1.0 ,
675- dt : float = None ,
675+ dt : Optional [ float ] = None ,
676676 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
682682) -> Dict :
683683 """
684684 Simulate a planar PCS model. Save the video and figures.
@@ -922,13 +922,12 @@ def simulate_planar_pcs_time_eval(
922922 results_path = (results_path_parent / file_name ).with_suffix (".pkl" )
923923
924924 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" :
927927 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 } "
929929 )
930- else :
931- results_path = Path (results_path )
930+ results_path = results_path_obj
932931 else :
933932 raise TypeError (
934933 f"results_path must be a string, but got { type (results_path ).__name__ } "
@@ -982,7 +981,7 @@ def simulate_planar_pcs_time_eval(
982981 timer_start = time .time ()
983982 if type_of_derivation == "symbolic" :
984983 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 )
986985 )
987986 elif type_of_derivation == "numeric" :
988987 strain_basis , forward_kinematics_fn , dynamical_matrices_fn , auxiliary_fns = (
@@ -1330,7 +1329,7 @@ def time_diffeqsolve_over_time():
13301329
13311330 # JIT the functions
13321331 print ("JIT-compiling the ODE function..." )
1333- diffeqsolve_fn = jit (diffeqsolve_fn )
1332+ diffeqsolve_fn = jit (diffeqsolve_fn ) # type: ignore
13341333
13351334 # First evaluation of the ODE to trigger JIT compilation
13361335 print ("Solving the ODE for the first time (JIT-compilation)..." )
@@ -1579,6 +1578,7 @@ def time_kinetic_energy_over_time():
15791578 # ===========================
15801579 if bool_save_res :
15811580 print ("Saving the simulation results..." )
1581+ assert results_path is not None , "results_path should not be None when saving results"
15821582 with open (results_path , "wb" ) as f :
15831583 pickle .dump (simulation_dict , f )
15841584 print (f"Simulation results saved at { results_path } \n " )
0 commit comments