Skip to content

Commit

Permalink
fixed parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
EveCharbie committed Sep 20, 2024
1 parent 22ef229 commit 08e2007
Show file tree
Hide file tree
Showing 11 changed files with 149 additions and 163 deletions.
4 changes: 1 addition & 3 deletions bioptim/dynamics/configure_problem.py
Original file line number Diff line number Diff line change
Expand Up @@ -1166,8 +1166,6 @@ def configure_dynamics_function(ocp, nlp, dyn_func, **extra_params):
The function to get the derivative of the states
"""

DynamicsFunctions.apply_parameters(nlp)

dynamics_eval = dyn_func(
nlp.time_cx,
nlp.states.scaled.cx,
Expand Down Expand Up @@ -1355,7 +1353,7 @@ def configure_soft_contact_function(ocp, nlp):

q = nlp.states.cx[nlp.states["q"].index]
qdot = nlp.states.cx[nlp.states["qdot"].index]
global_soft_contact_force_func = nlp.model.soft_contact_forces()(q, qdot)
global_soft_contact_force_func = nlp.model.soft_contact_forces()(q, qdot, nlp.parameters.cx)
nlp.soft_contact_forces_func = global_soft_contact_force_func

for i_sc in range(nlp.model.nb_soft_contacts):
Expand Down
73 changes: 26 additions & 47 deletions bioptim/dynamics/dynamics_functions.py
Original file line number Diff line number Diff line change
Expand Up @@ -147,8 +147,8 @@ def torque_driven(
dq = DynamicsFunctions.compute_qdot(nlp, q, qdot)

tau = DynamicsFunctions.__get_fatigable_tau(nlp, states, controls, fatigue)
tau = tau + nlp.model.passive_joint_torque()(q, qdot) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot) if with_ligament else tau
tau = tau + nlp.model.passive_joint_torque()(q, qdot, nlp.parameters.cx) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot, nlp.parameters.cx) if with_ligament else tau
tau = tau - nlp.model.friction_coefficients @ qdot if with_friction else tau

if (
Expand Down Expand Up @@ -260,7 +260,7 @@ def torque_driven_free_floating_base(
n_qdot = nlp.model.nb_qdot

tau_joints = (
tau_joints + nlp.model.passive_joint_torque()(q_full, qdot_full) if with_passive_torque else tau_joints
tau_joints + nlp.model.passive_joint_torque()(q_full, qdot_full, nlp.parameters.cx) if with_passive_torque else tau_joints
)
tau_joints = tau_joints + nlp.model.ligament_joint_torque()(q_full, qdot_full) if with_ligament else tau_joints
tau_joints = tau_joints - nlp.model.friction_coefficients @ qdot_joints if with_friction else tau_joints
Expand Down Expand Up @@ -528,13 +528,13 @@ def torque_activations_driven(
qdot = DynamicsFunctions.get(nlp.states["qdot"], states)
tau_activation = DynamicsFunctions.get(nlp.controls["tau"], controls)

tau = nlp.model.torque()(tau_activation, q, qdot)
tau = nlp.model.torque()(tau_activation, q, qdot, nlp.parameters.cx)
if with_passive_torque:
tau += nlp.model.passive_joint_torque()(q, qdot)
tau += nlp.model.passive_joint_torque()(q, qdot, nlp.parameters.cx)
if with_residual_torque:
tau += DynamicsFunctions.get(nlp.controls["residual_tau"], controls)
if with_ligament:
tau += nlp.model.ligament_joint_torque()(q, qdot)
tau += nlp.model.ligament_joint_torque()(q, qdot, nlp.parameters.cx)

dq = DynamicsFunctions.compute_qdot(nlp, q, qdot)
ddq = DynamicsFunctions.forward_dynamics(nlp, q, qdot, tau, with_contact, external_forces)
Expand Down Expand Up @@ -598,8 +598,8 @@ def torque_derivative_driven(
qdot = DynamicsFunctions.get(nlp.states["qdot"], states)

tau = DynamicsFunctions.get(nlp.states["tau"], states)
tau = tau + nlp.model.passive_joint_torque()(q, qdot) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot) if with_ligament else tau
tau = tau + nlp.model.passive_joint_torque()(q, qdot, nlp.parameters.cx) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot, nlp.parameters.cx) if with_ligament else tau

dq = DynamicsFunctions.compute_qdot(nlp, q, qdot)
dtau = DynamicsFunctions.get(nlp.controls["taudot"], controls)
Expand Down Expand Up @@ -673,11 +673,11 @@ def forces_from_torque_driven(
q = nlp.get_var_from_states_or_controls("q", states, controls)
qdot = nlp.get_var_from_states_or_controls("qdot", states, controls)
tau = nlp.get_var_from_states_or_controls("tau", states, controls)
tau = tau + nlp.model.passive_joint_torque()(q, qdot) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot) if with_ligament else tau
tau = tau + nlp.model.passive_joint_torque()(q, qdot, nlp.parameters.cx) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot, nlp.parameters.cx) if with_ligament else tau

external_forces = [] if external_forces is None else external_forces
return nlp.model.contact_forces()(q, qdot, tau, external_forces)
return nlp.model.contact_forces()(q, qdot, tau, external_forces, nlp.parameters.cx)

@staticmethod
def forces_from_torque_activation_driven(
Expand Down Expand Up @@ -726,12 +726,12 @@ def forces_from_torque_activation_driven(
q = nlp.get_var_from_states_or_controls("q", states, controls)
qdot = nlp.get_var_from_states_or_controls("qdot", states, controls)
tau_activations = nlp.get_var_from_states_or_controls("tau", states, controls)
tau = nlp.model.torque()(tau_activations, q, qdot)
tau = tau + nlp.model.passive_joint_torque()(q, qdot) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot) if with_ligament else tau
tau = nlp.model.torque()(tau_activations, q, qdot, nlp.parameters.cx)
tau = tau + nlp.model.passive_joint_torque()(q, qdot, nlp.parameters.cx) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot, nlp.parameters.cx) if with_ligament else tau

external_forces = [] if external_forces is None else external_forces
return nlp.model.contact_forces()(q, qdot, tau, external_forces)
return nlp.model.contact_forces()(q, qdot, tau, external_forces, nlp.parameters.cx)

@staticmethod
def muscles_driven(
Expand Down Expand Up @@ -831,8 +831,8 @@ def muscles_driven(
muscles_tau = DynamicsFunctions.compute_tau_from_muscle(nlp, q, qdot, mus_activations, fatigue_states)

tau = muscles_tau + residual_tau if residual_tau is not None else muscles_tau
tau = tau + nlp.model.passive_joint_torque()(q, qdot) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot) if with_ligament else tau
tau = tau + nlp.model.passive_joint_torque()(q, qdot, nlp.parameters.cx) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot, nlp.parameters.cx) if with_ligament else tau

dq = DynamicsFunctions.compute_qdot(nlp, q, qdot)

Expand Down Expand Up @@ -932,8 +932,8 @@ def forces_from_muscle_driven(
muscles_tau = DynamicsFunctions.compute_tau_from_muscle(nlp, q, qdot, mus_activations)

tau = muscles_tau + residual_tau if residual_tau is not None else muscles_tau
tau = tau + nlp.model.passive_joint_torque()(q, qdot) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot) if with_ligament else tau
tau = tau + nlp.model.passive_joint_torque()(q, qdot, nlp.parameters.cx) if with_passive_torque else tau
tau = tau + nlp.model.ligament_joint_torque()(q, qdot, nlp.parameters.cx) if with_ligament else tau

external_forces = [] if external_forces is None else external_forces
return nlp.model.contact_forces()(q, qdot, tau, external_forces)
Expand Down Expand Up @@ -1040,27 +1040,6 @@ def get(var: OptimizationVariable, cx: MX | SX):

return var.mapping.to_second.map(cx[var.index, :])

@staticmethod
def apply_parameters(nlp):
"""
Apply the parameter variables to the model. This should be called before calling the dynamics
Parameters
----------
parameters: MX.sym | SX.sym
The state of the system
nlp: NonLinearProgram
The definition of the system
"""

for param_key in nlp.parameters:
# Call the pre dynamics function
if nlp.parameters[param_key].function:
param = nlp.parameters[param_key]
param_scaling = nlp.parameters[param_key].scaling.scaling
param_reduced = nlp.parameters.scaled.cx[param.index]
param.function(nlp.model, param_reduced * param_scaling, **param.kwargs)

@staticmethod
def compute_qdot(nlp, q: MX | SX, qdot: MX | SX):
"""
Expand Down Expand Up @@ -1093,7 +1072,7 @@ def compute_qdot(nlp, q: MX | SX, qdot: MX | SX):
mapping = nlp.controls["q"].mapping
else:
raise RuntimeError("Your q key combination was not found in states or controls")
return mapping.to_first.map(nlp.model.reshape_qdot()(q, qdot))
return mapping.to_first.map(nlp.model.reshape_qdot()(q, qdot, nlp.parameters.cx))

