|
1 | | -import PrecompileTools |
2 | | - |
3 | | -PrecompileTools.@compile_workload begin |
4 | | - vis = Visualizer() |
5 | | - robot = create_robot_franka("panda_arm", vis) |
6 | | - problem = Problem(robot, 201, 1/100) |
7 | | - fix_joint_velocities!(problem, robot, 1, zeros(robot.n_v)) |
8 | | - cpu_time, x, solver_log = solve_with_ipopt(problem, robot) |
9 | | - play_trajectory(vis, problem, robot, x) |
10 | | - plot_results(problem, robot, x) |
11 | | - Plots.closeall() |
12 | | - MeshCat.close_server!(vis.core) |
| 1 | +using PrecompileTools: @setup_workload, @compile_workload |
| 2 | + |
| 3 | +# PrecompileTools allows you to reduce the latency of the first execution of Julia code. |
| 4 | +# It is applicable for package developers and for "ordinary users" in their personal workflows. |
| 5 | +# See the GitHub repository and docs for more details: https://github.com/JuliaLang/PrecompileTools.jl. |
| 6 | + |
| 7 | +@setup_workload begin |
| 8 | + |
| 9 | + # Putting some things in `@setup_workload` instead of `@compile_workload` can |
| 10 | + # reduce the size of the precompile file and potentially make loading faster. |
| 11 | + |
| 12 | + # CAREFUL! Objects defined here will persist in every session including this package. |
| 13 | + |
| 14 | + @compile_workload begin |
| 15 | + |
| 16 | + # All calls in this block will be precompiled, regardless of whether they belong to this package or not. |
| 17 | + |
| 18 | + # Options for the Ipopt numerical solver |
| 19 | + ipopt_options = Dict( |
| 20 | + # "acceptable_compl_inf_tol" => 0.1, |
| 21 | + # "acceptable_constr_viol_tol" => 0.1, |
| 22 | + # "acceptable_dual_inf_tol" => 1.0, |
| 23 | + "acceptable_iter" => 1, |
| 24 | + "acceptable_tol" => 1.0, |
| 25 | + "hessian_approximation" => "limited-memory", |
| 26 | + # "max_cpu_time" => 15.0, |
| 27 | + "max_iter" => 1, |
| 28 | + "mu_strategy" => "monotone", |
| 29 | + "print_level" => 0, # default: 5 |
| 30 | + ) |
| 31 | + |
| 32 | + vis = Visualizer() |
| 33 | + robot = create_robot_franka("panda_arm", vis) |
| 34 | + problem = Problem(robot, 2, 1 / 100) |
| 35 | + |
| 36 | + initial_q = Float64[0, 0, 0, -π/2, 0, π, 0] |
| 37 | + |
| 38 | + fix_joint_positions!(problem, robot, 1, initial_q) |
| 39 | + fix_joint_velocities!(problem, robot, 1, zeros(robot.n_v)) |
| 40 | + constrain_ee_position!(problem, 1, zeros(3)) |
| 41 | + |
| 42 | + initial_guess = zeros(problem.num_knots * (robot.n_q + robot.n_v + robot.n_τ) - robot.n_τ) |
| 43 | + |
| 44 | + cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=false, minimise_τ=false) |
| 45 | + cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=false, minimise_τ=true) |
| 46 | + cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=true, minimise_τ=false) |
| 47 | + |
| 48 | + play_trajectory(vis, problem, robot, x) |
| 49 | + plot_results(problem, robot, x) |
| 50 | + |
| 51 | + Plots.closeall() |
| 52 | + MeshCat.close_server!(vis.core) |
| 53 | + |
| 54 | + end |
| 55 | + |
13 | 56 | end |
0 commit comments