Skip to content

Commit

Permalink
Continue implementing actuation_mapping_fn
Browse files Browse the repository at this point in the history
  • Loading branch information
mstoelzle committed Nov 19, 2024
1 parent ae1b67d commit 4d42ffd
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 4 deletions.
6 changes: 5 additions & 1 deletion src/jsrm/systems/planar_pcs.py
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,8 @@ def stiffness_fn(

if actuation_mapping_fn is None:
def actuation_mapping_fn(
forward_kinematics_fn: Callable,
jacobian_fn: Callable,
params: Dict[str, Array],
B_xi: Array,
q: Array,
Expand All @@ -246,6 +248,8 @@ def actuation_mapping_fn(
Returns the actuation matrix that maps the actuation space to the configuration space.
Assumes the fully actuated and identity actuation matrix.
Args:
forward_kinematics_fn: function to compute the forward kinematics
jacobian_fn: function to compute the Jacobian
params: dictionary with robot parameters
B_xi: strain basis matrix
q: configuration of the robot
Expand Down Expand Up @@ -355,7 +359,7 @@ def dynamical_matrices_fn(
# compute the stiffness matrix
K = stiffness_fn(params, B_xi, formulate_in_strain_space=True)
# compute the actuation matrix
A = actuation_mapping_fn(params, B_xi, q)
A = actuation_mapping_fn(forward_kinematics_fn, actuation_mapping_fn, params, B_xi, q)

# dissipative matrix from the parameters
D = params.get("D", jnp.zeros((n_xi, n_xi)))
Expand Down
34 changes: 31 additions & 3 deletions src/jsrm/systems/pneumatic_planar_pcs.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import jax.numpy as jnp
from jsrm.math_utils import blk_diag
import numpy as onp
from typing import Dict, Optional, Tuple, Union
from typing import Callable, Dict, Optional, Tuple, Union

from .planar_pcs import factory as planar_pcs_factory

Expand Down Expand Up @@ -37,13 +37,17 @@ def factory(
actuation_basis = actuation_basis.at[2 * i + 1, j + 1].set(1.0)

def actuation_mapping_fn(
forward_kinematics_fn: Callable,
jacobian_fn: Callable,
params: Dict[str, Array],
B_xi: Array,
q: Array,
) -> Array:
"""
Returns the actuation matrix that maps the actuation space to the configuration space.
Args:
forward_kinematics_fn: function to compute the forward kinematics
jacobian_fn: function to compute the Jacobian
params: dictionary with robot parameters
B_xi: strain basis matrix
q: configuration of the robot
Expand All @@ -57,8 +61,32 @@ def actuation_mapping_fn(
# number of strains
n_xi = xi.shape[0]

for i in range(num_segments):
pass
# all segment bases and tips
sms = jnp.concat([jnp.zeros((1,)), jnp.cumsum(params["l"])], axis=0)
print("sms =\n", sms)

# compute the poses of all segment tips
chi_sms = vmap(forward_kinematics_fn, in_axes=(None, None, 0))(params, q, sms)

# compute the Jacobian for all segment tips
J_sms = vmap(jacobian_fn, in_axes=(None, None, 0))(params, q, sms)

def compute_actuation_matrix_for_segment(
chi_sm: Array, J_sm: Array, xi: Array
) -> Array:
"""
Compute the actuation matrix for a single segment.
Args:
chi_sm: tip position of the segment
J_sm: Jacobian of the segment
xi: strains of the segment
Returns:
A_sm: actuation matrix of shape (n_xi, 2)
"""
# compute the actuation matrix for a single segment
A_sm = jnp.zeros((n_xi, 2))
return A_sm


A = jnp.zeros((n_xi, 2 * num_segments))

Expand Down

0 comments on commit 4d42ffd

Please sign in to comment.