Skip to content

Commit

Permalink
Increase eps in operational space dynamics
Browse files Browse the repository at this point in the history
  • Loading branch information
mstoelzle committed Oct 28, 2023
1 parent 37eb694 commit 77ef846
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions src/jsrm/systems/planar_hsa.py
Original file line number Diff line number Diff line change
Expand Up @@ -595,7 +595,7 @@ def operational_space_dynamical_matrices_fn(
xi = configuration_to_strains_fn(params, 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_fn(xi, eps)
xi_epsed = apply_eps_to_bend_strains_fn(xi, 1e4*eps)

# 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)
Expand All @@ -610,7 +610,7 @@ def operational_space_dynamical_matrices_fn(
Lambda = jnp.linalg.inv(Jee @ B_inv @ Jee.T) # inertia matrix in the operational space
mu = Lambda @ (Jee @ B_inv @ C - Jee_d) # coriolis and centrifugal matrix in the operational space

JeeB_pinv = B_inv @ Jee.T @ Lambda
JeeB_pinv = B_inv @ Jee.T @ Lambda # dynamically-consistent pseudo-inverse of the Jacobian

return Lambda, mu, Jee, Jee_d, JeeB_pinv

Expand Down

0 comments on commit 77ef846

Please sign in to comment.