Skip to content

Commit b094c37

Browse files
committed
._dot .dot ._d changed to .d
1 parent 7f27d15 commit b094c37

14 files changed

+162
-1756
lines changed

examples/benchmark_planar_pcs.py

Lines changed: 0 additions & 1594 deletions
This file was deleted.

examples/demo_planar_hsa_motor2ee_jacobian.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,8 @@ def factory_fn(
5252
jacobian_end_effector_fn = jit(partial(jacobian_end_effector_fn, params))
5353

5454
def residual_fn(q: Array, phi: Array) -> Array:
55-
q_d = jnp.zeros_like(q)
56-
_, _, G, K, _, alpha = dynamical_matrices_fn(q, q_d, phi=phi)
55+
qd = jnp.zeros_like(q)
56+
_, _, G, K, _, alpha = dynamical_matrices_fn(q, qd, phi=phi)
5757
res = alpha - G - K
5858
return jnp.square(res).mean()
5959

examples/simulate_planar_pcs.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -191,7 +191,7 @@ def update_plot(frame_idx):
191191
# Solver
192192
solver = Tsit5() # Runge-Kutta 5(4) method
193193

194-
ts, q_ts, q_d_ts = robot.resolve_upon_time(
194+
ts, q_ts, qd_ts = robot.resolve_upon_time(
195195
q0=q0,
196196
qd0=qd0,
197197
actuation_args=actuation_args,
@@ -239,7 +239,7 @@ def update_plot(frame_idx):
239239
# Energy computation upon time
240240
# =====================================================
241241
U_ts = jax.vmap(jax.jit(partial(robot.potential_energy)))(q_ts)
242-
T_ts = jax.vmap(jax.jit(partial(robot.kinetic_energy)))(q_ts, q_d_ts)
242+
T_ts = jax.vmap(jax.jit(partial(robot.kinetic_energy)))(q_ts, qd_ts)
243243

244244
plt.figure()
245245
plt.plot(ts, U_ts, label="Potential Energy")

examples/simulate_tendon_actuated_planar_pcs.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -148,7 +148,7 @@ def draw_robot(
148148
# the evolution of the generalized coordinates
149149
q_ts = sol.ys[:, :n_q]
150150
# the evolution of the generalized velocities
151-
q_d_ts = sol.ys[:, n_q:]
151+
qd_ts = sol.ys[:, n_q:]
152152

153153
# evaluate the forward kinematics along the trajectory
154154
chi_ee_ts = vmap(forward_kinematics_fn, in_axes=(None, 0, None))(
@@ -213,7 +213,7 @@ def draw_robot(
213213
partial(auxiliary_fns["potential_energy_fn"], params)
214214
)
215215
U_ts = potential_energy_fn_vmapped(q_ts)
216-
T_ts = kinetic_energy_fn_vmapped(q_ts, q_d_ts)
216+
T_ts = kinetic_energy_fn_vmapped(q_ts, qd_ts)
217217
plt.figure()
218218
plt.plot(video_ts, U_ts, label="Potential energy")
219219
plt.plot(video_ts, T_ts, label="Kinetic energy")

src/jsrm/integration.py

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -8,12 +8,12 @@ def ode_factory(
88
dynamical_matrices_fn: Callable, params: Dict[str, Array], tau: Array
99
) -> Callable[[float, Array], Array]:
1010
"""
11-
Make an ODE function of the form ode_fn(t, x) -> x_dot.
11+
Make an ODE function of the form ode_fn(t, x) -> xd.
1212
This function assumes a constant torque input (i.e. zero-order hold).
1313
Args:
1414
dynamical_matrices_fn: Callable that returns the B, C, G, K, D, and A matrices. Needs to conform to the signature:
15-
dynamical_matrices_fn(params, q, q_d) -> Tuple[B, C, G, K, D, A]
16-
where q and q_d are the configuration and velocity vectors, respectively,
15+
dynamical_matrices_fn(params, q, qd) -> Tuple[B, C, G, K, D, A]
16+
where q and qd are the configuration and velocity vectors, respectively,
1717
B is the inertia matrix of shape (n_q, n_q),
1818
C is the Coriolis matrix of shape (n_q, n_q),
1919
G is the gravity vector of shape (n_q, ),
@@ -23,7 +23,7 @@ def ode_factory(
2323
params: Dictionary with robot parameters
2424
tau: torque vector of shape (n_tau, )
2525
Returns:
26-
ode_fn: ODE function of the form ode_fn(t, x) -> x_dot
26+
ode_fn: ODE function of the form ode_fn(t, x) -> xd
2727
"""
2828

2929
def ode_fn(t: float, x: Array, *args) -> Array:
@@ -34,15 +34,15 @@ def ode_fn(t: float, x: Array, *args) -> Array:
3434
x: state vector of shape (2 * n_q, )
3535
args: additional arguments
3636
Returns:
37-
x_d: time-derivative of the state vector of shape (2 * n_q, )
37+
xd: time-derivative of the state vector of shape (2 * n_q, )
3838
"""
39-
x_d = euler_lagrangian.nonlinear_state_space(
39+
xd = euler_lagrangian.nonlinear_state_space(
4040
dynamical_matrices_fn,
4141
params,
4242
x,
4343
tau,
4444
)
45-
return x_d
45+
return xd
4646

4747
return ode_fn
4848

@@ -51,12 +51,12 @@ def ode_with_forcing_factory(
5151
dynamical_matrices_fn: Callable, params: Dict[str, Array]
5252
) -> Callable[[float, Array], Array]:
5353
"""
54-
Make an ODE function of the form ode_fn(t, x) -> x_dot.
54+
Make an ODE function of the form ode_fn(t, x) -> xd.
5555
This function assumes a constant torque input (i.e. zero-order hold).
5656
Args:
5757
dynamical_matrices_fn: Callable that returns the B, C, G, K, D, and A matrices. Needs to conform to the signature:
58-
dynamical_matrices_fn(params, q, q_d) -> Tuple[B, C, G, K, D, A]
59-
where q and q_d are the configuration and velocity vectors, respectively,
58+
dynamical_matrices_fn(params, q, qd) -> Tuple[B, C, G, K, D, A]
59+
where q and qd are the configuration and velocity vectors, respectively,
6060
B is the inertia matrix of shape (n_q, n_q),
6161
C is the Coriolis matrix of shape (n_q, n_q),
6262
G is the gravity vector of shape (n_q, ),
@@ -65,7 +65,7 @@ def ode_with_forcing_factory(
6565
A is the actuation matrix of shape (n_q, n_tau).
6666
params: Dictionary with robot parameters
6767
Returns:
68-
ode_fn: ODE function of the form ode_fn(t, x, tau) -> x_dot
68+
ode_fn: ODE function of the form ode_fn(t, x, tau) -> xd
6969
"""
7070

7171
def ode_fn(
@@ -80,14 +80,14 @@ def ode_fn(
8080
x: state vector of shape (2 * n_q, )
8181
tau: external torque vector of shape (n_tau, )
8282
Returns:
83-
x_d: time-derivative of the state vector of shape (2 * n_q, )
83+
xd: time-derivative of the state vector of shape (2 * n_q, )
8484
"""
85-
x_d = euler_lagrangian.nonlinear_state_space(
85+
xd = euler_lagrangian.nonlinear_state_space(
8686
dynamical_matrices_fn,
8787
params,
8888
x,
8989
tau,
9090
)
91-
return x_d
91+
return xd
9292

9393
return ode_fn

src/jsrm/symbolic_derivation/pendulum.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ def symbolically_derive_pendulum_model(
3131

3232
# configuration variables and their derivatives
3333
q_syms = list(sp.symbols(f"q1:{num_links + 1}")) # joint angle
34-
q_d_syms = list(sp.symbols(f"q_d1:{num_links + 1}")) # joint velocity
34+
qd_syms = list(sp.symbols(f"qd1:{num_links + 1}")) # joint velocity
3535

3636
# construct the symbolic matrices
3737
m = sp.Matrix(m_syms) # mass of each link
@@ -42,7 +42,7 @@ def symbolically_derive_pendulum_model(
4242

4343
# configuration variables and their derivatives
4444
q = sp.Matrix(q_syms) # joint angle
45-
q_d = sp.Matrix(q_d_syms) # joint velocity
45+
qd = sp.Matrix(qd_syms) # joint velocity
4646

4747
# matrix with tip of link and center of mass positions
4848
chi_ls, chic_ls = [], []
@@ -113,7 +113,7 @@ def symbolically_derive_pendulum_model(
113113
B = sp.simplify(B)
114114
print("B =\n", B)
115115

116-
C = compute_coriolis_matrix(B, q, q_d)
116+
C = compute_coriolis_matrix(B, q, qd)
117117
print("C =\n", C)
118118

119119
# compute the gravity force vector
@@ -131,7 +131,7 @@ def symbolically_derive_pendulum_model(
131131
},
132132
"state_syms": {
133133
"q": q_syms,
134-
"q_d": q_d_syms,
134+
"qd": qd_syms,
135135
},
136136
"exps": {
137137
"chi_ls": chi_ls, # matrix with tip poses of shape (3, n_q)

src/jsrm/symbolic_derivation/planar_hsa.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -134,8 +134,8 @@ def symbolically_derive_planar_hsa_model(
134134

135135
# planar strains and their derivatives
136136
xi_syms = list(sp.symbols(f"xi1:{num_dof + 1}", nonzero=True)) # strains
137-
xi_d_syms = list(sp.symbols(f"xi_d1:{num_dof + 1}")) # strain time derivatives
138-
xi_dd_syms = list(sp.symbols(f"xi_dd1:{num_dof + 1}")) # strain accelerations
137+
xid_syms = list(sp.symbols(f"xid1:{num_dof + 1}")) # strain time derivatives
138+
xidd_syms = list(sp.symbols(f"xidd1:{num_dof + 1}")) # strain accelerations
139139
phi_syms = list(
140140
sp.symbols(f"phi1:{num_segments * num_rods_per_segment + 1}")
141141
) # twist angles
@@ -198,8 +198,8 @@ def symbolically_derive_planar_hsa_model(
198198

199199
# configuration variables and their derivatives
200200
xi = sp.Matrix(xi_syms) # strains
201-
xi_d = sp.Matrix(xi_d_syms) # strain time derivatives
202-
xi_dd = sp.Matrix(xi_dd_syms) # strain accelerations
201+
xid = sp.Matrix(xid_syms) # strain time derivatives
202+
xidd = sp.Matrix(xidd_syms) # strain accelerations
203203
# twist angle of rods
204204
phi = sp.Matrix(phi_syms)
205205

@@ -493,8 +493,8 @@ def symbolically_derive_planar_hsa_model(
493493
print("chiee =\n", chiee)
494494
Jee = chiee.jacobian(xi) # Jacobian of the end-effector
495495
print("Jee =\n", Jee)
496-
Jee_d = compute_dAdt(Jee, xi, xi_d) # time derivative of the end-effector Jacobian
497-
print("Jee_d =\n", Jee_d)
496+
Jeed = compute_dAdt(Jee, xi, xid) # time derivative of the end-effector Jacobian
497+
print("Jeed =\n", Jeed)
498498

499499
# add contribution of the payload mass
500500
# the center of gravity of the payload mass should be specified relative to the end effector position
@@ -515,7 +515,7 @@ def symbolically_derive_planar_hsa_model(
515515
B = sp.simplify(B)
516516
print("B =\n", B)
517517

518-
C = compute_coriolis_matrix(B, xi, xi_d, simplify=simplify)
518+
C = compute_coriolis_matrix(B, xi, xid, simplify=simplify)
519519
print("C =\n", C)
520520

521521
# compute the gravity force vector
@@ -569,8 +569,8 @@ def symbolically_derive_planar_hsa_model(
569569
},
570570
"state_syms": {
571571
"xi": xi_syms,
572-
"xi_d": xi_d_syms,
573-
"xi_dd": xi_dd_syms,
572+
"xid": xid_syms,
573+
"xidd": xidd_syms,
574574
"phi": phi_syms,
575575
"s": s,
576576
},
@@ -587,7 +587,7 @@ def symbolically_derive_planar_hsa_model(
587587
"Jr_sms": Jr_sms, # list of the Jacobians of the centerline of each rod
588588
"Jp_sms": Jp_sms, # list of the platform Jacobians
589589
"Jee": Jee, # Jacobian of the end-effector
590-
"Jee_d": Jee_d, # time derivative of the Jacobian of the end-effector
590+
"Jeed": Jeed, # time derivative of the Jacobian of the end-effector
591591
"B": B,
592592
"C": C,
593593
"G": G,

src/jsrm/symbolic_derivation/planar_pcs.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ def symbolically_derive_planar_pcs_model(
4444

4545
# planar strains and their derivatives
4646
xi_syms = list(sp.symbols(f"xi1:{num_dof + 1}", nonzero=True)) # strains
47-
xi_d_syms = list(sp.symbols(f"xi_d1:{num_dof + 1}")) # strain time derivatives
47+
xid_syms = list(sp.symbols(f"xid1:{num_dof + 1}")) # strain time derivatives
4848

4949
# construct the symbolic matrices
5050
rho = sp.Matrix(rho_syms) # volumetric mass density [kg/m^3]
@@ -54,12 +54,12 @@ def symbolically_derive_planar_pcs_model(
5454

5555
# configuration variables and their derivatives
5656
xi = sp.Matrix(xi_syms) # strains
57-
xi_d = sp.Matrix(xi_d_syms) # strain time derivatives
57+
xid = sp.Matrix(xid_syms) # strain time derivatives
5858

5959
# matrix with symbolic expressions to derive the poses along each segment
6060
chi_sms = []
6161
# Jacobians (positional + orientation) in each segment as a function of the point coordinate s and its time derivative
62-
J_sms, J_d_sms = [], []
62+
J_sms, Jd_sms = [], []
6363
# tendon lengths for each segment as a function of the point coordinate s
6464
L_tend_sms = []
6565
# tendon length jacobians for each segment as a function of the point coordinate s
@@ -127,8 +127,8 @@ def symbolically_derive_planar_pcs_model(
127127
J_sms.append(J)
128128

129129
# compute the time derivative of the Jacobian
130-
J_d = compute_dAdt(J, xi, xi_d) # time derivative of the end-effector Jacobian
131-
J_d_sms.append(J_d)
130+
Jd = compute_dAdt(J, xi, xid) # time derivative of the end-effector Jacobian
131+
Jd_sms.append(Jd)
132132

133133
# derivative of mass matrix with respect to the point coordinate s
134134
dB_ds = rho[i] * A[i] * Jp.T @ Jp + rho[i] * I[i] * Jo.T @ Jo
@@ -175,7 +175,7 @@ def symbolically_derive_planar_pcs_model(
175175
B = sp.simplify(B)
176176
print("B =\n", B)
177177

178-
C = compute_coriolis_matrix(B, xi, xi_d, simplify=simplify_expressions)
178+
C = compute_coriolis_matrix(B, xi, xid, simplify=simplify_expressions)
179179
print("C =\n", C)
180180

181181
# compute the gravity force vector
@@ -195,7 +195,7 @@ def symbolically_derive_planar_pcs_model(
195195
},
196196
"state_syms": {
197197
"xi": xi_syms,
198-
"xi_d": xi_d_syms,
198+
"xid": xid_syms,
199199
"s": s,
200200
},
201201
"exps": {
@@ -207,8 +207,8 @@ def symbolically_derive_planar_pcs_model(
207207
"Jee": J_sms[-1].subs(
208208
s, l[-1]
209209
), # end-effector Jacobian of shape (3, num_dof)
210-
"J_d_sms": J_d_sms, # list of time derivatives of Jacobians (for each segment)
211-
"Jee_d": J_d_sms[-1].subs(
210+
"Jd_sms": Jd_sms, # list of time derivatives of Jacobians (for each segment)
211+
"Jeed": Jd_sms[-1].subs(
212212
s, l[-1]
213213
), # time derivative of end-effector Jacobian of shape (3, num_dof)
214214
"B": B, # mass matrix

src/jsrm/symbolic_derivation/symbolic_utils.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,14 +2,14 @@
22

33

44
def compute_coriolis_matrix(
5-
B: sp.Matrix, q: sp.Matrix, q_d: sp.Matrix, simplify: bool = True
5+
B: sp.Matrix, q: sp.Matrix, qd: sp.Matrix, simplify: bool = True
66
) -> sp.Matrix:
77
"""
8-
Compute the matrix C(q, q_d) containing the coriolis and centrifugal terms using Christoffel symbols.
8+
Compute the matrix C(q, qd) containing the coriolis and centrifugal terms using Christoffel symbols.
99
Args:
1010
B: mass / inertial matrix of shape (num_dof, num_dof)
1111
q: vector of generalized coordinates of shape (num_dof,)
12-
q_d: vector of generalized velocities of shape (num_dof,)
12+
qd: vector of generalized velocities of shape (num_dof,)
1313
simplify: whether to simplify the result
1414
Returns:
1515
C: matrix of shape (num_dof, num_dof) containing the coriolis and centrifugal terms
@@ -36,18 +36,18 @@ def compute_coriolis_matrix(
3636
for i in range(num_dof):
3737
for j in range(num_dof):
3838
for k in range(num_dof):
39-
C[i, j] = C[i, j] + Ch[i, j, k] * q_d[k]
39+
C[i, j] = C[i, j] + Ch[i, j, k] * qd[k]
4040
if simplify:
4141
# simplify coriolis and centrifugal force matrix
4242
C = sp.simplify(C)
4343

4444
return C
4545

4646

47-
def compute_dAdt(A: sp.Matrix, x: sp.Matrix, xdot: sp.Matrix) -> sp.Matrix:
47+
def compute_dAdt(A: sp.Matrix, x: sp.Matrix, xd: sp.Matrix) -> sp.Matrix:
4848
dAdt = sp.zeros(A.shape[0], A.shape[1])
4949
for j in range(A.shape[1]):
5050
# iterate through columns
51-
dAdt[:, j] = A[:, j].jacobian(x) @ xdot
51+
dAdt[:, j] = A[:, j].jacobian(x) @ xd
5252

5353
return dAdt

0 commit comments

Comments
 (0)