Skip to content

Commit

Permalink
multi_model
Browse files Browse the repository at this point in the history
  • Loading branch information
EveCharbie committed Sep 20, 2024
1 parent 4182e7b commit 22ef229
Show file tree
Hide file tree
Showing 9 changed files with 512 additions and 390 deletions.
2 changes: 1 addition & 1 deletion bioptim/examples/getting_started/custom_dynamics.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ def custom_dynamics(

# You can directly call biorbd function (as for ddq) or call bioptim accessor (as for dq)
dq = DynamicsFunctions.compute_qdot(nlp, q, qdot) * my_additional_factor
ddq = nlp.model.forward_dynamics(q, qdot, tau, [])
ddq = nlp.model.forward_dynamics()(q, qdot, tau, [])

# the user has to choose if want to return the explicit dynamics dx/dt = f(x,u,p)
# as the first argument of DynamicsEvaluation or
Expand Down
14 changes: 6 additions & 8 deletions bioptim/examples/muscle_driven_ocp/muscle_excitations_tracker.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

import biorbd_casadi as biorbd
import numpy as np
from casadi import MX, vertcat
from casadi import MX, SX, vertcat, horzcat
from matplotlib import pyplot as plt
from scipy.integrate import solve_ivp

Expand Down Expand Up @@ -44,6 +44,7 @@ def generate_data(
n_shooting: int,
use_residual_torque: bool = True,
phase_dynamics: PhaseDynamics = PhaseDynamics.SHARED_DURING_THE_PHASE,
use_sx: bool = False,
) -> tuple:
"""
Generate random data. If np.random.seed is defined before, it will always return the same results
Expand Down Expand Up @@ -91,7 +92,8 @@ def generate_data(
symbolic_controls = vertcat(*(symbolic_tau, symbolic_mus_controls))

symbolic_parameters = MX.sym("u", 0, 0)
nlp = NonLinearProgram(phase_dynamics=phase_dynamics)
nlp = NonLinearProgram(phase_dynamics=phase_dynamics, use_sx=use_sx)
nlp.cx = SX if use_sx else MX
nlp.model = bio_model
nlp.variable_mappings = {
"q": BiMapping(range(n_q), range(n_q)),
Expand All @@ -100,8 +102,6 @@ def generate_data(
"tau": BiMapping(range(n_tau), range(n_tau)),
"muscles": BiMapping(range(n_mus), range(n_mus)),
}
markers_func = biorbd.to_casadi_func("ForwardKin", bio_model.markers, symbolic_q)

nlp.states = OptimizationVariableContainer(phase_dynamics=phase_dynamics)
nlp.states_dot = OptimizationVariableContainer(phase_dynamics=phase_dynamics)
nlp.controls = OptimizationVariableContainer(phase_dynamics=phase_dynamics)
Expand Down Expand Up @@ -202,7 +202,7 @@ def dyn_interface(t, x, u):

def add_to_data(i, q):
X[:, i] = q
markers[:, :, i] = markers_func(q[:n_q])
markers[:, :, i] = horzcat(*bio_model.markers()(q[:n_q]))

x_init = np.array([0.0] * n_q + [0.0] * n_qdot + [0.5] * n_mus)
add_to_data(0, x_init)
Expand Down Expand Up @@ -374,10 +374,8 @@ def main():
n_frames = q.shape[1]

markers = np.ndarray((3, n_mark, q.shape[1]))
symbolic_states = MX.sym("x", n_q, 1)
markers_func = biorbd.to_casadi_func("ForwardKin", bio_model.markers, symbolic_states)
for i in range(n_frames):
markers[:, :, i] = markers_func(q[:, i])
markers[:, :, i] = horzcat(*bio_model.markers()(q[:, i]))

plt.figure("Markers")
n_steps_ode = ocp.nlp[0].ode_solver.steps + 1 if ocp.nlp[0].ode_solver.is_direct_collocation else 1
Expand Down
3 changes: 2 additions & 1 deletion bioptim/limits/constraints.py
Original file line number Diff line number Diff line change
Expand Up @@ -414,7 +414,8 @@ def qddot_equals_forward_dynamics(
tau = tau + controller.model.ligament_joint_torque(q, qdot) if with_ligament else tau

qddot = controller.controls["qddot"].cx if "qddot" in controller.controls else controller.states["qddot"].cx
qddot_fd = controller.model.forward_dynamics(with_contact=with_contact)(q, qdot, tau)
# @Ipuch: no f_ext allowed ?
qddot_fd = controller.model.forward_dynamics(with_contact=with_contact)(q, qdot, tau, [])
return qddot - qddot_fd

@staticmethod
Expand Down
2 changes: 1 addition & 1 deletion bioptim/models/biorbd/biorbd_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ def center_of_mass_acceleration(self) -> Function:
biorbd_return = self.model.CoMddot(q_biorbd, qdot_biorbd, qddot_biorbd, True).to_mx()
casadi_fun = Function(
"center_of_mass_acceleration",
[self.q, self.qdot, self.tau],
[self.q, self.qdot, self.qddot],
[biorbd_return],
)
return casadi_fun
Expand Down
Loading

0 comments on commit 22ef229

Please sign in to comment.