Skip to content

Commit f1eef10

Browse files
committed
Update Jupyter notebooks
1 parent e02737f commit f1eef10

File tree

3 files changed

+83
-16
lines changed

3 files changed

+83
-16
lines changed

notebooks/Example.ipynb

Lines changed: 79 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,11 @@
2727
"metadata": {},
2828
"outputs": [],
2929
"source": [
30-
"# Workaround for: https://github.com/JuliaRobotics/RigidBodyDynamics.jl/issues/500\n",
31-
"using LinearAlgebra; BLAS.set_num_threads(1)"
30+
"using LinearAlgebra\n",
31+
"# Try to load something faster than OpenBLAS\n",
32+
"try using AppleAccelerate catch e; end\n",
33+
"try using MKL catch e; end\n",
34+
"BLAS.get_config()"
3235
]
3336
},
3437
{
@@ -37,11 +40,23 @@
3740
"metadata": {},
3841
"outputs": [],
3942
"source": [
40-
"using KNITRO\n",
43+
"# using KNITRO\n",
4144
"using MeshCat\n",
4245
"using RigidBodyDynamics"
4346
]
4447
},
48+
{
49+
"cell_type": "code",
50+
"execution_count": null,
51+
"metadata": {},
52+
"outputs": [],
53+
"source": [
54+
"# Load the pre-compiled binaries of Coin HSL routines\n",
55+
"HSL_jll_path = expanduser(\"~/HSL_jll.jl-2023.5.26\")\n",
56+
"Pkg.develop(path=HSL_jll_path)\n",
57+
"import HSL_jll"
58+
]
59+
},
4560
{
4661
"cell_type": "code",
4762
"execution_count": null,
@@ -71,8 +86,13 @@
7186
"metadata": {},
7287
"outputs": [],
7388
"source": [
74-
"robot = TORA.create_robot_kuka_iiwa_14(vis)\n",
75-
"problem = TORA.Problem(robot, 301, 1/150)\n",
89+
"robot = TORA.create_robot_franka(\"panda_arm\", vis)\n",
90+
"# robot = TORA.create_robot_kinova_gen2(\"j2s6s200\", vis)\n",
91+
"# robot = TORA.create_robot_kinova_gen3(\"gen3_robotiq_2f_140\", vis)\n",
92+
"# robot = TORA.create_robot_kuka(\"iiwa14\", vis)\n",
93+
"# robot = TORA.create_robot_ur(\"ur10e\", vis)\n",
94+
"\n",
95+
"problem = TORA.Problem(robot, 2001, 1/1000)\n",
7696
"\n",
7797
"# Constrain initial and final joint velocities to zero\n",
7898
"TORA.fix_joint_velocities!(problem, robot, 1, zeros(robot.n_v))\n",
@@ -90,7 +110,8 @@
90110
"\n",
91111
" for k = 1:2:problem.num_knots\n",
92112
" θ = CubicTimeScaling(problem.num_knots - 1, k - 1) * 2π\n",
93-
" pos = [0.5, 0.2 * cos(θ), 0.8 + 0.2 * sin(θ)]\n",
113+
" # pos = [0.5, 0.2 * cos(θ), 0.8 + 0.2 * sin(θ)] # UR10e\n",
114+
" pos = [0.4, 0.2 * cos(θ), 0.7 + 0.2 * sin(θ)] # Franka Emika\n",
94115
" # pos = [0.5, 0.3 * sin(θ) + 0.1 * sin(8 * θ), 0.8 + 0.3 * cos(θ) + 0.1 * cos(8 * θ)]\n",
95116
" TORA.constrain_ee_position!(problem, k, pos)\n",
96117
" end\n",
@@ -105,7 +126,11 @@
105126
"metadata": {},
106127
"outputs": [],
107128
"source": [
108-
"initial_q = [0, 0, 0, -π/2, 0, 0, 0]\n",
129+
"initial_q = zeros(robot.n_q)\n",
130+
"# initial_q = [0, 0, 0, -π/2, 0, 0, 0]\n",
131+
"initial_q = [0, -π/4, 0, -3π/4, 0, π/2, 0] # Franka Emika\n",
132+
"# initial_q = [0, -120, 120, -180, -90, 0] .|> deg2rad # UR10e\n",
133+
"# initial_q = x[1:7]\n",
109134
"\n",
110135
"zero!(robot.state)\n",
111136
"set_configuration!(robot.state, initial_q)\n",
@@ -130,6 +155,45 @@
130155
"use_inv_dyn = true\n",
131156
"minimise_τ = false\n",
132157
"\n",
158+
"user_options = Dict(\n",
159+
" # === Termination === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Termination\n",
160+
" # \"tol\" => 10e-2, # default: 10e-8\n",
161+
" # \"max_cpu_time\" => 4.0, # default: 10e20\n",
162+
" # \"constr_viol_tol\" => 0.1, # default: 0.0001\n",
163+
" # \"acceptable_tol\" => 0.1, # default: 10e-6\n",
164+
" # \"acceptable_constr_viol_tol\" => 0.1, # default: 0.01\n",
165+
"\n",
166+
" # === Output === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Output\n",
167+
" # \"print_level\" => 0, # [0, 12], default: 5\n",
168+
" \n",
169+
" # === NLP Scaling === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_NLP_Scaling\n",
170+
" # \"nlp_scaling_method\" => \"none\", # none, user-scaling, gradient-based, equilibration-based\n",
171+
"\n",
172+
" # === Warm Start === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Warm_Start\n",
173+
" # \"warm_start_init_point\" => \"yes\",\n",
174+
" # \"warm_start_same_structure\" => \"yes\",\n",
175+
" # \"warm_start_entire_iterate\" => \"yes\",\n",
176+
"\n",
177+
" # === Barrier Parameter Update === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Barrier_Parameter_Update\n",
178+
" \"mu_strategy\" => \"adaptive\", # monotone (default), adaptive\n",
179+
" # \"mu_oracle\" => \"loqo\", # probing, loqo, quality-function (default)\n",
180+
"\n",
181+
" # === Linear Solver === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Linear_Solver\n",
182+
" \"linear_solver\" => \"ma57\", # ma27 (default), ma57, ma77, ma86, ma97, (...)\n",
183+
" # \"ma57_pre_alloc\" => 1.10, # [1, Inf), 1.05 (default)\n",
184+
"\n",
185+
" # === Step Calculation === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Step_Calculation\n",
186+
" # \"mehrotra_algorithm\" => \"yes\", # yes, no (default)\n",
187+
" # \"fast_step_computation\" => \"yes\", # yes, no (default)\n",
188+
"\n",
189+
" # === Hessian Approximation === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Hessian_Approximation\n",
190+
" \"hessian_approximation\" => \"limited-memory\", # exact (default), limited-memory\n",
191+
" # \"hessian_approximation_space\" => \"all-variables\", # nonlinear-variables (default), all-variables\n",
192+
"\n",
193+
" # === Derivative Checker === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Derivative_Checker\n",
194+
" # \"derivative_test\" => \"first-order\", # none, first-order, second-order, only-second-order\n",
195+
")\n",
196+
"\n",
133197
"# Choose which solver you want to use:\n",
134198
"solve = TORA.solve_with_ipopt # Uses Ipopt (https://github.com/coin-or/Ipopt)\n",
135199
"# solve = TORA.solve_with_knitro # Uses KNITRO (https://www.artelys.com/solvers/knitro/)\n",
@@ -138,7 +202,8 @@
138202
"cpu_time, x, solver_log = solve(problem, robot,\n",
139203
" initial_guess=initial_guess,\n",
140204
" use_inv_dyn=use_inv_dyn,\n",
141-
" minimise_τ=minimise_τ)"
205+
" minimise_τ=minimise_τ,\n",
206+
" user_options=user_options)"
142207
]
143208
},
144209
{
@@ -162,7 +227,9 @@
162227
{
163228
"cell_type": "code",
164229
"execution_count": null,
165-
"metadata": {},
230+
"metadata": {
231+
"tags": []
232+
},
166233
"outputs": [],
167234
"source": [
168235
"TORA.plot_log(solver_log)"
@@ -171,15 +238,15 @@
171238
],
172239
"metadata": {
173240
"kernelspec": {
174-
"display_name": "Julia 1.8.0",
241+
"display_name": "Julia 1.9.1",
175242
"language": "julia",
176-
"name": "julia-1.8"
243+
"name": "julia-1.9"
177244
},
178245
"language_info": {
179246
"file_extension": ".jl",
180247
"mimetype": "application/julia",
181248
"name": "julia",
182-
"version": "1.8.0"
249+
"version": "1.9.1"
183250
}
184251
},
185252
"nbformat": 4,

notebooks/Tutorial.ipynb

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -128,15 +128,15 @@
128128
],
129129
"metadata": {
130130
"kernelspec": {
131-
"display_name": "Julia 1.8.0",
131+
"display_name": "Julia 1.9.1",
132132
"language": "julia",
133-
"name": "julia-1.8"
133+
"name": "julia-1.9"
134134
},
135135
"language_info": {
136136
"file_extension": ".jl",
137137
"mimetype": "application/julia",
138138
"name": "julia",
139-
"version": "1.8.0"
139+
"version": "1.9.1"
140140
}
141141
},
142142
"nbformat": 4,

src/transcription/ipopt.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ function solve_with_ipopt(problem::Problem, robot::Robot;
2525
initial_guess::Vector{Float64}=Float64[],
2626
use_inv_dyn::Bool=false,
2727
minimise_τ::Bool=false,
28-
user_options::Dict=Dict())
28+
user_options::Dict=Dict("hessian_approximation" => "limited-memory"))
2929
# # # # # # # # # # # # # # # #
3030
# Variables and their bounds #
3131
# # # # # # # # # # # # # # # #

0 commit comments

Comments
 (0)