Skip to content

Commit 56d4e83

Browse files
committed
Jupyter notebook to derive Jacobaians of rotational transforms
1 parent 0c9bd07 commit 56d4e83

File tree

1 file changed

+381
-0
lines changed

1 file changed

+381
-0
lines changed

symbolic/rotation-derivative.ipynb

Lines changed: 381 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,381 @@
1+
{
2+
"cells": [
3+
{
4+
"cell_type": "markdown",
5+
"metadata": {},
6+
"source": [
7+
"# Determine derivatives of angular sequence to rotation matrix\n",
8+
"\n",
9+
"SymPy code to evaluate the mappings from rotation angle sequences to rotation matrix, then compute the derivatives to determine the mapping from angular rates to angular velocity.\n",
10+
"\n",
11+
"Adjust the next cell to choose the particular angle sequence."
12+
]
13+
},
14+
{
15+
"cell_type": "code",
16+
"execution_count": 225,
17+
"metadata": {},
18+
"outputs": [],
19+
"source": [
20+
"angle_names = ('alpha', 'beta', 'gamma')\n",
21+
"func = eul2r\n",
22+
"\n",
23+
"#angle_names = ('phi', 'theta', 'psi')\n",
24+
"#func = lambda Gamma: rpy2r(Gamma, order='xyz')"
25+
]
26+
},
27+
{
28+
"cell_type": "code",
29+
"execution_count": 226,
30+
"metadata": {},
31+
"outputs": [],
32+
"source": [
33+
"from spatialmath.base import *\n",
34+
"from sympy import *"
35+
]
36+
},
37+
{
38+
"cell_type": "markdown",
39+
"metadata": {},
40+
"source": [
41+
"Define a symbol for time"
42+
]
43+
},
44+
{
45+
"cell_type": "code",
46+
"execution_count": 227,
47+
"metadata": {},
48+
"outputs": [],
49+
"source": [
50+
"t = symbols('t')"
51+
]
52+
},
53+
{
54+
"cell_type": "markdown",
55+
"metadata": {},
56+
"source": [
57+
"Define arrays of symbols for the angles, angle as function of time, time derivative of angle as a function of time"
58+
]
59+
},
60+
{
61+
"cell_type": "code",
62+
"execution_count": 228,
63+
"metadata": {},
64+
"outputs": [],
65+
"source": [
66+
"angle = [] # names of angles, eg. theta\n",
67+
"anglet = [] # angles as function of time, eg. theta(t)\n",
68+
"angled = [] # derivative of above, eg. d theta(t) / dt\n",
69+
"angledn = [] # symbol to represent above, eg. theta_dot\n",
70+
"for i in angle_names:\n",
71+
" angle.append(symbols(i))\n",
72+
" anglet.append(Function(i)(t))\n",
73+
" angled.append(anglet[-1].diff(t))\n",
74+
" angledn.append(i + '_dot')"
75+
]
76+
},
77+
{
78+
"cell_type": "markdown",
79+
"metadata": {},
80+
"source": [
81+
"Compute the rotation matrix"
82+
]
83+
},
84+
{
85+
"cell_type": "code",
86+
"execution_count": 229,
87+
"metadata": {},
88+
"outputs": [
89+
{
90+
"data": {
91+
"text/latex": [
92+
"$\\displaystyle \\left[\\begin{matrix}- \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} + \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} & - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} - \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} & \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)}\\\\\\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} + \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} & - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} + \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} & \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\beta{\\left(t \\right)} \\right)}\\\\- \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} & \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} & \\cos{\\left(\\beta{\\left(t \\right)} \\right)}\\end{matrix}\\right]$"
93+
],
94+
"text/plain": [
95+
"Matrix([\n",
96+
"[-sin(alpha(t))*sin(gamma(t)) + cos(alpha(t))*cos(beta(t))*cos(gamma(t)), -sin(alpha(t))*cos(gamma(t)) - sin(gamma(t))*cos(alpha(t))*cos(beta(t)), sin(beta(t))*cos(alpha(t))],\n",
97+
"[ sin(alpha(t))*cos(beta(t))*cos(gamma(t)) + sin(gamma(t))*cos(alpha(t)), -sin(alpha(t))*sin(gamma(t))*cos(beta(t)) + cos(alpha(t))*cos(gamma(t)), sin(alpha(t))*sin(beta(t))],\n",
98+
"[ -sin(beta(t))*cos(gamma(t)), sin(beta(t))*sin(gamma(t)), cos(beta(t))]])"
99+
]
100+
},
101+
"execution_count": 229,
102+
"metadata": {},
103+
"output_type": "execute_result"
104+
}
105+
],
106+
"source": [
107+
"R = Matrix(func(anglet))\n",
108+
"R"
109+
]
110+
},
111+
{
112+
"cell_type": "markdown",
113+
"metadata": {},
114+
"source": [
115+
"Compute its time derivative"
116+
]
117+
},
118+
{
119+
"cell_type": "code",
120+
"execution_count": 230,
121+
"metadata": {},
122+
"outputs": [
123+
{
124+
"data": {
125+
"text/latex": [
126+
"$\\displaystyle \\left[\\begin{matrix}- \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} - \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)} - \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} - \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} & \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} + \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} + \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)} - \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} - \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} & - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} + \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)}\\\\- \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)} - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} + \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} + \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} & \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)} - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} - \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} - \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)} - \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} & \\sin{\\left(\\alpha{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)} + \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\alpha{\\left(t \\right)} \\right)} \\frac{d}{d t} \\alpha{\\left(t \\right)}\\\\\\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} - \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)} & \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\cos{\\left(\\gamma{\\left(t \\right)} \\right)} \\frac{d}{d t} \\gamma{\\left(t \\right)} + \\sin{\\left(\\gamma{\\left(t \\right)} \\right)} \\cos{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)} & - \\sin{\\left(\\beta{\\left(t \\right)} \\right)} \\frac{d}{d t} \\beta{\\left(t \\right)}\\end{matrix}\\right]$"
127+
],
128+
"text/plain": [
129+
"Matrix([\n",
130+
"[-sin(alpha(t))*cos(beta(t))*cos(gamma(t))*Derivative(alpha(t), t) - sin(alpha(t))*cos(gamma(t))*Derivative(gamma(t), t) - sin(beta(t))*cos(alpha(t))*cos(gamma(t))*Derivative(beta(t), t) - sin(gamma(t))*cos(alpha(t))*cos(beta(t))*Derivative(gamma(t), t) - sin(gamma(t))*cos(alpha(t))*Derivative(alpha(t), t), sin(alpha(t))*sin(gamma(t))*cos(beta(t))*Derivative(alpha(t), t) + sin(alpha(t))*sin(gamma(t))*Derivative(gamma(t), t) + sin(beta(t))*sin(gamma(t))*cos(alpha(t))*Derivative(beta(t), t) - cos(alpha(t))*cos(beta(t))*cos(gamma(t))*Derivative(gamma(t), t) - cos(alpha(t))*cos(gamma(t))*Derivative(alpha(t), t), -sin(alpha(t))*sin(beta(t))*Derivative(alpha(t), t) + cos(alpha(t))*cos(beta(t))*Derivative(beta(t), t)],\n",
131+
"[-sin(alpha(t))*sin(beta(t))*cos(gamma(t))*Derivative(beta(t), t) - sin(alpha(t))*sin(gamma(t))*cos(beta(t))*Derivative(gamma(t), t) - sin(alpha(t))*sin(gamma(t))*Derivative(alpha(t), t) + cos(alpha(t))*cos(beta(t))*cos(gamma(t))*Derivative(alpha(t), t) + cos(alpha(t))*cos(gamma(t))*Derivative(gamma(t), t), sin(alpha(t))*sin(beta(t))*sin(gamma(t))*Derivative(beta(t), t) - sin(alpha(t))*cos(beta(t))*cos(gamma(t))*Derivative(gamma(t), t) - sin(alpha(t))*cos(gamma(t))*Derivative(alpha(t), t) - sin(gamma(t))*cos(alpha(t))*cos(beta(t))*Derivative(alpha(t), t) - sin(gamma(t))*cos(alpha(t))*Derivative(gamma(t), t), sin(alpha(t))*cos(beta(t))*Derivative(beta(t), t) + sin(beta(t))*cos(alpha(t))*Derivative(alpha(t), t)],\n",
132+
"[ sin(beta(t))*sin(gamma(t))*Derivative(gamma(t), t) - cos(beta(t))*cos(gamma(t))*Derivative(beta(t), t), sin(beta(t))*cos(gamma(t))*Derivative(gamma(t), t) + sin(gamma(t))*cos(beta(t))*Derivative(beta(t), t), -sin(beta(t))*Derivative(beta(t), t)]])"
133+
]
134+
},
135+
"execution_count": 230,
136+
"metadata": {},
137+
"output_type": "execute_result"
138+
}
139+
],
140+
"source": [
141+
"Rdot = Matrix(R).diff(t)\n",
142+
"Rdot"
143+
]
144+
},
145+
{
146+
"cell_type": "markdown",
147+
"metadata": {},
148+
"source": [
149+
"Get angular velocity vector in terms of angles and angle rates"
150+
]
151+
},
152+
{
153+
"cell_type": "code",
154+
"execution_count": 231,
155+
"metadata": {},
156+
"outputs": [],
157+
"source": [
158+
"omega = Matrix(vex(Rdot * R.T))"
159+
]
160+
},
161+
{
162+
"cell_type": "markdown",
163+
"metadata": {},
164+
"source": [
165+
"For each element of this 3x1 matrix get the coefficients of each angle derivative"
166+
]
167+
},
168+
{
169+
"cell_type": "code",
170+
"execution_count": 232,
171+
"metadata": {},
172+
"outputs": [],
173+
"source": [
174+
"A = Matrix.zeros(3,3)\n",
175+
"for i in range(3):\n",
176+
" e = omega[i,0].expand()\n",
177+
" for j in range(3):\n",
178+
" A[i, j] = e.coeff(angled[j])"
179+
]
180+
},
181+
{
182+
"cell_type": "markdown",
183+
"metadata": {},
184+
"source": [
185+
"The result is a 3x3 matrix. Mapping from angle rates to angular velocity. We subsitute angle as a function of time to plain angle, then simplify."
186+
]
187+
},
188+
{
189+
"cell_type": "code",
190+
"execution_count": 233,
191+
"metadata": {},
192+
"outputs": [],
193+
"source": [
194+
"A = trigsimp(A.subs(a for a in zip(anglet, angle)))"
195+
]
196+
},
197+
{
198+
"cell_type": "markdown",
199+
"metadata": {},
200+
"source": [
201+
"Compute the inverse and simplify. Mapping from angular velocity to angle rates."
202+
]
203+
},
204+
{
205+
"cell_type": "code",
206+
"execution_count": 234,
207+
"metadata": {},
208+
"outputs": [],
209+
"source": [
210+
"Ai = trigsimp(A.inv())"
211+
]
212+
},
213+
{
214+
"cell_type": "markdown",
215+
"metadata": {},
216+
"source": [
217+
"Render as code"
218+
]
219+
},
220+
{
221+
"cell_type": "code",
222+
"execution_count": 235,
223+
"metadata": {},
224+
"outputs": [
225+
{
226+
"data": {
227+
"text/plain": [
228+
"'np.array([[0, -math.sin(alpha), math.sin(beta)*math.cos(alpha)], [0, math.cos(alpha), math.sin(alpha)*math.sin(beta)], [1, 0, math.cos(beta)]])'"
229+
]
230+
},
231+
"execution_count": 235,
232+
"metadata": {},
233+
"output_type": "execute_result"
234+
}
235+
],
236+
"source": [
237+
"pycode(A).replace('ImmutableDenseMatrix', 'np.array')"
238+
]
239+
},
240+
{
241+
"cell_type": "code",
242+
"execution_count": 236,
243+
"metadata": {},
244+
"outputs": [
245+
{
246+
"data": {
247+
"text/plain": [
248+
"'np.array([[-math.cos(alpha)/math.tan(beta), -math.sin(alpha)/math.tan(beta), 1], [-math.sin(alpha), math.cos(alpha), 0], [math.cos(alpha)/math.sin(beta), math.sin(alpha)/math.sin(beta), 0]])'"
249+
]
250+
},
251+
"execution_count": 236,
252+
"metadata": {},
253+
"output_type": "execute_result"
254+
}
255+
],
256+
"source": [
257+
"pycode(Ai).replace('ImmutableDenseMatrix', 'np.array')"
258+
]
259+
},
260+
{
261+
"cell_type": "markdown",
262+
"metadata": {},
263+
"source": [
264+
"Compute the time derivative of `Ai`, from angular acceleration to angle acceleration"
265+
]
266+
},
267+
{
268+
"cell_type": "code",
269+
"execution_count": 237,
270+
"metadata": {},
271+
"outputs": [],
272+
"source": [
273+
"Ai = Ai.subs(a for a in zip(angle, anglet))"
274+
]
275+
},
276+
{
277+
"cell_type": "code",
278+
"execution_count": 238,
279+
"metadata": {},
280+
"outputs": [
281+
{
282+
"data": {
283+
"text/latex": [
284+
"$\\displaystyle \\left[\\begin{matrix}\\frac{\\alpha_{dot} \\sin{\\left(\\alpha \\right)}}{\\tan{\\left(\\beta \\right)}} + \\frac{\\beta_{dot} \\cos{\\left(\\alpha \\right)}}{\\sin^{2}{\\left(\\beta \\right)}} & - \\frac{\\alpha_{dot} \\cos{\\left(\\alpha \\right)}}{\\tan{\\left(\\beta \\right)}} + \\frac{\\beta_{dot} \\sin{\\left(\\alpha \\right)}}{\\sin^{2}{\\left(\\beta \\right)}} & 0\\\\- \\alpha_{dot} \\cos{\\left(\\alpha \\right)} & - \\alpha_{dot} \\sin{\\left(\\alpha \\right)} & 0\\\\- \\frac{\\alpha_{dot} \\sin{\\left(\\alpha \\right)} + \\frac{\\beta_{dot} \\cos{\\left(\\alpha \\right)} \\cos{\\left(\\beta \\right)}}{\\sin{\\left(\\beta \\right)}}}{\\sin{\\left(\\beta \\right)}} & \\frac{\\alpha_{dot} \\cos{\\left(\\alpha \\right)} - \\frac{\\beta_{dot} \\sin{\\left(\\alpha \\right)} \\cos{\\left(\\beta \\right)}}{\\sin{\\left(\\beta \\right)}}}{\\sin{\\left(\\beta \\right)}} & 0\\end{matrix}\\right]$"
285+
],
286+
"text/plain": [
287+
"Matrix([\n",
288+
"[ alpha_dot*sin(alpha)/tan(beta) + beta_dot*cos(alpha)/sin(beta)**2, -alpha_dot*cos(alpha)/tan(beta) + beta_dot*sin(alpha)/sin(beta)**2, 0],\n",
289+
"[ -alpha_dot*cos(alpha), -alpha_dot*sin(alpha), 0],\n",
290+
"[-(alpha_dot*sin(alpha) + beta_dot*cos(alpha)*cos(beta)/sin(beta))/sin(beta), (alpha_dot*cos(alpha) - beta_dot*sin(alpha)*cos(beta)/sin(beta))/sin(beta), 0]])"
291+
]
292+
},
293+
"execution_count": 238,
294+
"metadata": {},
295+
"output_type": "execute_result"
296+
}
297+
],
298+
"source": [
299+
"Ai_dot = trigsimp(Ai.diff(t).subs(a for a in zip(angled, angledn)).subs(a for a in zip(anglet, angle)))\n",
300+
"Ai_dot"
301+
]
302+
},
303+
{
304+
"cell_type": "code",
305+
"execution_count": 239,
306+
"metadata": {},
307+
"outputs": [
308+
{
309+
"data": {
310+
"text/plain": [
311+
"'np.array([[alpha_dot*math.sin(alpha)/math.tan(beta) + beta_dot*math.cos(alpha)/math.sin(beta)**2, -alpha_dot*math.cos(alpha)/math.tan(beta) + beta_dot*math.sin(alpha)/math.sin(beta)**2, 0], [-alpha_dot*math.cos(alpha), -alpha_dot*math.sin(alpha), 0], [-(alpha_dot*math.sin(alpha) + beta_dot*math.cos(alpha)*math.cos(beta)/math.sin(beta))/math.sin(beta), (alpha_dot*math.cos(alpha) - beta_dot*math.sin(alpha)*math.cos(beta)/math.sin(beta))/math.sin(beta), 0]])'"
312+
]
313+
},
314+
"execution_count": 239,
315+
"metadata": {},
316+
"output_type": "execute_result"
317+
}
318+
],
319+
"source": [
320+
"pycode(Ai_dot).replace('ImmutableDenseMatrix', 'np.array')"
321+
]
322+
},
323+
{
324+
"cell_type": "code",
325+
"execution_count": null,
326+
"metadata": {},
327+
"outputs": [],
328+
"source": []
329+
}
330+
],
331+
"metadata": {
332+
"kernelspec": {
333+
"display_name": "Python 3",
334+
"language": "python",
335+
"name": "python3"
336+
},
337+
"language_info": {
338+
"codemirror_mode": {
339+
"name": "ipython",
340+
"version": 3
341+
},
342+
"file_extension": ".py",
343+
"mimetype": "text/x-python",
344+
"name": "python",
345+
"nbconvert_exporter": "python",
346+
"pygments_lexer": "ipython3",
347+
"version": "3.8.5"
348+
},
349+
"varInspector": {
350+
"cols": {
351+
"lenName": 16,
352+
"lenType": 16,
353+
"lenVar": 40
354+
},
355+
"kernels_config": {
356+
"python": {
357+
"delete_cmd_postfix": "",
358+
"delete_cmd_prefix": "del ",
359+
"library": "var_list.py",
360+
"varRefreshCmd": "print(var_dic_list())"
361+
},
362+
"r": {
363+
"delete_cmd_postfix": ") ",
364+
"delete_cmd_prefix": "rm(",
365+
"library": "var_list.r",
366+
"varRefreshCmd": "cat(var_dic_list()) "
367+
}
368+
},
369+
"types_to_exclude": [
370+
"module",
371+
"function",
372+
"builtin_function_or_method",
373+
"instance",
374+
"_Feature"
375+
],
376+
"window_display": false
377+
}
378+
},
379+
"nbformat": 4,
380+
"nbformat_minor": 4
381+
}

0 commit comments

Comments
 (0)