Skip to content

Commit a386c3a

Browse files
author
Murilo Marinho
committed
[lesson2] Added exercise d.
1 parent 5435c78 commit a386c3a

2 files changed

Lines changed: 169 additions & 23 deletions

File tree

basic_lessons/lesson2_exercise_answers.ipynb

Lines changed: 112 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -44,14 +44,19 @@
4444
"source": "# Valid imports"
4545
},
4646
{
47-
"metadata": {},
47+
"metadata": {
48+
"ExecuteTime": {
49+
"end_time": "2026-01-29T22:31:23.725947Z",
50+
"start_time": "2026-01-29T22:31:23.709145Z"
51+
}
52+
},
4853
"cell_type": "code",
4954
"source": [
5055
"from math import pi, sin, cos\n",
5156
"import numpy as np"
5257
],
5358
"outputs": [],
54-
"execution_count": null
59+
"execution_count": 13
5560
},
5661
{
5762
"metadata": {},
@@ -63,7 +68,12 @@
6368
]
6469
},
6570
{
66-
"metadata": {},
71+
"metadata": {
72+
"ExecuteTime": {
73+
"end_time": "2026-01-29T22:31:23.749857Z",
74+
"start_time": "2026-01-29T22:31:23.733624Z"
75+
}
76+
},
6777
"cell_type": "code",
6878
"source": [
6979
"θ_a = pi/4.0\n",
@@ -74,16 +84,30 @@
7484
"# Printing the result is NOT a mandatory part of the answer.\n",
7585
"print(f'R_a = {R_a}')"
7686
],
77-
"outputs": [],
78-
"execution_count": null
87+
"outputs": [
88+
{
89+
"name": "stdout",
90+
"output_type": "stream",
91+
"text": [
92+
"R_a = [[ 0.70710678 -0.70710678]\n",
93+
" [ 0.70710678 0.70710678]]\n"
94+
]
95+
}
96+
],
97+
"execution_count": 14
7998
},
8099
{
81100
"metadata": {},
82101
"cell_type": "markdown",
83102
"source": "## Exercise b"
84103
},
85104
{
86-
"metadata": {},
105+
"metadata": {
106+
"ExecuteTime": {
107+
"end_time": "2026-01-29T22:31:23.765717Z",
108+
"start_time": "2026-01-29T22:31:23.750326Z"
109+
}
110+
},
87111
"cell_type": "code",
88112
"source": [
89113
"θ_b1 = pi/12.0\n",
@@ -99,21 +123,35 @@
99123
"\n",
100124
"print(f'R_b = {R_b}')"
101125
],
102-
"outputs": [],
103-
"execution_count": null
126+
"outputs": [
127+
{
128+
"name": "stdout",
129+
"output_type": "stream",
130+
"text": [
131+
"R_b = [[ 0.25881905 0.96592583]\n",
132+
" [-0.96592583 0.25881905]]\n"
133+
]
134+
}
135+
],
136+
"execution_count": 15
104137
},
105138
{
106139
"metadata": {},
107140
"cell_type": "markdown",
108141
"source": "## Exercise c"
109142
},
110143
{
111-
"metadata": {},
144+
"metadata": {
145+
"ExecuteTime": {
146+
"end_time": "2026-01-29T22:31:23.779702Z",
147+
"start_time": "2026-01-29T22:31:23.766189Z"
148+
}
149+
},
112150
"cell_type": "code",
113151
"source": [
114-
"θ_c = pi/3.0 # As given in the exercise\n",
115-
"x_c = 2.0 # As given in the exercise\n",
116-
"y_c = 5.0 # As given in the exercise\n",
152+
"θ_c = pi/3.0\n",
153+
"x_c = 2.0\n",
154+
"y_c = 5.0\n",
117155
"\n",
118156
"H_c1 = np.array([[cos(θ_c),-sin(θ_c), 0],\n",
119157
" [sin(θ_c), cos(θ_c), 0],\n",
@@ -127,8 +165,68 @@
127165
"\n",
128166
"print(f'H_c = {H_c}')"
129167
],
130-
"outputs": [],
131-
"execution_count": null
168+
"outputs": [
169+
{
170+
"name": "stdout",
171+
"output_type": "stream",
172+
"text": [
173+
"H_c = [[ 0.5 -0.8660254 -3.33012702]\n",
174+
" [ 0.8660254 0.5 4.23205081]\n",
175+
" [ 0. 0. 1. ]]\n"
176+
]
177+
}
178+
],
179+
"execution_count": 16
180+
},
181+
{
182+
"metadata": {},
183+
"cell_type": "markdown",
184+
"source": "## Exercise d"
185+
},
186+
{
187+
"metadata": {
188+
"ExecuteTime": {
189+
"end_time": "2026-01-29T22:31:23.798367Z",
190+
"start_time": "2026-01-29T22:31:23.780110Z"
191+
}
192+
},
193+
"cell_type": "code",
194+
"source": [
195+
"θ_d = pi/3.0\n",
196+
"x_d = 2.0\n",
197+
"y_d = 5.0\n",
198+
"\n",
199+
"\n",
200+
"H_d1 = np.array([[1,0,x_d],\n",
201+
" [0,1,y_d],\n",
202+
" [0,0,1]])\n",
203+
"\n",
204+
"H_d2 = np.array([[cos(θ_d),-sin(θ_d), 0],\n",
205+
" [sin(θ_d), cos(θ_d), 0],\n",
206+
" [0, 0, 1]])\n",
207+
"\n",
208+
"\n",
209+
"H_d = H_d1 @ H_d2\n",
210+
"\n",
211+
"print(f'H_d = {H_d}')"
212+
],
213+
"outputs": [
214+
{
215+
"name": "stdout",
216+
"output_type": "stream",
217+
"text": [
218+
"H_d = [[ 0.5 -0.8660254 2. ]\n",
219+
" [ 0.8660254 0.5 5. ]\n",
220+
" [ 0. 0. 1. ]]\n"
221+
]
222+
}
223+
],
224+
"execution_count": 17
225+
},
226+
{
227+
"metadata": {},
228+
"cell_type": "markdown",
229+
"source": "`H_c` is *not* the same as `H_d`. This indicates that the order of operations matter. That is, sequential pose transformations are not commutative."
132230
}
133231
],
134232
"metadata": {

basic_lessons/lesson2_tutorial.ipynb

Lines changed: 57 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -253,16 +253,27 @@
253253
"source": [
254254
"# 2D poses (combined translation/orientation)\n",
255255
"\n",
256-
"2D poses can be represented using elements of SE(2). Translations and rotations can be combined into a single $\\mymatrix{H}\\in\\mathbb{R}^{3 \\times 3}$ with the following structure\n",
257-
"\n",
258-
"$$\\mymatrix{H}(x,y,\\theta) = \\left[\\begin{array}{ccc}\n",
256+
"2D poses can be represented using elements of SE(2). A translation followed by a rotation can be combined into a single $\\mymatrix{H}\\in\\mathbb{R}^{3 \\times 3}$ with the following structure\n",
257+
"\n",
258+
"$$\\mymatrix{H}(x,y,\\theta) =\n",
259+
"\\left[\\begin{array}{ccc}\n",
260+
" 1 & 0 & x \\\\\n",
261+
" 0 & 1 & y \\\\\n",
262+
" 0 & 0 & 1\n",
263+
" \\end{array}\\right]\n",
264+
"\\left[\\begin{array}{ccc}\n",
265+
" \\cos{\\theta} & -\\sin{\\theta} & 0 \\\\\n",
266+
" \\sin{\\theta} & \\cos{\\theta} & 0 \\\\\n",
267+
" 0 & 0 & 1\n",
268+
" \\end{array}\\right] =\n",
269+
"\\left[\\begin{array}{ccc}\n",
259270
" \\cos{\\theta} & -\\sin{\\theta} & x \\\\\n",
260271
" \\sin{\\theta} & \\cos{\\theta} & y \\\\\n",
261272
" 0 & 0 & 1\n",
262273
" \\end{array}\\right].$$\n",
263274
"\n",
264275
"<div class=\"alert alert-block alert-info\">\n",
265-
"The pose written as a homogenous matrix shown above represents a translation followed by a rotation. To see the difference, check the exercises at the end of this lesson.\n",
276+
"The translation and rotation order is extremelly important. Check the exercises at the end of this lesson.\n",
266277
"</div>\n",
267278
"\n",
268279
"For $\\theta = \\frac{\\pi}{2}$, $x = 0.1$, and $y = 0.2$, we have the following equivalent piece of code."
@@ -363,7 +374,7 @@
363374
"source": [
364375
"## Compositions of rotations in SO(3)\n",
365376
"\n",
366-
"Compositions in SO(3) follow the same rules as SO(2), where sequential frame transformations are represented by right multiplications. For instance,\n",
377+
"Compositions in SO(3) follow the same rules as SO(2), where sequential rotations are represented by right multiplications. For instance,\n",
367378
"\n",
368379
"$$\\mymatrix{R}_c = \\mymatrix{R}_a\\mymatrix{R}^a_b\\mymatrix{R}^b_c.$$\n",
369380
"\n",
@@ -428,12 +439,25 @@
428439
"source": [
429440
"# 3D poses\n",
430441
"\n",
431-
"3D poses are represented in SE(3) with matrices $\\mymatrix{H}\\in\\mathbb{R}^{4 \\times 4}$ with the following structure\n",
432-
"\n",
433-
"$$\\mymatrix{H}(\\myvec{t},\\mymatrix{R}) = \\left[\\begin{array}{ccc}\n",
442+
"A translation followed by a rotation in 3D is represented in SE(3) with matrices $\\mymatrix{H}\\in\\mathbb{R}^{4 \\times 4}$ with the following structure\n",
443+
"\n",
444+
"$$\\mymatrix{H}(\\myvec{t},\\mymatrix{R}) =\n",
445+
"\\left[\\begin{array}{ccc}\n",
446+
" \\mymatrix{I} & \\myvec{t} \\\\\n",
447+
" \\myvec{0} & 1\n",
448+
" \\end{array}\\right]\n",
449+
"\\left[\\begin{array}{ccc}\n",
450+
" \\mymatrix{R} & \\myvec{0} \\\\\n",
451+
" \\myvec{0} & 1\n",
452+
" \\end{array}\\right] =\n",
453+
"\\left[\\begin{array}{ccc}\n",
434454
" \\mymatrix{R} & \\myvec{t} \\\\\n",
435455
" \\myvec{0} & 1 \n",
436-
" \\end{array}\\right].$$"
456+
" \\end{array}\\right].$$\n",
457+
"\n",
458+
"<div class=\"alert alert-block alert-info\">\n",
459+
"The translation and rotation order is extremelly important.\n",
460+
"</div>"
437461
]
438462
},
439463
{
@@ -614,6 +638,30 @@
614638
],
615639
"outputs": [],
616640
"execution_count": null
641+
},
642+
{
643+
"metadata": {},
644+
"cell_type": "markdown",
645+
"source": [
646+
"## Exercise d\n",
647+
"\n",
648+
"Consider the same variables as in `Exercise c` by replacing the subscripts with `d`. Calculate, instead, the rotation followed by the translation. Store the result in the variable `H_d` shown in the cell below.\n",
649+
"\n",
650+
"Is `H_c` the same as `H_d`? What does that indicate?"
651+
]
652+
},
653+
{
654+
"metadata": {},
655+
"cell_type": "code",
656+
"outputs": [],
657+
"execution_count": null,
658+
"source": [
659+
"θ_d = pi/3.0 # As given in the exercise\n",
660+
"x_d = 2.0 # As given in the exercise\n",
661+
"y_d = 5.0 # As given in the exercise\n",
662+
"\n",
663+
"H_d = None # Replace None with your solution to this exercise."
664+
]
617665
}
618666
],
619667
"metadata": {

0 commit comments

Comments
 (0)