diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index fda4b41..54d87fa 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -13,9 +13,9 @@ jobs: runs-on: ubuntu-latest steps: - name: Checkout - uses: actions/checkout@v2 + uses: actions/checkout@v4 - name: Set up Python - uses: actions/setup-python@v1 + uses: actions/setup-python@v5 with: python-version: '3.x' - name: Install build dependencies diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index d44a4ed..ed2e7df 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -9,14 +9,14 @@ jobs: test: strategy: matrix: - python: ['3.10', '3.11', '3.12'] + python: ['3.10', '3.11', '3.12', '3.13'] platform: [ubuntu-latest, macos-latest, windows-latest] runs-on: ${{ matrix.platform }} steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Set up Python ${{ matrix.python }} - uses: actions/setup-python@v3 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python }} - name: Install test dependencies diff --git a/examples/analyze_segment_fusion.py b/examples/analyze_segment_fusion.py index fe6a0db..fd855cc 100644 --- a/examples/analyze_segment_fusion.py +++ b/examples/analyze_segment_fusion.py @@ -1,8 +1,12 @@ import sympy as sp -l1, l2 = sp.symbols('l1 l2', nonnegative=True, nonzero=True) -kappa_be1, sigma_sh1, sigma_ax1 = sp.symbols('kappa_be1 sigma_sh1 sigma_ax1', real=True, nonnegative=True, nonzero=True) -kappa_be2, sigma_sh2, sigma_ax2 = sp.symbols('kappa_be2 sigma_sh2 sigma_ax2', real=True, nonnegative=True, nonzero=True) +l1, l2 = sp.symbols("l1 l2", nonnegative=True, nonzero=True) +kappa_be1, sigma_sh1, sigma_ax1 = sp.symbols( + "kappa_be1 sigma_sh1 sigma_ax1", real=True, nonnegative=True, nonzero=True +) +kappa_be2, sigma_sh2, sigma_ax2 = sp.symbols( + "kappa_be2 sigma_sh2 sigma_ax2", real=True, nonnegative=True, nonzero=True +) # deactivate shear and axial strains # sigma_sh1, sigma_sh2 = 0.0, 0.0 @@ -19,30 +23,42 @@ # apply the forward kinematics on the individual segments s_be1, c_be1 = sp.sin(kappa_be1 * l1), sp.cos(kappa_be1 * l1) s_be2, c_be2 = sp.sin(kappa_be2 * l2), sp.cos(kappa_be2 * l2) -chi1 = sp.Matrix([ - [sigma_sh1 * s_be1 / kappa_be1 + sigma_ax1 * (c_be1 - 1) / kappa_be1], - [sigma_sh1 * (1 - c_be1) / kappa_be1 + sigma_ax1 * s_be1 / kappa_be1], - [kappa_be1 * l1], -]) +chi1 = sp.Matrix( + [ + [sigma_sh1 * s_be1 / kappa_be1 + sigma_ax1 * (c_be1 - 1) / kappa_be1], + [sigma_sh1 * (1 - c_be1) / kappa_be1 + sigma_ax1 * s_be1 / kappa_be1], + [kappa_be1 * l1], + ] +) # rotation matrix -R1 = sp.Matrix([ - [c_be1, -s_be1, 0], - [s_be1, c_be1, 0], - [0, 0, 1], -]) -chi2_rel = sp.Matrix([ - [sigma_sh2 * s_be2 / kappa_be2 + sigma_ax2 * (c_be2 - 1) / kappa_be2], - [sigma_sh2 * (1 - c_be2) / kappa_be2 + sigma_ax2 * s_be2 / kappa_be2], - [kappa_be2 * l2], -]) +R1 = sp.Matrix( + [ + [c_be1, -s_be1, 0], + [s_be1, c_be1, 0], + [0, 0, 1], + ] +) +chi2_rel = sp.Matrix( + [ + [sigma_sh2 * s_be2 / kappa_be2 + sigma_ax2 * (c_be2 - 1) / kappa_be2], + [sigma_sh2 * (1 - c_be2) / kappa_be2 + sigma_ax2 * s_be2 / kappa_be2], + [kappa_be2 * l2], + ] +) chi2 = sp.simplify(chi1 + R1 @ chi2_rel) # print("chi2 =\n", chi2) # apply the one-segment inverse kinematic on the distal end of the two segments px, py, th = chi2[0, 0], chi2[1, 0], chi2[2, 0] s_th, c_th = sp.sin(th), sp.cos(th) -qfkik = sp.simplify(th / (2 * (l1 + l2)) * sp.Matrix([ - [2], - [py - px * s_th / (c_th - 1)], - [-px - py * s_th / (c_th - 1)], -])) +qfkik = sp.simplify( + th + / (2 * (l1 + l2)) + * sp.Matrix( + [ + [2], + [py - px * s_th / (c_th - 1)], + [-px - py * s_th / (c_th - 1)], + ] + ) +) print("qfkik =\n", qfkik) diff --git a/examples/demo_planar_hsa_motor2ee_jacobian.py b/examples/demo_planar_hsa_motor2ee_jacobian.py index d4794f3..ade693b 100644 --- a/examples/demo_planar_hsa_motor2ee_jacobian.py +++ b/examples/demo_planar_hsa_motor2ee_jacobian.py @@ -26,7 +26,9 @@ ) -def factory_fn(params: Dict[str, Array], verbose: bool = False) -> Tuple[Callable, Callable]: +def factory_fn( + params: Dict[str, Array], verbose: bool = False +) -> Tuple[Callable, Callable]: """ Factory function for the planar HSA. Args: @@ -45,7 +47,9 @@ def factory_fn(params: Dict[str, Array], verbose: bool = False) -> Tuple[Callabl sys_helpers, ) = planar_hsa.factory(sym_exp_filepath, strain_selector) dynamical_matrices_fn = partial(dynamical_matrices_fn, params) - forward_kinematics_end_effector_fn = jit(partial(forward_kinematics_end_effector_fn, params)) + forward_kinematics_end_effector_fn = jit( + partial(forward_kinematics_end_effector_fn, params) + ) jacobian_end_effector_fn = jit(partial(jacobian_end_effector_fn, params)) def residual_fn(q: Array, phi: Array) -> Array: @@ -64,7 +68,9 @@ def residual_fn(q: Array, phi: Array) -> Array: print("Compiling jac_residual_fn...") print(jac_residual_fn(jnp.zeros((3,)), jnp.zeros((2,)))) - def phi2q_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tuple[Array, Dict[str, Array]]: + def phi2q_static_model_fn( + phi: Array, q0: Array = jnp.zeros((3,)) + ) -> Tuple[Array, Dict[str, Array]]: """ A static model mapping the motor angles to the planar HSA configuration using scipy.optimize.minimize. Arguments: @@ -82,7 +88,12 @@ def phi2q_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tuple[Arr options={"disp": True} if verbose else None, ) if verbose: - print("Optimization converged after", sol.nit, "iterations with residual", sol.fun) + print( + "Optimization converged after", + sol.nit, + "iterations with residual", + sol.fun, + ) # configuration that minimizes the residual q = jnp.array(sol.x) @@ -95,7 +106,9 @@ def phi2q_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tuple[Arr return q, aux - def phi2chi_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tuple[Array, Dict[str, Array]]: + def phi2chi_static_model_fn( + phi: Array, q0: Array = jnp.zeros((3,)) + ) -> Tuple[Array, Dict[str, Array]]: """ A static model mapping the motor angles to the planar end-effector pose. Arguments: @@ -110,7 +123,9 @@ def phi2chi_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tuple[A aux["chi"] = chi return chi, aux - def jac_phi2chi_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tuple[Array, Dict[str, Array]]: + def jac_phi2chi_static_model_fn( + phi: Array, q0: Array = jnp.zeros((3,)) + ) -> Tuple[Array, Dict[str, Array]]: """ Compute the Jacobian between the actuation space and the task-space. Arguments: @@ -157,12 +172,7 @@ def jac_phi2chi_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tup phi = jnp.array([1.0, 1.0]) case _: rng, subkey = random.split(rng) - phi = random.uniform( - subkey, - phi_max.shape, - minval=0.0, - maxval=phi_max - ) + phi = random.uniform(subkey, phi_max.shape, minval=0.0, maxval=phi_max) print("i", i) @@ -170,4 +180,4 @@ def jac_phi2chi_static_model_fn(phi: Array, q0: Array = jnp.zeros((3, ))) -> Tup print("phi", phi, "q", aux["q"], "chi", chi) J_phi2chi, aux = jac_phi2chi_static_model_fn(phi, q0=q0) - print("J_phi2chi:\n", J_phi2chi) \ No newline at end of file + print("J_phi2chi:\n", J_phi2chi) diff --git a/examples/derive_planar_pcs.py b/examples/derive_planar_pcs.py index 8462062..8923f51 100644 --- a/examples/derive_planar_pcs.py +++ b/examples/derive_planar_pcs.py @@ -12,5 +12,7 @@ / f"planar_pcs_ns-{NUM_SEGMENTS}.dill" ) symbolically_derive_planar_pcs_model( - num_segments=NUM_SEGMENTS, filepath=sym_exp_filepath, simplify_expressions=True + num_segments=NUM_SEGMENTS, + filepath=sym_exp_filepath, + simplify_expressions=True if NUM_SEGMENTS < 3 else False, ) diff --git a/examples/simulate_planar_pcs.py b/examples/simulate_planar_pcs.py index ba84afb..eb3daa0 100644 --- a/examples/simulate_planar_pcs.py +++ b/examples/simulate_planar_pcs.py @@ -43,7 +43,7 @@ strain_selector = jnp.array([True, False, False]) # define initial configuration -q0 = jnp.array([10 * jnp.pi]) +q0 = jnp.array([5 * jnp.pi]) # number of generalized coordinates n_q = q0.shape[0] @@ -95,8 +95,8 @@ def draw_robot( if __name__ == "__main__": - strain_basis, forward_kinematics_fn, dynamical_matrices_fn, auxiliary_fns = planar_pcs.factory( - sym_exp_filepath, strain_selector + strain_basis, forward_kinematics_fn, dynamical_matrices_fn, auxiliary_fns = ( + planar_pcs.factory(sym_exp_filepath, strain_selector) ) batched_forward_kinematics = vmap( forward_kinematics_fn, in_axes=(None, None, 0), out_axes=-1 @@ -142,9 +142,38 @@ def draw_robot( # the evolution of the generalized velocities q_d_ts = sol.ys[:, n_q:] + # evaluate the forward kinematics along the trajectory + chi_ee_ts = vmap(forward_kinematics_fn, in_axes=(None, 0, None))( + params, q_ts, jnp.array([jnp.sum(params["l"])]) + ) + # plot the end-effector position along the trajectory + plt.figure() + plt.plot(chi_ee_ts[0, :], chi_ee_ts[1, :]) + plt.axis("equal") + plt.grid(True) + plt.xlabel("End-effector x [m]") + plt.ylabel("End-effector y [m]") + plt.tight_layout() + plt.show() + # plot end-effector position vs time + plt.figure() + plt.plot(video_ts, chi_ee_ts[:, 0], label="x") + plt.plot(video_ts, chi_ee_ts[:, 1], label="y") + plt.xlabel("Time [s]") + plt.ylabel("End-effector Position [m]") + plt.legend() + plt.grid(True) + plt.box(True) + plt.tight_layout() + plt.show() + # plot the energy along the trajectory - kinetic_energy_fn_vmapped = vmap(partial(auxiliary_fns["kinetic_energy_fn"], params)) - potential_energy_fn_vmapped = vmap(partial(auxiliary_fns["potential_energy_fn"], params)) + kinetic_energy_fn_vmapped = vmap( + partial(auxiliary_fns["kinetic_energy_fn"], params) + ) + potential_energy_fn_vmapped = vmap( + partial(auxiliary_fns["potential_energy_fn"], params) + ) U_ts = potential_energy_fn_vmapped(q_ts) T_ts = kinetic_energy_fn_vmapped(q_ts, q_d_ts) plt.figure() @@ -155,6 +184,7 @@ def draw_robot( plt.legend() plt.grid(True) plt.box(True) + plt.tight_layout() plt.show() # create video diff --git a/pyproject.toml b/pyproject.toml index 3bf9f56..c9e3049 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -17,7 +17,7 @@ name = "jsrm" # Required # # For a discussion on single-sourcing the version, see # https://packaging.python.org/guides/single-sourcing-package-version/ -version = "0.0.10" # Required +version = "0.0.11" # Required # This is a one-line description or tagline of what your project does. This # corresponds to the "Summary" metadata field: @@ -88,10 +88,10 @@ classifiers = [ # Optional # that you indicate you support Python 3. These classifiers are *not* # checked by "pip install". See instead "python_requires" below. "Programming Language :: Python :: 3", - "Programming Language :: Python :: 3.9", "Programming Language :: Python :: 3.10", "Programming Language :: Python :: 3.11", "Programming Language :: Python :: 3.12", + "Programming Language :: Python :: 3.13", "Programming Language :: Python :: 3 :: Only", ] diff --git a/src/jsrm/symbolic_derivation/planar_hsa.py b/src/jsrm/symbolic_derivation/planar_hsa.py index 2cfe74c..287503b 100644 --- a/src/jsrm/symbolic_derivation/planar_hsa.py +++ b/src/jsrm/symbolic_derivation/planar_hsa.py @@ -219,7 +219,7 @@ def symbolically_derive_planar_hsa_model( # inertia matrix B = sp.zeros(num_dof, num_dof) # potential energy - U = sp.Matrix([[0]]) + U_g = sp.Matrix([[0]]) # stiffness matrix Shat = sp.zeros(3 * num_segments, 3 * num_segments) # elastic vector @@ -299,11 +299,11 @@ def symbolically_derive_planar_hsa_model( B = B + Br_ij # derivative of the potential energy with respect to the point coordinate s - dUr_ds = sp.simplify(rhor[i, j] * Ar[i, j] * g.T @ pr) + dU_g_r_ds = sp.simplify(-rhor[i, j] * Ar[i, j] * g.T @ pr) # potential energy of the current segment - U_ij = sp.simplify(sp.integrate(dUr_ds, (s, 0, l[i]))) + U_g_ij = sp.simplify(sp.integrate(dU_g_r_ds, (s, 0, l[i]))) # add potential energy of segment to previous segments - U = U + U_ij + U_g = U_g + U_g_ij # strains in physical HSA rod pxir = _sym_beta_fn(vxi, roff[i, j]) @@ -466,8 +466,8 @@ def symbolically_derive_planar_hsa_model( Bp = sp.simplify(Bp) B = B + Bp # potential energy of the platform - Up = sp.simplify(mp * g.T @ pCoGp) - U = U + Up + U_g_p = sp.simplify(-mp * g.T @ pCoGp) + U_g = U_g + U_g_p # update the orientation for the next segment th_prev = th.subs(s, l[i]) @@ -507,8 +507,8 @@ def symbolically_derive_planar_hsa_model( Bpl = sp.simplify(Bpl) B = B + Bpl # add the gravitational potential energy of the payload - Upl = sp.simplify(mpl * g.T @ pCoGpl) - U = U + Upl + Upl = sp.simplify(-mpl * g.T @ pCoGpl) + U_g = U_g + Upl # simplify mass matrix if simplify: @@ -519,7 +519,7 @@ def symbolically_derive_planar_hsa_model( print("C =\n", C) # compute the gravity force vector - G = -U.jacobian(xi).transpose() + G = U_g.jacobian(xi).transpose() if simplify: G = sp.simplify(G) print("G =\n", G) diff --git a/src/jsrm/symbolic_derivation/planar_pcs.py b/src/jsrm/symbolic_derivation/planar_pcs.py index 4a96d68..bfc3bc0 100644 --- a/src/jsrm/symbolic_derivation/planar_pcs.py +++ b/src/jsrm/symbolic_derivation/planar_pcs.py @@ -3,11 +3,13 @@ import sympy as sp from typing import Callable, Dict, Optional, Tuple, Union -from .symbolic_utils import compute_coriolis_matrix +from .symbolic_utils import compute_coriolis_matrix, compute_dAdt def symbolically_derive_planar_pcs_model( - num_segments: int, filepath: Optional[Union[str, Path]] = None, simplify_expressions: bool = True + num_segments: int, + filepath: Optional[Union[str, Path]] = None, + simplify_expressions: bool = True, ) -> Dict: """ Symbolically derive the kinematics and dynamics of a planar continuum soft robot modelled with @@ -55,8 +57,8 @@ def symbolically_derive_planar_pcs_model( # matrix with symbolic expressions to derive the poses along each segment chi_sms = [] - # Jacobians (positional + orientation) in each segment as a function of the point coordinate s - J_sms = [] + # Jacobians (positional + orientation) in each segment as a function of the point coordinate s and its time derivative + J_sms, J_d_sms = [], [] # cross-sectional area of each segment A = sp.zeros(num_segments) # second area moment of inertia of each segment @@ -64,7 +66,7 @@ def symbolically_derive_planar_pcs_model( # inertia matrix B = sp.zeros(num_dof, num_dof) # potential energy - U = sp.Matrix([[0]]) + U_g = sp.Matrix([[0]]) # symbol for the point coordinate s = sp.symbols("s", real=True, nonnegative=True) @@ -118,6 +120,10 @@ def symbolically_derive_planar_pcs_model( J = Jp.col_join(Jo) J_sms.append(J) + # compute the time derivative of the Jacobian + J_d = compute_dAdt(J, xi, xi_d) # time derivative of the end-effector Jacobian + J_d_sms.append(J_d) + # derivative of mass matrix with respect to the point coordinate s dB_ds = rho[i] * A[i] * Jp.T @ Jp + rho[i] * I[i] * Jo.T @ Jo if simplify_expressions: @@ -130,15 +136,15 @@ def symbolically_derive_planar_pcs_model( B = B + B_i # derivative of the potential energy with respect to the point coordinate s - dU_ds = rho[i] * A[i] * g.T @ p + dU_g_ds = -rho[i] * A[i] * g.T @ p if simplify_expressions: - dU_ds = sp.simplify(dU_ds) - # potential energy of the current segment - U_i = sp.integrate(dU_ds, (s, 0, l[i])) + dU_g_ds = sp.simplify(dU_g_ds) + # gravitational potential energy of the current segment + U_gi = sp.integrate(dU_g_ds, (s, 0, l[i])) if simplify_expressions: - U_i = sp.simplify(U_i) + U_gi = sp.simplify(U_gi) # add potential energy of segment to previous segments - U = U + U_i + U_g = U_g + U_gi # update the orientation for the next segment th_prev = th.subs(s, l[i]) @@ -151,11 +157,11 @@ def symbolically_derive_planar_pcs_model( B = sp.simplify(B) print("B =\n", B) - C = compute_coriolis_matrix(B, xi, xi_d) + C = compute_coriolis_matrix(B, xi, xi_d, simplify=simplify_expressions) print("C =\n", C) # compute the gravity force vector - G = -U.jacobian(xi).transpose() + G = U_g.jacobian(xi).transpose() if simplify_expressions: G = sp.simplify(G) print("G =\n", G) @@ -179,12 +185,18 @@ def symbolically_derive_planar_pcs_model( "chiee": chi_sms[-1].subs( s, l[-1] ), # expression for end-effector pose of shape (3, ) - "J_sms": J_sms, - "Jee": J_sms[-1].subs(s, l[-1]), + "J_sms": J_sms, # list of Jacobians (for each segment) of shape (3, num_dof) + "Jee": J_sms[-1].subs( + s, l[-1] + ), # end-effector Jacobian of shape (3, num_dof) + "J_d_sms": J_d_sms, # list of time derivatives of Jacobians (for each segment) + "Jee_d": J_d_sms[-1].subs( + s, l[-1] + ), # time derivative of end-effector Jacobian of shape (3, num_dof) "B": B, # mass matrix "C": C, # coriolis matrix "G": G, # gravity vector - "U": U, # gravitational potential energy + "U_g": U_g, # gravitational potential energy }, } diff --git a/src/jsrm/symbolic_expressions/planar_pcs_ns-1.dill b/src/jsrm/symbolic_expressions/planar_pcs_ns-1.dill index 57a26ef..9118c75 100644 Binary files a/src/jsrm/symbolic_expressions/planar_pcs_ns-1.dill and b/src/jsrm/symbolic_expressions/planar_pcs_ns-1.dill differ diff --git a/src/jsrm/symbolic_expressions/planar_pcs_ns-2.dill b/src/jsrm/symbolic_expressions/planar_pcs_ns-2.dill index 9343291..f45a909 100644 Binary files a/src/jsrm/symbolic_expressions/planar_pcs_ns-2.dill and b/src/jsrm/symbolic_expressions/planar_pcs_ns-2.dill differ diff --git a/src/jsrm/symbolic_expressions/planar_pcs_ns-3.dill b/src/jsrm/symbolic_expressions/planar_pcs_ns-3.dill index d44d0da..1a0fdec 100644 Binary files a/src/jsrm/symbolic_expressions/planar_pcs_ns-3.dill and b/src/jsrm/symbolic_expressions/planar_pcs_ns-3.dill differ diff --git a/src/jsrm/symbolic_expressions/planar_pcs_ns-4.dill b/src/jsrm/symbolic_expressions/planar_pcs_ns-4.dill new file mode 100644 index 0000000..e552c1e Binary files /dev/null and b/src/jsrm/symbolic_expressions/planar_pcs_ns-4.dill differ diff --git a/src/jsrm/symbolic_expressions/planar_pcs_ns-5.dill b/src/jsrm/symbolic_expressions/planar_pcs_ns-5.dill new file mode 100644 index 0000000..c0e3720 Binary files /dev/null and b/src/jsrm/symbolic_expressions/planar_pcs_ns-5.dill differ diff --git a/src/jsrm/systems/planar_pcs.py b/src/jsrm/systems/planar_pcs.py index 14bee58..5b1ba94 100644 --- a/src/jsrm/systems/planar_pcs.py +++ b/src/jsrm/systems/planar_pcs.py @@ -1,6 +1,7 @@ import dill from jax import Array, jit, lax, vmap from jax import numpy as jnp +import numpy as onp import sympy as sp from pathlib import Path from typing import Callable, Dict, List, Tuple, Union @@ -48,7 +49,7 @@ def factory( params_syms = sym_exps["params_syms"] @jit - def select_params_for_lambdify(params: Dict[str, Array]) -> List[Array]: + def select_params_for_lambdify_fn(params: Dict[str, Array]) -> List[Array]: """ Select the parameters for lambdify Args: @@ -101,6 +102,27 @@ def select_params_for_lambdify(params: Dict[str, Array]) -> List[Array]: "jax", ) chi_lambda_sms.append(chi_lambda) + J_lambda_sms = [] + for J_exp in sym_exps["exps"]["J_sms"]: + J_lambda = sp.lambdify( + params_syms_cat + + sym_exps["state_syms"]["xi"] + + [sym_exps["state_syms"]["s"]], + J_exp, + "jax", + ) + J_lambda_sms.append(J_lambda) + J_d_lambda_sms = [] + for J_d_exp in sym_exps["exps"]["J_d_sms"]: + J_d_lambda = sp.lambdify( + params_syms_cat + + sym_exps["state_syms"]["xi"] + + sym_exps["state_syms"]["xi_d"] + + [sym_exps["state_syms"]["s"]], + J_d_exp, + "jax", + ) + J_d_lambda_sms.append(J_d_lambda) B_lambda = sp.lambdify( params_syms_cat + sym_exps["state_syms"]["xi"], sym_exps["exps"]["B"], "jax" @@ -111,8 +133,8 @@ def select_params_for_lambdify(params: Dict[str, Array]) -> List[Array]: G_lambda = sp.lambdify( params_syms_cat + sym_exps["state_syms"]["xi"], sym_exps["exps"]["G"], "jax" ) - U_lambda = sp.lambdify( - params_syms_cat + sym_exps["state_syms"]["xi"], sym_exps["exps"]["U"], "jax" + U_g_lambda = sp.lambdify( + params_syms_cat + sym_exps["state_syms"]["xi"], sym_exps["exps"]["U_g"], "jax" ) compute_stiffness_matrix_for_all_segments_fn = vmap( @@ -153,6 +175,57 @@ def apply_eps_to_bend_strains(xi: Array, _eps: float) -> Array: return xi_epsed + def classify_segment(params: Dict[str, Array], s: Array) -> Tuple[Array, Array]: + """ + Classify the point along the robot to the corresponding segment + Args: + params: Dictionary of robot parameters + s: point coordinate along the robot in the interval [0, L]. + Returns: + segment_idx: index of the segment + s_segment: point coordinate along the segment in the interval [0, l_segment + """ + # cumsum of the segment lengths + l_cum = jnp.cumsum(params["l"]) + # add zero to the beginning of the array + l_cum_padded = jnp.concatenate([jnp.array([0.0]), l_cum], axis=0) + # determine in which segment the point is located + # use argmax to find the last index where the condition is true + segment_idx = ( + l_cum.shape[0] - 1 - jnp.argmax((s >= l_cum_padded[:-1])[::-1]).astype(int) + ) + # point coordinate along the segment in the interval [0, l_segment] + s_segment = s - l_cum_padded[segment_idx] + + return segment_idx, s_segment + + def stiffness_fn( + params: Dict[str, Array], formulate_in_strain_space: bool = False + ) -> Array: + """ + Compute the stiffness matrix of the system. + Args: + params: Dictionary of robot parameters + + Returns: + K: elastic matrix of shape (n_q, n_q) if formulate_in_strain_space is False or (n_xi, n_xi) otherwise + """ + # cross-sectional area and second moment of area + A = jnp.pi * params["r"] ** 2 + Ib = A**2 / (4 * jnp.pi) + + # elastic and shear modulus + E, G = params["E"], params["G"] + # stiffness matrix of shape (num_segments, 3, 3) + S = compute_stiffness_matrix_for_all_segments_fn(A, Ib, E, G) + # we define the elastic matrix of shape (n_xi, n_xi) as K(xi) = K @ xi where K is equal to + K = blk_diag(S) + + if not formulate_in_strain_space: + K = B_xi.T @ K @ B_xi + + return K + @jit def forward_kinematics_fn( params: Dict[str, Array], q: Array, s: Array, eps: float = global_eps @@ -172,24 +245,14 @@ def forward_kinematics_fn( """ # map the configuration to the strains xi = xi_eq + B_xi @ q - # add a small number to the bending strain to avoid singularities xi_epsed = apply_eps_to_bend_strains(xi, eps) - # cumsum of the segment lengths - l_cum = jnp.cumsum(params["l"]) - # add zero to the beginning of the array - l_cum_padded = jnp.concatenate([jnp.array([0.0]), l_cum], axis=0) - # determine in which segment the point is located - # use argmax to find the last index where the condition is true - segment_idx = ( - l_cum.shape[0] - 1 - jnp.argmax((s >= l_cum_padded[:-1])[::-1]).astype(int) - ) - # point coordinate along the segment in the interval [0, l_segment] - s_segment = s - l_cum_padded[segment_idx] + # classify the point along the robot to the corresponding segment + segment_idx, s_segment = classify_segment(params, s) # convert the dictionary of parameters to a list, which we can pass to the lambda function - params_for_lambdify = select_params_for_lambdify(params) + params_for_lambdify = select_params_for_lambdify_fn(params) chi = lax.switch( segment_idx, chi_lambda_sms, *params_for_lambdify, *xi_epsed, s_segment @@ -197,6 +260,42 @@ def forward_kinematics_fn( return chi + @jit + def jacobian_fn( + params: Dict[str, Array], q: Array, s: Array, eps: float = global_eps + ) -> Array: + """ + Evaluate the forward kinematics the tip of the links + Args: + params: Dictionary of robot parameters + q: generalized coordinates of shape (n_q, ) + s: point coordinate along the rod in the interval [0, L]. + eps: small number to avoid singularities (e.g., division by zero) + Returns: + J: Jacobian matrix of shape (3, n_q) of the backbone point in Cartesian-space + Relates the configuration-space velocity q_d to the Cartesian-space velocity chi_d, + where chi_d = J @ q_d. Chi_d consists of [p_x_d, p_y_d, theta_d] + """ + # map the configuration to the strains + xi = xi_eq + B_xi @ q + # add a small number to the bending strain to avoid singularities + xi_epsed = apply_eps_to_bend_strains(xi, eps) + + # classify the point along the robot to the corresponding segment + segment_idx, s_segment = classify_segment(params, s) + + # convert the dictionary of parameters to a list, which we can pass to the lambda function + params_for_lambdify = select_params_for_lambdify_fn(params) + + J = lax.switch( + segment_idx, J_lambda_sms, *params_for_lambdify, *xi_epsed, s_segment + ).squeeze() + + # apply the strain basis to the Jacobian + J = J @ B_xi + + return J + @jit def dynamical_matrices_fn( params: Dict[str, Array], q: Array, q_d: Array, eps: float = 1e4 * global_eps @@ -223,23 +322,13 @@ def dynamical_matrices_fn( # add a small number to the bending strain to avoid singularities xi_epsed = apply_eps_to_bend_strains(xi, eps) - # cross-sectional area and second moment of area - A = jnp.pi * params["r"] ** 2 - Ib = A**2 / (4 * jnp.pi) - - # elastic and shear modulus - E, G = params["E"], params["G"] - - # stiffness matrix of shape (num_segments, 3, 3) - S = compute_stiffness_matrix_for_all_segments_fn(A, Ib, E, G) - - # we define the elastic matrix of shape (n_xi, n_xi) as K(xi) = K @ xi where K is equal to - K = blk_diag(S) + # compute the stiffness matrix + K = stiffness_fn(params, formulate_in_strain_space=True) # dissipative matrix from the parameters D = params.get("D", jnp.zeros((n_xi, n_xi))) - params_for_lambdify = select_params_for_lambdify(params) + params_for_lambdify = select_params_for_lambdify_fn(params) B = B_xi.T @ B_lambda(*params_for_lambdify, *xi_epsed) @ B_xi C_xi = C_lambda(*params_for_lambdify, *xi_epsed, *xi_d) @@ -254,7 +343,6 @@ def dynamical_matrices_fn( alpha = B_xi.T @ jnp.identity(n_xi) @ B_xi return B, C, G, K, D, alpha - def kinetic_energy_fn(params: Dict[str, Array], q: Array, q_d: Array) -> Array: """ @@ -270,11 +358,12 @@ def kinetic_energy_fn(params: Dict[str, Array], q: Array, q_d: Array) -> Array: # kinetic energy T = (0.5 * q_d.T @ B @ q_d).squeeze() - + return T - - def potential_energy_fn(params: Dict[str, Array], q: Array, eps: float = 1e4 * global_eps) -> Array: + def potential_energy_fn( + params: Dict[str, Array], q: Array, eps: float = 1e4 * global_eps + ) -> Array: """ Compute the potential energy of the system. Args: @@ -289,22 +378,14 @@ def potential_energy_fn(params: Dict[str, Array], q: Array, eps: float = 1e4 * g # add a small number to the bending strain to avoid singularities xi_epsed = apply_eps_to_bend_strains(xi, eps) - # cross-sectional area and second moment of area - A = jnp.pi * params["r"] ** 2 - Ib = A**2 / (4 * jnp.pi) - - # elastic and shear modulus - E, G = params["E"], params["G"] - # stiffness matrix of shape (num_segments, 3, 3) - S = compute_stiffness_matrix_for_all_segments_fn(A, Ib, E, G) - # we define the elastic matrix of shape (n_xi, n_xi) as K(xi) = K @ xi where K is equal to - K = blk_diag(S) + # compute the stiffness matrix + K = stiffness_fn(params, formulate_in_strain_space=True) # elastic energy U_K = (xi - xi_eq).T @ K @ (xi - xi_eq) # evaluate K(xi) = K @ xi # gravitational potential energy - params_for_lambdify = select_params_for_lambdify(params) - U_G = U_lambda(*params_for_lambdify, *xi_epsed) + params_for_lambdify = select_params_for_lambdify_fn(params) + U_G = U_g_lambda(*params_for_lambdify, *xi_epsed) # total potential energy U = (U_G + U_K).squeeze() @@ -327,11 +408,96 @@ def energy_fn(params: Dict[str, Array], q: Array, q_d: Array) -> Array: return E + def operational_space_dynamical_matrices_fn( + params: Dict[str, Array], + q: Array, + q_d: Array, + s: Array, + B: Array, + C: Array, + operational_space_selector: Tuple = (True, True, True), + eps: float = 1e4 * global_eps, + ) -> Tuple[Array, Array, Array, Array, Array]: + """ + Compute the dynamics in operational space. + The implementation is based on Chapter 7.8 of "Modelling, Planning and Control of Robotics" by + Siciliano, Sciavicco, Villani, Oriolo. + Args: + params: dictionary of parameters + q: generalized coordinates of shape (n_q,) + q_d: generalized velocities of shape (n_q,) + s: point coordinate along the robot in the interval [0, L]. + B: inertia matrix in the generalized coordinates of shape (n_q, n_q) + C: coriolis matrix derived with Christoffer symbols in the generalized coordinates of shape (n_q, n_q) + operational_space_selector: tuple of shape (3,) to select the operational space variables. + For examples, (True, True, False) selects only the positional components of the operational space. + eps: small number to avoid singularities (e.g., division by zero) + Returns: + Lambda: inertia matrix in the operational space of shape (3, 3) + mu: matrix with corioli and centrifugal terms in the operational space of shape (3, 3) + J: Jacobian of the Cartesian pose with respect to the generalized coordinates of shape (3, n_q) + J: time-derivative of the Jacobian of the end-effector pose with respect to the generalized coordinates + of shape (3, n_q) + JB_pinv: Dynamically-consistent pseudo-inverse of the Jacobian. Allows the mapping of torques + from the generalized coordinates to the operational space: f = JB_pinv.T @ tau_q + Shape (n_q, 3) + """ + ## map the configuration to the strains + xi = xi_eq + B_xi @ q + xi_d = B_xi @ q_d + # add a small number to the bending strain to avoid singularities + xi_epsed = apply_eps_to_bend_strains(xi, eps) + + # classify the point along the robot to the corresponding segment + segment_idx, s_segment = classify_segment(params, s) + + # convert the dictionary of parameters to a list, which we can pass to the lambda function + params_for_lambdify = select_params_for_lambdify_fn(params) + + # make operational_space_selector a boolean array + operational_space_selector = onp.array(operational_space_selector, dtype=bool) + + # Jacobian and its time-derivative + J = lax.switch( + segment_idx, J_lambda_sms, *params_for_lambdify, *xi_epsed, s_segment + ).squeeze() + J_d = lax.switch( + segment_idx, + J_d_lambda_sms, + *params_for_lambdify, + *xi_epsed, + *xi_d, + s_segment, + ).squeeze() + # apply the operational_space_selector and strain basis to the J and J_d + J = J[operational_space_selector, :] @ B_xi + J_d = J_d[operational_space_selector, :] @ B_xi + + # inverse of the inertia matrix in the configuration space + B_inv = jnp.linalg.inv(B) + + Lambda = jnp.linalg.inv( + J @ B_inv @ J.T + ) # inertia matrix in the operational space + mu = Lambda @ ( + J @ B_inv @ C - J_d + ) # coriolis and centrifugal matrix in the operational space + + JB_pinv = ( + B_inv @ J.T @ Lambda + ) # dynamically-consistent pseudo-inverse of the Jacobian + + return Lambda, mu, J, J_d, JB_pinv + auxiliary_fns = { "apply_eps_to_bend_strains": apply_eps_to_bend_strains, + "classify_segment": classify_segment, + "stiffness_fn": stiffness_fn, + "jacobian_fn": jacobian_fn, "kinetic_energy_fn": kinetic_energy_fn, "potential_energy_fn": potential_energy_fn, "energy_fn": energy_fn, + "operational_space_dynamical_matrices_fn": operational_space_dynamical_matrices_fn, } return B_xi, forward_kinematics_fn, dynamical_matrices_fn, auxiliary_fns diff --git a/src/jsrm/utils/numerical_jacobian.py b/src/jsrm/utils/numerical_jacobian.py index 5294c5a..56d34a9 100644 --- a/src/jsrm/utils/numerical_jacobian.py +++ b/src/jsrm/utils/numerical_jacobian.py @@ -1,5 +1,6 @@ """Routines for numerical differentiation.""" -__all__ = ['approx_derivative'] + +__all__ = ["approx_derivative"] import functools import jax.numpy as jnp @@ -35,9 +36,9 @@ def _adjust_scheme_to_bounds(x0, h, num_steps, scheme, lb, ub): Whether to switch to one-sided scheme. Informative only for ``scheme='2-sided'``. """ - if scheme == '1-sided': + if scheme == "1-sided": use_one_sided = jnp.ones_like(h, dtype=bool) - elif scheme == '2-sided': + elif scheme == "2-sided": h = jnp.abs(h) use_one_sided = jnp.zeros_like(h, dtype=bool) else: @@ -52,7 +53,7 @@ def _adjust_scheme_to_bounds(x0, h, num_steps, scheme, lb, ub): lower_dist = x0 - lb upper_dist = ub - x0 - if scheme == '1-sided': + if scheme == "1-sided": x = x0 + h_total violated = (x < lb) | (x > ub) fitting = jnp.abs(h_total) <= jnp.maximum(lower_dist, upper_dist) @@ -62,21 +63,23 @@ def _adjust_scheme_to_bounds(x0, h, num_steps, scheme, lb, ub): h_adjusted[forward] = upper_dist[forward] / num_steps backward = (upper_dist < lower_dist) & ~fitting h_adjusted[backward] = -lower_dist[backward] / num_steps - elif scheme == '2-sided': + elif scheme == "2-sided": central = (lower_dist >= h_total) & (upper_dist >= h_total) forward = (upper_dist >= lower_dist) & ~central h_adjusted[forward] = jnp.minimum( - h[forward], 0.5 * upper_dist[forward] / num_steps) + h[forward], 0.5 * upper_dist[forward] / num_steps + ) use_one_sided[forward] = True backward = (upper_dist < lower_dist) & ~central h_adjusted[backward] = -jnp.minimum( - h[backward], 0.5 * lower_dist[backward] / num_steps) + h[backward], 0.5 * lower_dist[backward] / num_steps + ) use_one_sided[backward] = True min_dist = jnp.minimum(upper_dist, lower_dist) / num_steps - adjusted_central = (~central & (jnp.abs(h_adjusted) <= min_dist)) + adjusted_central = ~central & (jnp.abs(h_adjusted) <= min_dist) h_adjusted[adjusted_central] = min_dist[adjusted_central] use_one_sided[adjusted_central] = False @@ -131,10 +134,11 @@ def _eps_for_method(x0_dtype, f0_dtype, method): if method in ["2-point"]: return EPS**0.5 elif method in ["3-point"]: - return EPS**(1/3) + return EPS ** (1 / 3) else: - raise RuntimeError("Unknown step method, should be one of " - "{'2-point', '3-point'}") + raise RuntimeError( + "Unknown step method, should be one of " "{'2-point', '3-point'}" + ) def _compute_absolute_step(rel_step, x0, f0, method): @@ -178,10 +182,10 @@ def _compute_absolute_step(rel_step, x0, f0, method): # however we don't want an abs_step of 0, which can happen if # rel_step is 0, or x0 is 0. Instead, substitute a realistic step - dx = ((x0 + abs_step) - x0) - abs_step = jnp.where(dx == 0, - rstep * sign_x0 * jnp.maximum(1.0, jnp.abs(x0)), - abs_step) + dx = (x0 + abs_step) - x0 + abs_step = jnp.where( + dx == 0, rstep * sign_x0 * jnp.maximum(1.0, jnp.abs(x0)), abs_step + ) return abs_step @@ -207,8 +211,17 @@ def _prepare_bounds(bounds, x0): return lb, ub -def approx_derivative(fun, x0, method='3-point', rel_step=None, abs_step=None, - f0=None, bounds=(-jnp.inf, jnp.inf), args=(), kwargs={}): +def approx_derivative( + fun, + x0, + method="3-point", + rel_step=None, + abs_step=None, + f0=None, + bounds=(-jnp.inf, jnp.inf), + args=(), + kwargs={}, +): """Compute finite difference approximation of the derivatives of a vector-valued function. @@ -327,7 +340,7 @@ def approx_derivative(fun, x0, method='3-point', rel_step=None, abs_step=None, >>> approx_derivative(g, x0, bounds=(1.0, jnp.inf)) array([ 2.]) """ - if method not in ['2-point', '3-point']: + if method not in ["2-point", "3-point"]: raise ValueError("Unknown method '%s'. " % method) if x0.ndim > 1: @@ -358,21 +371,22 @@ def fun_wrapped(x): # cannot have a zero step. This might happen if x0 is very large # or small. In which case fall back to relative step. - dx = ((x0 + h) - x0) - h = jnp.where(dx == 0, - _eps_for_method(x0.dtype, f0.dtype, method) * - sign_x0 * jnp.maximum(1.0, jnp.abs(x0)), - h) - - if method == '2-point': - h, use_one_sided = _adjust_scheme_to_bounds( - x0, h, 1, '1-sided', lb, ub) - elif method == '3-point': - h, use_one_sided = _adjust_scheme_to_bounds( - x0, h, 1, '2-sided', lb, ub) - - return _dense_difference(fun_wrapped, x0, f0, h, - use_one_sided, method) + dx = (x0 + h) - x0 + h = jnp.where( + dx == 0, + _eps_for_method(x0.dtype, f0.dtype, method) + * sign_x0 + * jnp.maximum(1.0, jnp.abs(x0)), + h, + ) + + if method == "2-point": + h, use_one_sided = _adjust_scheme_to_bounds(x0, h, 1, "1-sided", lb, ub) + elif method == "3-point": + h, use_one_sided = _adjust_scheme_to_bounds(x0, h, 1, "2-sided", lb, ub) + + return _dense_difference(fun_wrapped, x0, f0, h, use_one_sided, method) + def _dense_difference(fun, x0, f0, h, use_one_sided, method): m = f0.shape[-1] @@ -380,18 +394,20 @@ def _dense_difference(fun, x0, f0, h, use_one_sided, method): J_T_rows = [] for i in range(h.size): - if method == '2-point': + if method == "2-point": x1 = x0 + jnp.concat( [ - jnp.zeros((i, ), ), - h[i: i + 1], - jnp.zeros((n - i - 1, )), + jnp.zeros( + (i,), + ), + h[i : i + 1], + jnp.zeros((n - i - 1,)), ], axis=-1, ) dx = h[i] df = fun(x1) - f0 - elif method == '3-point' and use_one_sided[i]: + elif method == "3-point" and use_one_sided[i]: x1[i] += h[i] x2[i] += 2 * h[i] dx = x2[i] - x0[i] @@ -402,7 +418,7 @@ def _dense_difference(fun, x0, f0, h, use_one_sided, method): dx01 = jnp.concat( [ jnp.zeros((i,)), - h[i: i + 1], + h[i : i + 1], jnp.zeros((n - i - 1,)), ], axis=-1, @@ -413,12 +429,12 @@ def _dense_difference(fun, x0, f0, h, use_one_sided, method): f1 = fun(x1) f2 = fun(x2) df = -3.0 * f0 + 4 * f1 - f2 - elif method == '3-point' and not use_one_sided[i]: + elif method == "3-point" and not use_one_sided[i]: dx02 = jnp.concat( [ - jnp.zeros((i, )), - h[i: i + 1], - jnp.zeros((n - i - 1, )), + jnp.zeros((i,)), + h[i : i + 1], + jnp.zeros((n - i - 1,)), ], axis=-1, ) diff --git a/tests/test_numerical_jacobian.py b/tests/test_numerical_jacobian.py index 9f8b4bd..42332d4 100644 --- a/tests/test_numerical_jacobian.py +++ b/tests/test_numerical_jacobian.py @@ -7,7 +7,7 @@ from jsrm.utils.numerical_jacobian import approx_derivative -def test_finite_differences(method = "2-point"): +def test_finite_differences(method="2-point"): def fun(x: Array): return jnp.stack([x[0] * jnp.sin(x[1]), x[0] * jnp.cos(x[1])]) @@ -21,7 +21,14 @@ def fun(x: Array): jac_autodiff = jac_autodiff_fn(x) jac_numdiff = jac_numdiff_fn(x) - print("x = ", x, "\njac_autodiff = \n", jac_autodiff, "\njac_numdiff = \n", jac_numdiff) + print( + "x = ", + x, + "\njac_autodiff = \n", + jac_autodiff, + "\njac_numdiff = \n", + jac_numdiff, + ) error_jac = jnp.linalg.norm(jac_autodiff - jac_numdiff) print("error_jac = ", error_jac) diff --git a/tests/test_planar_pcs.py b/tests/test_planar_pcs.py index 80de54b..9bec6eb 100644 --- a/tests/test_planar_pcs.py +++ b/tests/test_planar_pcs.py @@ -27,8 +27,8 @@ def test_planar_pcs_one_segment(): # activate all strains (i.e. bending, shear, and axial) strain_selector = jnp.ones((3,), dtype=bool) - strain_basis, forward_kinematics_fn, dynamical_matrices_fn, auxiliary_fns = planar_pcs.factory( - sym_exp_filepath, strain_selector + strain_basis, forward_kinematics_fn, dynamical_matrices_fn, auxiliary_fns = ( + planar_pcs.factory(sym_exp_filepath, strain_selector) ) forward_dynamics_fn = partial( euler_lagrangian.forward_dynamics, dynamical_matrices_fn