Skip to content

Commit d7deba9

Browse files
ferrolhoHenrique Ferrolho
authored andcommitted
Rename minimise_τ to minimise_torques
1 parent 5660076 commit d7deba9

File tree

7 files changed

+18
-18
lines changed

7 files changed

+18
-18
lines changed

interoperability/python_calls_julia.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ def main():
120120
initial_guess=jl_initial_guess,
121121
user_options=ipopt_options,
122122
use_inv_dyn=True,
123-
minimise_τ=False,
123+
minimise_torques=False,
124124
)
125125

126126
# Unpack the solution `x` into joint positions, velocities, and torques

notebooks/Example.ipynb

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,7 @@
153153
"outputs": [],
154154
"source": [
155155
"use_inv_dyn = true\n",
156-
"minimise_τ = false\n",
156+
"minimise_torques = false\n",
157157
"\n",
158158
"user_options = Dict(\n",
159159
" # === Termination === # https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_Termination\n",
@@ -202,7 +202,7 @@
202202
"cpu_time, x, solver_log = solve(problem, robot,\n",
203203
" initial_guess=initial_guess,\n",
204204
" use_inv_dyn=use_inv_dyn,\n",
205-
" minimise_τ=minimise_τ,\n",
205+
" minimise_torques=minimise_torques,\n",
206206
" user_options=user_options)"
207207
]
208208
},
@@ -238,15 +238,15 @@
238238
],
239239
"metadata": {
240240
"kernelspec": {
241-
"display_name": "Julia 1.11.1",
241+
"display_name": "Julia 1.11.3",
242242
"language": "julia",
243243
"name": "julia-1.11"
244244
},
245245
"language_info": {
246246
"file_extension": ".jl",
247247
"mimetype": "application/julia",
248248
"name": "julia",
249-
"version": "1.11.1"
249+
"version": "1.11.3"
250250
}
251251
},
252252
"nbformat": 4,

notebooks/Tutorial.ipynb

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

src/TORA.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ import Base: length
2424
solve_with_knitro(problem, robot;
2525
initial_guess=Float64[],
2626
use_inv_dyn=false,
27-
minimise_τ=false,
27+
minimise_torques=false,
2828
user_options=Dict())
2929
3030
Solve the nonlinear optimization problem with Knitro.
@@ -34,7 +34,7 @@ Further options can be set using the keyword arguments. See [Solver Interfaces](
3434
# Keyword arguments
3535
- `initial_guess::Vector{Float64}=Float64[]`: the starting point for the solver.
3636
- `use_inv_dyn::Bool=false`: if true, enables the use of inverse dynamics instead of forward dynamics.
37-
- `minimise_τ::Bool=false`: if true, activates a cost function to minimize the joint torques.
37+
- `minimise_torques::Bool=false`: if true, activates a cost function to minimize the joint torques.
3838
- `user_options::Dict=Dict()`: the user options for Knitro.
3939
4040
See also: [`solve_with_ipopt`](@ref)

src/precompile.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -45,9 +45,9 @@ using PrecompileTools: @setup_workload, @compile_workload
4545

4646
initial_guess = zeros(problem.num_knots * (robot.n_q + robot.n_v + robot.n_τ) - robot.n_τ)
4747

48-
cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=false, minimise_τ=false)
49-
cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=false, minimise_τ=true)
50-
cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=true, minimise_τ=false)
48+
cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=false, minimise_torques=false)
49+
cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=false, minimise_torques=true)
50+
cpu_time, x, solver_log = solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=ipopt_options, use_inv_dyn=true, minimise_torques=false)
5151

5252
play_trajectory(vis, problem, robot, x)
5353
plot_results(problem, robot, x)

src/transcription/ipopt.jl

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ addOption(prob, k, v::Float64) = Ipopt.AddIpoptNumOption(prob, k, v)
66
solve_with_ipopt(problem, robot;
77
initial_guess=Float64[],
88
use_inv_dyn=false,
9-
minimise_τ=false,
9+
minimise_torques=false,
1010
user_options=Dict())
1111
1212
Solve the nonlinear optimization problem with Ipopt.
@@ -16,15 +16,15 @@ Further options can be set using the keyword arguments. See [Solver Interfaces](
1616
# Keyword arguments
1717
- `initial_guess::Vector{Float64}=Float64[]`: the starting point for the solver.
1818
- `use_inv_dyn::Bool=false`: if true, enables the use of inverse dynamics instead of forward dynamics.
19-
- `minimise_τ::Bool=false`: if true, activates a cost function to minimize the joint torques.
19+
- `minimise_torques::Bool=false`: if true, activates a cost function to minimize the joint torques.
2020
- `user_options::Dict=Dict()`: the user options for Ipopt.
2121
2222
See also: [`solve_with_knitro`](@ref)
2323
"""
2424
function solve_with_ipopt(problem::Problem, robot::Robot;
2525
initial_guess::Vector{Float64}=Float64[],
2626
use_inv_dyn::Bool=false,
27-
minimise_τ::Bool=false,
27+
minimise_torques::Bool=false,
2828
user_options::Dict=Dict("hessian_approximation" => "limited-memory"))
2929
# # # # # # # # # # # # # # # #
3030
# Variables and their bounds #
@@ -283,7 +283,7 @@ function solve_with_ipopt(problem::Problem, robot::Robot;
283283
grad_f[:] = zeros(n)
284284
end
285285

286-
if minimise_τ
286+
if minimise_torques
287287
ind_τ = hcat([range(1 + (i * nₓ) + robot.n_q + robot.n_v, length=robot.n_τ)
288288
for i = (1:problem.num_knots - 1) .- 1]...)
289289
indexVars, coefs = vec(ind_τ), fill(1 / (problem.num_knots - 1), n3)

src/transcription/knitro.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ using .KNITRO
33
function solve_with_knitro(problem::Problem, robot::Robot;
44
initial_guess::Vector{Float64}=Float64[],
55
use_inv_dyn::Bool=false,
6-
minimise_τ::Bool=false,
6+
minimise_torques::Bool=false,
77
user_options::Dict=Dict())
88
lm = KNITRO.LMcontext() # Instantiate license manager
99
kc = KNITRO.KN_new_lm(lm) # Create a new Knitro instance
@@ -136,7 +136,7 @@ function solve_with_knitro(problem::Problem, robot::Robot;
136136
# Objective #
137137
# # # # # # #
138138

139-
if minimise_τ
139+
if minimise_torques
140140
# Minimize τ, i.e., the necessary joint torques.
141141
indexVars, coefs = Cint.(vec(ind_τ) .- 1), fill(1 / (problem.num_knots - 1), n3)
142142
KNITRO.KN_add_obj_quadratic_struct(kc, indexVars, indexVars, coefs)

0 commit comments

Comments
 (0)