58
58
auxiliary_fns ["jacobian_fn" ],
59
59
)
60
60
61
+ def sweep_local_tip_force_to_bending_torque_mapping ():
62
+ def compute_bending_torque (q : Array ) -> Array :
63
+ # backbone coordinate of the end-effector
64
+ s_ee = jnp .sum (params ["l" ])
65
+ # compute the pose of the end-effector
66
+ chi_ee = forward_kinematics_fn (params , q , s_ee )
67
+ # orientation of the end-effector
68
+ th_ee = chi_ee [2 ]
69
+ # compute the jacobian of the end-effector
70
+ J_ee = auxiliary_fns ["jacobian_fn" ](params , q , s_ee )
71
+ # local tip force
72
+ f_ee_local = jnp .array ([0.0 , 1.0 ])
73
+ # tip force in inertial frame
74
+ f_ee = jnp .array ([[jnp .cos (th_ee ), - jnp .sin (th_ee )], [jnp .sin (th_ee ), jnp .cos (th_ee )]]) @ f_ee_local
75
+ # compute the generalized torque
76
+ tau_be = J_ee [:2 , 0 ].T @ f_ee
77
+ return tau_be
78
+
79
+ kappa_be_pts = jnp .arange (- 2 * jnp .pi , 2 * jnp .pi , 0.01 )
80
+ sigma_ax_pts = jnp .zeros_like (kappa_be_pts )
81
+ q_pts = jnp .stack ([kappa_be_pts , sigma_ax_pts ], axis = - 1 )
82
+
83
+ tau_be_pts = vmap (compute_bending_torque )(q_pts )
84
+
85
+ # plot the mapping on the bending strain
86
+ fig , ax = plt .subplots (num = "planar_pcs_local_tip_force_to_bending_torque_mapping" )
87
+ plt .title (r"Mapping from $f_\mathrm{ee}$ to $\tau_\mathrm{be}$" )
88
+ ax .plot (kappa_be_pts , tau_be_pts , linewidth = 2.5 )
89
+ ax .set_xlabel (r"$\kappa_\mathrm{be}$ [rad/m]" )
90
+ ax .set_ylabel (r"$\tau_\mathrm{be}$ [N m]" )
91
+ plt .grid (True )
92
+ plt .tight_layout ()
93
+ plt .show ()
94
+
95
+
61
96
def sweep_actuation_mapping ():
62
97
# evaluate the actuation matrix for a straight backbone
63
98
q = jnp .zeros ((2 * num_segments ,))
@@ -70,12 +105,14 @@ def sweep_actuation_mapping():
70
105
A_pts = vmap (actuation_mapping_fn , in_axes = (None , None , 0 ))(params , B_xi , q_pts )
71
106
# plot the mapping on the bending strain for various bending strains
72
107
fig , ax = plt .subplots (num = "pneumatic_planar_pcs_actuation_mapping_bending_torque_vs_bending_strain" )
73
- plt .title (r"Actuation mapping from $u_1$ to $\tau_\mathrm{be}$" )
74
- ax .plot (kappa_be_pts , A_pts [:, 0 , 0 ], linewidth = 2 )
108
+ plt .title (r"Actuation mapping from $u$ to $\tau_\mathrm{be}$" )
75
109
# shade the region where the actuation mapping is negative as we are not able to bend the robot further
76
- ax .axhspan (A_pts [:, 0 , 0 ].min (), 0.0 , facecolor = 'red' , alpha = 0.5 )
110
+ ax .axhspan (A_pts [:, 0 , 0 :2 ].min (), 0.0 , facecolor = 'red' , alpha = 0.2 )
111
+ ax .plot (kappa_be_pts , A_pts [:, 0 , 0 ], linewidth = 2 , label = r"$\frac{\partial \tau_\mathrm{be}}{\partial u_1}$" )
112
+ ax .plot (kappa_be_pts , A_pts [:, 0 , 1 ], linewidth = 2 , label = r"$\frac{\partial \tau_\mathrm{ax}}{\partial u_2}$" )
77
113
ax .set_xlabel (r"$\kappa_\mathrm{be}$ [rad/m]" )
78
114
ax .set_ylabel (r"$\frac{\partial \tau_\mathrm{be}}{\partial u_1}$" )
115
+ plt .legend ()
79
116
plt .grid (True )
80
117
plt .tight_layout ()
81
118
plt .show ()
@@ -225,5 +262,6 @@ def simulate_robot():
225
262
plt .show ()
226
263
227
264
if __name__ == "__main__" :
265
+ sweep_local_tip_force_to_bending_torque_mapping ()
228
266
sweep_actuation_mapping ()
229
267
simulate_robot ()
0 commit comments