@staticmethod
def forward_dynamics(
Expand Down Expand Up @@ -1134,10 +1113,10 @@ def forward_dynamics(
qdot_var_mapping = BiMapping([i for i in range(qdot.shape[0])], [i for i in range(qdot.shape[0])]).to_first

if external_forces is None:
qddot = nlp.model.forward_dynamics(with_contact=with_contact)(q, qdot, tau, [])
qddot = nlp.model.forward_dynamics(with_contact=with_contact)(q, qdot, tau, [], nlp.parameters.cx)
return qdot_var_mapping.map(qddot)
else:
qddot = nlp.model.forward_dynamics(with_contact=with_contact)(q, qdot, tau, external_forces)
qddot = nlp.model.forward_dynamics(with_contact=with_contact)(q, qdot, tau, external_forces, nlp.parameters.cx)
return qdot_var_mapping.map(qddot)

@staticmethod
Expand Down Expand Up @@ -1173,7 +1152,7 @@ def inverse_dynamics(
"""

if external_forces is None:
tau = nlp.model.inverse_dynamics(with_contact=with_contact)(q, qdot, qddot, [])
tau = nlp.model.inverse_dynamics(with_contact=with_contact)(q, qdot, qddot, [], nlp.parameters.cx)
else:
if "tau" in nlp.states:
tau_shape = nlp.states["tau"].cx.shape[0]
Expand All @@ -1183,7 +1162,7 @@ def inverse_dynamics(
tau_shape = nlp.model.nb_tau
tau = nlp.cx(tau_shape, nlp.ns)
for i in range(external_forces.shape[1]):
tau[:, i] = nlp.model.inverse_dynamics(with_contact=with_contact)(q, qdot, qddot, external_forces[:, i])
tau[:, i] = nlp.model.inverse_dynamics(with_contact=with_contact)(q, qdot, qddot, external_forces[:, i], nlp.parameters.cx)
return tau # We ignore on purpose the mapping to keep zeros in the defects of the dynamic.

@staticmethod
Expand Down Expand Up @@ -1240,7 +1219,7 @@ def compute_tau_from_muscle(
activations = vertcat(activations, muscle_activations[k] * (1 - fatigue_states[k]))
else:
activations = vertcat(activations, muscle_activations[k])
return nlp.model.muscle_joint_torque()(activations, q, qdot)
return nlp.model.muscle_joint_torque()(activations, q, qdot, nlp.parameters.cx)

@staticmethod
def holonomic_torque_driven(
Expand Down Expand Up @@ -1283,6 +1262,6 @@ def holonomic_torque_driven(
q_u = DynamicsFunctions.get(nlp.states["q_u"], states)
qdot_u = DynamicsFunctions.get(nlp.states["qdot_u"], states)
tau = DynamicsFunctions.get(nlp.controls["tau"], controls)
qddot_u = nlp.model.partitioned_forward_dynamics(q_u, qdot_u, tau, external_forces=external_forces)
qddot_u = nlp.model.partitioned_forward_dynamics(q_u, qdot_u, tau, external_forces, nlp.parameters.cx)

return DynamicsEvaluation(dxdt=vertcat(qdot_u, qddot_u), defects=None)
2 changes: 0 additions & 2 deletions bioptim/examples/getting_started/custom_objectives.py
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,6 @@ def prepare_ocp(
first_marker="m0",
second_marker="m1",
weight=1000,
method=0,
)
objective_functions.add(
custom_func_track_markers,
Expand All @@ -118,7 +117,6 @@ def prepare_ocp(
first_marker="m0",
second_marker="m2",
weight=1000,
method=1,
)

# Dynamics
Expand Down
56 changes: 28 additions & 28 deletions bioptim/examples/getting_started/custom_parameters.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ def my_parameter_function(bio_model: BiorbdModel, value: MX, extra_value: Any):
"""

value[2] *= extra_value
bio_model.set_gravity(value)
bio_model.model.setGravity(value)


def set_mass(bio_model: BiorbdModel, value: MX):
Expand All @@ -65,7 +65,7 @@ def set_mass(bio_model: BiorbdModel, value: MX):
The CasADi variables to modify the model
"""

bio_model.segments[0].characteristics().setMass(value)
bio_model.model.segments()[0].characteristics().setMass(value)


def my_target_function(controller: PenaltyController, key: str) -> MX:
Expand Down Expand Up @@ -149,32 +149,6 @@ def prepare_ocp(
The ocp ready to be solved
"""

# --- Options --- #
bio_model = BiorbdModel(biorbd_model_path)
n_tau = bio_model.nb_tau

# Add objective functions
objective_functions = ObjectiveList()
objective_functions.add(ObjectiveFcn.Lagrange.MINIMIZE_CONTROL, key="tau", weight=1)
objective_functions.add(ObjectiveFcn.Lagrange.MINIMIZE_STATE, key="q", weight=1)

# Dynamics
dynamics = Dynamics(DynamicsFcn.TORQUE_DRIVEN, expand_dynamics=expand_dynamics, phase_dynamics=phase_dynamics)

# Path constraint
x_bounds = BoundsList()
x_bounds["q"] = bio_model.bounds_from_ranges("q")
x_bounds["q"][:, [0, -1]] = 0
x_bounds["q"][1, -1] = 3.14
x_bounds["qdot"] = bio_model.bounds_from_ranges("qdot")
x_bounds["qdot"][:, [0, -1]] = 0

# Define control path constraint
tau_min, tau_max = -300, 300
u_bounds = BoundsList()
u_bounds["tau"] = [tau_min] * n_tau, [tau_max] * n_tau
u_bounds["tau"][1, :] = 0

# Define the parameter to optimize
parameters = ParameterList(use_sx=use_sx)
parameter_objectives = ParameterObjectiveList()
Expand Down Expand Up @@ -230,6 +204,32 @@ def prepare_ocp(
key="mass",
)

# --- Options --- #
bio_model = BiorbdModel(biorbd_model_path, parameters=parameters)
n_tau = bio_model.nb_tau

# Add objective functions
objective_functions = ObjectiveList()
objective_functions.add(ObjectiveFcn.Lagrange.MINIMIZE_CONTROL, key="tau", weight=1)
objective_functions.add(ObjectiveFcn.Lagrange.MINIMIZE_STATE, key="q", weight=1)

# Dynamics
dynamics = Dynamics(DynamicsFcn.TORQUE_DRIVEN, expand_dynamics=expand_dynamics, phase_dynamics=phase_dynamics)

# Path constraint
x_bounds = BoundsList()
x_bounds["q"] = bio_model.bounds_from_ranges("q")
x_bounds["q"][:, [0, -1]] = 0
x_bounds["q"][1, -1] = 3.14
x_bounds["qdot"] = bio_model.bounds_from_ranges("qdot")
x_bounds["qdot"][:, [0, -1]] = 0

# Define control path constraint
tau_min, tau_max = -300, 300
u_bounds = BoundsList()
u_bounds["tau"] = [tau_min] * n_tau, [tau_max] * n_tau
u_bounds["tau"][1, :] = 0

return OptimalControlProgram(
bio_model,
dynamics,
Expand Down
11 changes: 3 additions & 8 deletions bioptim/examples/moving_horizon_estimation/mhe.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,20 +42,15 @@
def states_to_markers(bio_model, states):
nq = bio_model.nb_q
n_mark = bio_model.nb_markers
q = cas.MX.sym("q", nq)
markers_func = biorbd.to_casadi_func("makers", bio_model.markers, q)
return np.array(markers_func(states[:nq, :])).reshape((3, n_mark, -1), order="F")
return np.array(bio_model.markers()(states[:nq, :])).reshape((3, n_mark, -1), order="F")


def generate_data(bio_model, tf, x0, t_max, n_shoot, noise_std, show_plots=False):
def pendulum_ode(t, x, u):
return np.concatenate((x[nq:, np.newaxis], qddot_func(x[:nq], x[nq:], u)))[:, 0]
return np.concatenate((x[nq:, np.newaxis], qddot_func(x[:nq], x[nq:], u, [])))[:, 0]

nq = bio_model.nb_q
q = cas.MX.sym("q", nq)
qdot = cas.MX.sym("qdot", nq)
tau = cas.MX.sym("tau", nq)
qddot_func = biorbd.to_casadi_func("forw_dyn", bio_model.forward_dynamics, q, qdot, tau)
qddot_func = bio_model.forward_dynamics()

# Simulated data
dt = tf / n_shoot
Expand Down
2 changes: 1 addition & 1 deletion bioptim/examples/track/track_segment_on_rt.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ def prepare_ocp(

# Constraints
constraints = ConstraintList()
constraints.add(ConstraintFcn.TRACK_SEGMENT_WITH_CUSTOM_RT, node=Node.ALL, segment="seg_rt", rt=0)
constraints.add(ConstraintFcn.TRACK_SEGMENT_WITH_CUSTOM_RT, node=Node.ALL, segment="seg_rt", rt_idx=0)

# Path constraint
x_bounds = BoundsList()
Expand Down
Loading

0 comments on commit 08e2007

Please sign in to comment.