Skip to content

Commit

Permalink
Merge pull request #881 from EveCharbie/removing_mx_reduced
Browse files Browse the repository at this point in the history
Removing mx_reduced by creating  "biorbd wrapper"
  • Loading branch information
pariterre authored Nov 8, 2024
2 parents 4c44763 + 1cdaf8e commit f1c8b2e
Show file tree
Hide file tree
Showing 88 changed files with 4,530 additions and 6,115 deletions.
3 changes: 0 additions & 3 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -86,9 +86,6 @@ venv.bak/
# pycharm
.idea

# Personnal stuff
Misc/

# Remove symbolic links to bioptim in examples and tests folder
examples/*/biorbd_optim
examples/biorbd_optim
Expand Down
27 changes: 6 additions & 21 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,6 @@ As a tour guide that uses this binder, you can watch the `bioptim` workshop that
- [CostType](#enum-costtype)
- [SolutionIntegrator](#enum-solutionintegrator)
- [QuadratureRule](#enum-quadraturerule)
- [RigidBodyDynamics](#enum-rigidbodydynamics)
- [SoftContactDynamics](#enum-softcontactdynamics)
- [DefectType](#enum-defecttype)

Expand Down Expand Up @@ -1227,11 +1226,11 @@ This constraint assumes that the normal forces is positive (that is having an ad
- **TRACK_COM_VELOCITY** — Constraints the center of mass velocity toward a target. The extra parameter `axis_to_track: Axis = (Axis.X, Axis.Y, Axis.Z)` can be provided to specify the axes along which the velocity should be tracked.
- **TRACK_CONTACT_FORCES** — Tracks the non-acceleration point reaction forces toward a target.
- **TRACK_LINEAR_MOMENTUM** — Constraints the linear momentum toward a target. The extra parameter `axis_to_track: Axis = (Axis.X, Axis.Y, Axis.Z)` can be sent to specify the axes along which the momentum should be tracked.
- **TRACK_MARKER_WITH_SEGMENT_AXIS** — Tracks a marker using a segment, that is aligning an axis toward the marker. The extra parameters `marker_idx: int`, `segment_idx: int`, and `axis: Axis` must be passed to the `Constraint` constructor
- **TRACK_MARKER_WITH_SEGMENT_AXIS** — Tracks a marker using a segment, that is aligning an axis toward the marker. The extra parameters `marker_idx: int`, `segment_index: int`, and `axis: Axis` must be passed to the `Constraint` constructor
- **TRACK_MARKERS_VELOCITY** — Tracks the skin marker velocities toward a target.
- **TRACK_MARKERS** — Tracks the skin markers toward a target. The extra parameter `axis_to_track: Axis = (Axis.X, Axis.Y, Axis.Z)` can be provided to specify the axes along which the markers should be tracked.
- **TRACK_MUSCLES_CONTROL** — Tracks the muscles (part of the control variables) toward a target.
- **TRACK_SEGMENT_WITH_CUSTOM_RT** —Links a segment with an RT (for instance, an Inertial Measurement Unit). It does so by computing the homogenous transformation between the segment and the RT and then converting this to Euler angles. The extra parameters `segment_idx: int` and `rt_idx: int` must be passed to the `Constraint` constructor.
- **TRACK_SEGMENT_WITH_CUSTOM_RT** —Links a segment with an RT (for instance, an Inertial Measurement Unit). It does so by computing the homogenous transformation between the segment and the RT and then converting this to Euler angles. The extra parameters `segment_index: int` and `rt_index: int` must be passed to the `Constraint` constructor.
- **TRACK_STATE** — Tracks the state's variable toward a target.
- **TRACK_TORQUE** — Tracks the generalized forces (part of the control variables) toward a target.
- **CUSTOM** — The user should not directly send CUSTOM, but the user should pass the custom_constraint function directly. You can look at Constraint and ConstraintList sections for more information about how to define custom constraints.
Expand Down Expand Up @@ -1323,11 +1322,11 @@ Here a list of objective function with its type (Lagrange and/or Mayer) in alpha
- **SUPERIMPOSE_MARKERS** (Lagrange and Mayer) — Tracks one marker with another one. The extra parameters `first_marker_idx: int` and `second_marker_idx: int` informs which markers are to be superimposed
- **TRACK_ALL_CONTROLS (Lagrange)** — Tracks all the control variables toward a target.
- **TRACK_CONTACT_FORCES** (Lagrange) — Tracks the non-acceleration points of the reaction forces toward a target.
- **TRACK_MARKER_WITH_SEGMENT_AXIS** (Lagrange and Mayer) — Minimizes the distance between a marker and an axis of a segment, that is aligning an axis toward the marker. The extra parameters `marker_idx: int`, `segment_idx: int` and `axis: Axis` must be passed to the `Objective` constructor
- **TRACK_MARKER_WITH_SEGMENT_AXIS** (Lagrange and Mayer) — Minimizes the distance between a marker and an axis of a segment, that is aligning an axis toward the marker. The extra parameters `marker_idx: int`, `segment_index: int` and `axis: Axis` must be passed to the `Objective` constructor
- **TRACK_MARKERS_VELOCITY or TRACK_MARKERS_ACCELERATION** (Lagrange and Mayer) — Tracks the marker velocities or accelerations toward a target.
- **TRACK_MARKERS** (Lagrange and Mayer) — Tracks the skin markers towards a target. The extra parameter `axis_to_track: Axis = (Axis.X, Axis.Y, Axis.Z)` can be sent to specify the axes along which the markers should be tracked.
- **TRACK_MUSCLES_CONTROL** (Lagrange) — Tracks the muscles' controls (part of the control variables) toward a target.
- **TRACK_SEGMENT_WITH_CUSTOM_RT** (Lagrange and Mayer) — Minimizes the distance between a segment and an RT (for instance, an Inertial Measurement Unit). It does so by computing the homogenous transformation between the segment and the RT and then converting this to Euler angles. The extra parameters `segment_idx: int` and `rt_idx: int` must be passed to the `Objective` constructor.
- **TRACK_SEGMENT_WITH_CUSTOM_RT** (Lagrange and Mayer) — Minimizes the distance between a segment and an RT (for instance, an Inertial Measurement Unit). It does so by computing the homogenous transformation between the segment and the RT and then converting this to Euler angles. The extra parameters `segment_index: int` and `rt_index: int` must be passed to the `Objective` constructor.
- **TRACK_SOFT_CONTACT_FORCES** (Lagrange) — Tracks the external forces induced by soft contacts toward a target.
- **TRACK_STATE** (Lagrange and Mayer) — Tracks the state variable toward a target.
- **TRACK_TORQUE** (Lagrange — Tracks the generalized forces (part of the control variables) toward a target.
Expand Down Expand Up @@ -1747,14 +1746,6 @@ The type of integration used to integrate the cost function terms of Lagrange:
- APPROXIMATE_TRAPEZOIDAL: The integral is approximated by a trapezoidal rule using the state at the beginning of the next interval.
- TRAPEZOIDAL: The integral is approximated by a trapezoidal rule using the state at the end of the current interval.

### Enum: RigidBodyDynamics
The type of transcription of any dynamics (e.g., rigidbody_dynamics or soft_contact_dynamics):
- ODE: the dynamics is handled explicitly in the continuity constraint of the ordinary differential equation of the Direct Multiple Shooting approach.
- DAE_INVERSE_DYNAMICS: it adds an extra control *qddot* to respect inverse dynamics on nodes; this is a DAE-constrained OCP.
- DAE_FORWARD_DYNAMICS: it adds an extra control *qddot* to respect forward dynamics on nodes; this is a DAE-constrained OCP.
- DAE_INVERSE_DYNAMICS_JERK: it adds an extra control *qdddot* and an extra state *qddot* to respect inverse dynamics on nodes; this is a DAE-constrained OCP.
- DAE_FORWARD_DYNAMICS_JERK: it adds an extra control *qdddot* and an extra state *qddot* to respect forward dynamics on nodes; this is a DAE-constrained OCP.

### Enum: SoftContactDynamics
The type of transcription of any dynamics (e.g., rigidbody_dynamics or soft_contact_dynamics):
- ODE: soft contact dynamics is handled explicitly.
Expand Down Expand Up @@ -1911,9 +1902,6 @@ example, a spring) can be found at 'examples/torque_driven_ocp/spring_load.py'
`Bioptim` expects `external_forces` to be a np.ndarray [6 x n x n_shooting], where the six components are
[Mx, My, Mz, Fx, Fy, Fz], expressed at the origin of the global reference frame for each node.

### The [example_implicit_dynamics.py](./bioptim/examples/getting_started/example_implicit_dynamics.py) file
*#TODO*

### The [example_inequality_constraint.py](./bioptim/examples/getting_started/example_inequality_constraint.py) file
This example mimics what a jumper does when maximizing the predicted height of the center of mass at the peak of an aerial phase. It does so with a simplistic two segments model.
It is a clone of 'torque_driven_ocp/maximize_predicted_height_CoM.py' using
Expand Down Expand Up @@ -2367,7 +2355,7 @@ definition of the constraints of the problem:
```python
constraints = ConstraintList()
constraints.add(
ConstraintFcn.TRACK_MARKER_WITH_SEGMENT_AXIS, node=Node.ALL, marker_idx=1, segment_idx=2, axis=Axis.X
ConstraintFcn.TRACK_MARKER_WITH_SEGMENT_AXIS, node=Node.ALL, marker_idx=1, segment_index=2, axis=Axis.X
)
```

Expand All @@ -2381,12 +2369,9 @@ the rest is fully optimized. It is designed to show how to use the tracking RT f
any RT (for instance, Inertial Measurement Unit [IMU]) with a body segment.

To implement this tracking task, we use the `ConstraintFcn.TRACK_SEGMENT_WITH_CUSTOM_RT` constraint function, which
minimizes the distance between a segment and an RT. The extra parameters `segment_idx: int` and `rt_idx: int` must be
minimizes the distance between a segment and an RT. The extra parameters `segment_index: int` and `rt_index: int` must be
passed to the Objective constructor.

### The [track_vector_orientation.py](./bioptim/examples/track/track_vector_orientation.py) file
*#TODO*

## Moving estimation horizon (MHE)
In this section, we perform MHE on the pendulum example.

Expand Down
71 changes: 46 additions & 25 deletions bioptim/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -164,33 +164,50 @@
"""

from .misc.__version__ import __version__
from .dynamics.configure_problem import ConfigureProblem, DynamicsFcn, DynamicsList, Dynamics
from .dynamics.dynamics_functions import DynamicsFunctions
from .dynamics.configure_problem import ConfigureProblem, DynamicsFcn, DynamicsList, Dynamics
from .dynamics.dynamics_evaluation import DynamicsEvaluation
from .dynamics.dynamics_evaluation import DynamicsEvaluation
from .dynamics.dynamics_functions import DynamicsFunctions
from .dynamics.dynamics_functions import DynamicsFunctions
from .dynamics.fatigue.effort_perception import EffortPerception, TauEffortPerception
from .dynamics.fatigue.effort_perception import EffortPerception, TauEffortPerception
from .dynamics.fatigue.fatigue_dynamics import FatigueList
from .dynamics.fatigue.fatigue_dynamics import FatigueList
from .dynamics.fatigue.xia_fatigue import XiaFatigue, XiaTauFatigue, XiaFatigueStabilized
from .dynamics.fatigue.michaud_fatigue import MichaudFatigue, MichaudTauFatigue
from .dynamics.fatigue.effort_perception import EffortPerception, TauEffortPerception
from .dynamics.fatigue.michaud_fatigue import MichaudFatigue, MichaudTauFatigue
from .dynamics.fatigue.xia_fatigue import XiaFatigue, XiaTauFatigue, XiaFatigueStabilized
from .dynamics.fatigue.xia_fatigue import XiaFatigue, XiaTauFatigue, XiaFatigueStabilized
from .dynamics.ode_solver import OdeSolver, OdeSolverBase
from .dynamics.ode_solver import OdeSolver, OdeSolverBase
from .gui.online_callback_server import PlottingServer
from .gui.online_callback_server import PlottingServer
from .gui.plot import CustomPlot
from .gui.plot import CustomPlot
from .interfaces import Solver
from .interfaces import Solver
from .models.biorbd.biorbd_model import BiorbdModel
from .models.biorbd.multi_biorbd_model import MultiBiorbdModel
from .models.biorbd.holonomic_biorbd_model import HolonomicBiorbdModel
from .models.biorbd.variational_biorbd_model import VariationalBiorbdModel
from .models.biorbd.stochastic_biorbd_model import StochasticBiorbdModel
from .models.holonomic_constraints import HolonomicConstraintsFcn, HolonomicConstraintsList
from .models.protocols.stochastic_biomodel import StochasticBioModel
from .models.protocols.biomodel import BioModel
from .limits.constraints import ConstraintFcn, ConstraintList, Constraint, ParameterConstraintList
from .limits.phase_transition import PhaseTransitionFcn, PhaseTransitionList, PhaseTransition
from .limits.constraints import ConstraintFcn, ConstraintList, Constraint, ParameterConstraintList
from .limits.fatigue_path_conditions import FatigueBounds, FatigueInitialGuess
from .limits.fatigue_path_conditions import FatigueBounds, FatigueInitialGuess
from .limits.multinode_constraint import MultinodeConstraintFcn, MultinodeConstraintList, MultinodeConstraint
from .limits.multinode_constraint import MultinodeConstraintFcn, MultinodeConstraintList, MultinodeConstraint
from .limits.multinode_objective import MultinodeObjectiveFcn, MultinodeObjectiveList, MultinodeObjective
from .limits.multinode_objective import MultinodeObjectiveFcn, MultinodeObjectiveList, MultinodeObjective
from .limits.objective_functions import ObjectiveFcn, ObjectiveList, Objective, ParameterObjectiveList
from .limits.objective_functions import ObjectiveFcn, ObjectiveList, Objective, ParameterObjectiveList
from .limits.path_conditions import BoundsList, InitialGuessList, Bounds, InitialGuess
from .limits.fatigue_path_conditions import FatigueBounds, FatigueInitialGuess
from .limits.path_conditions import BoundsList, InitialGuessList, Bounds, InitialGuess
from .limits.penalty_controller import PenaltyController
from .limits.penalty_controller import PenaltyController
from .limits.penalty_helpers import PenaltyHelpers
from .limits.penalty_helpers import PenaltyHelpers
from .limits.phase_transition import PhaseTransitionFcn, PhaseTransitionList, PhaseTransition
from .limits.phase_transition import PhaseTransitionFcn, PhaseTransitionList, PhaseTransition
from .misc.__version__ import __version__
from .misc.__version__ import __version__
from .misc.casadi_expand import lt, le, gt, ge, if_else, if_else_zero
from .misc.casadi_expand import lt, le, gt, ge, if_else, if_else_zero
from .misc.enums import (
Axis,
Node,
Expand All @@ -202,7 +219,6 @@
VariableType,
SolutionIntegrator,
QuadratureRule,
RigidBodyDynamics,
SoftContactDynamics,
DefectType,
MagnitudeType,
Expand All @@ -211,25 +227,30 @@
OnlineOptim,
)
from .misc.mapping import BiMappingList, BiMapping, Mapping, NodeMapping, NodeMappingList, SelectionMapping, Dependency
from .misc.mapping import BiMappingList, BiMapping, Mapping, NodeMapping, NodeMappingList, SelectionMapping, Dependency
from .models.biorbd.biorbd_model import BiorbdModel
from .models.biorbd.external_forces import ExternalForceSetTimeSeries
from .models.biorbd.holonomic_biorbd_model import HolonomicBiorbdModel
from .models.biorbd.multi_biorbd_model import MultiBiorbdModel
from .models.biorbd.stochastic_biorbd_model import StochasticBiorbdModel
from .models.biorbd.variational_biorbd_model import VariationalBiorbdModel
from .models.holonomic_constraints import HolonomicConstraintsFcn, HolonomicConstraintsList
from .models.protocols.biomodel import BioModel
from .models.protocols.stochastic_biomodel import StochasticBioModel
from .optimization.multi_start import MultiStart
from .optimization.non_linear_program import NonLinearProgram
from .optimization.optimal_control_program import OptimalControlProgram
from .optimization.receding_horizon_optimization import MovingHorizonEstimator, NonlinearModelPredictiveControl
from .optimization.optimization_variable import OptimizationVariableList
from .optimization.parameters import ParameterList, ParameterContainer
from .optimization.problem_type import SocpType
from .optimization.receding_horizon_optimization import (
CyclicNonlinearModelPredictiveControl,
CyclicMovingHorizonEstimator,
MultiCyclicNonlinearModelPredictiveControl,
)
from .optimization.parameters import ParameterList, ParameterContainer
from .optimization.receding_horizon_optimization import MovingHorizonEstimator, NonlinearModelPredictiveControl
from .optimization.solution.solution import Solution
from .optimization.solution.solution_data import SolutionMerge, TimeAlignment
from .optimization.optimization_variable import OptimizationVariableList
from .optimization.stochastic_optimal_control_program import StochasticOptimalControlProgram
from .optimization.variable_scaling import VariableScalingList, VariableScaling
from .optimization.variational_optimal_control_program import VariationalOptimalControlProgram

from .optimization.stochastic_optimal_control_program import StochasticOptimalControlProgram
from .optimization.problem_type import SocpType
from .misc.casadi_expand import lt, le, gt, ge, if_else, if_else_zero

from .gui.plot import CustomPlot
from .gui.online_callback_server import PlottingServer
Loading

0 comments on commit f1c8b2e

Please sign in to comment.