OpenSim Moco  0.1.0-preprint
Solve optimal control problems with OpenSim models
Classes | Typedefs | Enumerations | Functions
OpenSim Namespace Reference

The Moco interface is contained within the OpenSim namespace. More...

Classes

class  AccelerationMotion
 This class is a thin wrapper to Simbody's SimTK::Motion for prescribing the acceleration of all degrees of freedom (UDot), and is used when enforcing dynamics using implicit differential equations (UDot is supplied by the solver, not by Simbody). More...
 
class  AckermannVanDenBogert2010Force
 This class is still under development. More...
 
class  ActivationCoordinateActuator
 Similar to CoordinateActuator (simply produces a generalized force) but with first-order linear activation dynamics. More...
 
class  DeGrooteFregly2016Muscle
 This muscle model was published in De Groote et al. More...
 
class  DiscreteForces
 This class is a thin wrapper to Simbody's SimTK::Force::DiscreteForces class. More...
 
class  EspositoMiller2018Force
 This contact model uses a continuous equation to transition between in and out of contact. More...
 
class  FileDeletionThrower
 This class helps a user cause an exception within the code. More...
 
class  FileDeletionThrowerException
 Thrown by FileDeletionThrower::throwIfDeleted(). More...
 
struct  make_printable_return
 Return type for make_printable() More...
 
struct  make_printable_return< std::string >
 Specialization for std::string. More...
 
class  MeyerFregly2016Force
 This contact model is from the following paper: Meyer A. More...
 
class  MocoAverageSpeedGoal
 This goal requires the average speed of the system to match a desired average speed. More...
 
class  MocoBounds
 Small struct to handle bounds. More...
 
class  MocoCasADiSolver
 This solver uses the CasADi library (https://casadi.org) to convert the MocoProblem into a generic nonlinear programming problem. More...
 
class  MocoCasOCProblem
 This class is the bridge between CasOC::Problem and MocoProblemRep. More...
 
class  MocoConstraintInfo
 Information for a given constraint in the optimal control problem. More...
 
class  MocoControlBoundConstraint
 This class constrains any number of control signals from ScalarActautors to be between two time-based functions. More...
 
class  MocoControlGoal
 Minimize the sum of the absolute value of the controls raised to a given exponent, integrated over the phase. More...
 
class  MocoControlTrackingGoal
 The squared difference between a control variable value and a reference control variable value, summed over the control variables for which a reference is provided, and integrated over the phase. More...
 
class  MocoDirectCollocationSolver
 This is a base class for solvers that use direct collocation to convert an optimal control problem into a generic nonlinear programming problem. More...
 
class  MocoFinalBounds
 Used for specifying the bounds on a variable at the end of a phase. More...
 
class  MocoFinalTimeGoal
 Endpoint cost for final time. More...
 
class  MocoGoal
 A goal is term in the cost functional to be minimized, or a set of endpoint constraints that must lie within provided bounds. More...
 
class  MocoInitialActivationGoal
 For all muscles with activation dynamics, the initial activation and initial excitation should be the same. More...
 
class  MocoInitialBounds
 Used for specifying the bounds on a variable at the start of a phase. More...
 
class  MocoInitialForceEquilibriumGoal
 For all Muscle components with explicit tendon compliance dynamics, constrain (or minimize) the error computed from the muscle-tendon force equilibrium equation. More...
 
class  MocoInitialVelocityEquilibriumDGFGoal
 For DeGrooteFregly2016Muscle components with implicit tendon compliance dynamics, the initial tendon and fiber velocities are determined based the derivative of the linearized muscle-tendon equilibrium equation described in Millard et al. More...
 
class  MocoInverse
 This tool solves problems in which the kinematics are prescribed and you seek the actuator (e.g., muscle) behavior that may have given rise to the provided kinematics. More...
 
class  MocoInverseSolution
 This class holds the solution from MocoInverse. More...
 
class  MocoJointReactionGoal
 Minimize the sum of squares of specified reaction moment and force measures for a given joint, integrated over the phase. More...
 
class  MocoKinematicConstraint
 A model kinematic constraint to be enforced in the optimal control problem. More...
 
class  MocoMarkerFinalGoal
 The squared distance between a single model point location and reference location in the final state. More...
 
class  MocoMarkerTrackingGoal
 The squared difference between a model marker location and an experimental reference marker location, summed over the markers for which an experimental data location is provided, and integrated over the phase. More...
 
class  MocoOrientationTrackingGoal
 The squared difference between a model frame's orientation and a reference orientation value, summed over the frames for which a reference is provided, and integrated over the phase. More...
 
class  MocoParameter
 A MocoParameter allows you to optimize property values in an OpenSim Model. More...
 
class  MocoPathConstraint
 A path constraint to be enforced in the optimal control problem. More...
 
class  MocoPeriodicityGoal
 This goal enforces equality between initial and final variable values in the optimal control problem. More...
 
class  MocoPeriodicityGoalPair
 Create pair of variables for use with a MocoPeriodicityGoal. More...
 
class  MocoPhase
 The states, controls, dynamics, parameters, goals, and constraints for a phase of the problem. More...
 
class  MocoProblem
 A description of an optimal control problem, backed by OpenSim Models. More...
 
class  MocoProblemInfo
 This class is mostly for internal use for MocoProblemRep to pass select information about a problem to the MocoGoals and MocoPathConstraints of the problem during initializeOnModel(). More...
 
class  MocoProblemRep
 The primary intent of this class is for use by MocoSolvers, but users can also use this class to apply parameter values to the model and evaluate cost terms. More...
 
class  MocoSolution
 Return type for MocoStudy::solve(). More...
 
class  MocoSolver
 Once the solver is created, you should not make any edits to the MocoProblem. More...
 
class  MocoStateTrackingGoal
 The squared difference between a state variable value and a reference state variable value, summed over the state variables for which a reference is provided, and integrated over the phase. More...
 
class  MocoStudy
 The top-level class for solving a custom optimal control problem. More...
 
class  MocoSumSquaredStateGoal
 Minimize the sum of squared states, integrated over the phase. More...
 
class  MocoTool
 This is a base class for solving problems that depend on an observed motion using Moco's optimal control methods. More...
 
class  MocoTrack
 
class  MocoTrajectory
 The values of the variables in an optimal control problem. More...
 
class  MocoTrajectoryIsSealed
 This exception is thrown if you try to invoke most methods on MocoTrajectory while the iterate is sealed. More...
 
class  MocoTranslationTrackingGoal
 The squared difference between a model frame's origin position and a reference position value, summed over the frames for which a reference is provided, and integrated over the phase. More...
 
class  MocoTropterSolver
 Solve the MocoProblem using the tropter direct collocation library. More...
 
class  MocoTropterSolverNotAvailable
 
class  MocoVariableInfo
 Bounds on continuous variables (states, controls, multipliers, etc). More...
 
class  MocoWeight
 This class contains a single property that holds a weighting factor to be used in a MocoGoal. More...
 
class  MocoWeightSet
 A container for Moco weights. More...
 
class  ModelFactory
 This class provides utilities for creating OpenSim models. More...
 
class  ModelOperator
 This abstract base class describes any operation that modifies a Model as part of a ModelProcessor. More...
 
class  ModelProcessor
 This class describes a workflow for processing a Model using ModelOperators. More...
 
class  ModOpAddExternalLoads
 Add external loads (e.g., ground reaction forces) to the model from a XML file. More...
 
class  ModOpAddReserves
 Add reserve actuators to the model using ModelFactory::createReserveActuators. More...
 
class  ModOpIgnoreActivationDynamics
 Turn off activation dynamics for all muscles in the model. More...
 
class  ModOpIgnorePassiveFiberForcesDGF
 Turn off passive fiber forces for all DeGrooteFregly2016Muscles in the model. More...
 
class  ModOpIgnoreTendonCompliance
 Turn off tendon compliance for all muscles in the model. More...
 
class  ModOpRemoveMuscles
 Remove all muscles contained in the model's ForceSet. More...
 
class  ModOpReplaceJointsWithWelds
 
class  ModOpReplaceMusclesWithDeGrooteFregly2016
 Invoke DeGrooteFregly2016Muscle::replaceMuscles() on the model. More...
 
class  ModOpScaleActiveFiberForceCurveWidthDGF
 Scale the active fiber force curve width for all DeGrooteFregly2016Muscles in the model. More...
 
class  ModOpScaleMaxIsometricForce
 Scale the max isometric force for all muscles in the model. More...
 
class  ModOpSetPathLengthApproximation
 Turn on or off path length approximation for all GeometryPath components in the model. More...
 
class  ModOpTendonComplianceDynamicsModeDGF
 For DeGrooteFregly2016Muscle muscles whose 'ignore_tendon_compliance' property is false, set the tendon compliance dynamics mode to either 'explicit' or 'implicit'. More...
 
class  ModOpUseImplicitTendonComplianceDynamicsDGF
 Turn off passive fiber forces for all DeGrooteFregly2016Muscles in the model. More...
 
class  MultivariatePolynomialFunction
 
class  PositionMotion
 This class prescribes the value, speed, and acceleration of all coordinates in the model using SimTK::Motion. More...
 
class  SimTKMultivariatePolynomial
 
class  SmoothSphereHalfSpaceForce
 
class  StationPlaneContactForce
 This class models compliant point contact with a ground plane y=0. More...
 
class  Stopwatch
 Record and report elapsed real time ("clock" or "wall" time) in seconds. More...
 
class  StreamFormat
 This class stores the formatting of a stream and restores that format when the StreamFormat is destructed. More...
 
class  TableOperator
 This abstract class describes any operation that consumes a modifies a TimeSeriesTable as part of a TableProcessor. More...
 
class  TableProcessor
 This class describes a workflow for processing a table using TableOperators. More...
 
class  TabOpLowPassFilter
 Apply a low-pass filter to the trajectory. More...
 
class  TabOpUseAbsoluteStateNames
 Update table column labels to use post-4.0 state paths instead of pre-4.0 state names. More...
 
class  ThreadsafeJar
 This class lets you store objects of a single type for reuse by multiple threads, ensuring threadsafe access to each of those objects. More...
 

Typedefs

using VectorDM = std::vector< casadi::DM >
 

Enumerations

enum  KinematicLevel {
  Position, DtPosition, Velocity, DtDtPosition,
  DtVelocity, Acceleration
}
 The kinematic level for a scalar kinematic constraint within a MocoKinematicConstraint. More...
 

Functions

OSIMMOCO_API std::string GetMocoVersionAndDate ()
 
OSIMMOCO_API std::string GetMocoVersion ()
 
CasOC::Bounds convertBounds (const MocoBounds &mb)
 
CasOC::Bounds convertBounds (const MocoInitialBounds &mb)
 
CasOC::Bounds convertBounds (const MocoFinalBounds &mb)
 
casadi::DM convertToCasADiDMTranspose (const SimTK::Matrix &simtkMatrix)
 This converts a SimTK::Matrix to a casadi::DM matrix, transposing the data in the process.
 
template<typename T >
casadi::DM convertToCasADiDMTemplate (const T &simtk)
 
casadi::DM convertToCasADiDMTranspose (const SimTK::RowVector &simtkRV)
 This converts a SimTK::RowVector to a casadi::DM column vector.
 
casadi::DM convertToCasADiDM (const SimTK::Vector &simtkVec)
 This converts a SimTK::Vector to a casadi::DM column vector.
 
CasOC::Iterate convertToCasOCIterate (const MocoTrajectory &mocoIt)
 This resamples the iterate to obtain values that lie on the mesh.
 
template<typename VectorType = SimTK::Vector>
VectorType convertToSimTKVector (const casadi::DM &casVector)
 
SimTK::Matrix convertToSimTKMatrix (const casadi::DM &casMatrix)
 This converts a casadi::DM matrix to a SimTK::Matrix, transposing the data in the process.
 
template<typename TOut = MocoTrajectory>
TOut convertToMocoTrajectory (const CasOC::Iterate &casIt)
 
template<typename T , typename... Args>
std::unique_ptr< T > make_unique (Args &&... args)
 Since Moco does not require C++14 (which contains std::make_unique()), here is an implementation of make_unique().
 
OSIMMOCO_API std::string getFormattedDateTime (bool appendMicroseconds=false, std::string format="%Y-%m-%dT%H%M%S")
 Get a string with the current date and time formatted as Y-m-dTHMS (year, month, day, "T", hour, minute, second). More...
 
bool startsWith (const std::string &string, const std::string &start)
 Determine if string starts with the substring start. More...
 
bool endsWith (const std::string &string, const std::string &ending)
 Determine if string ends with the substring ending. More...
 
OSIMMOCO_API SimTK::Vector createVectorLinspace (int length, double start, double end)
 Create a SimTK::Vector with the provided length whose elements are linearly spaced between start and end.
 
OSIMMOCO_API SimTK::Vector createVector (std::initializer_list< SimTK::Real > elements)
 Create a SimTK::Vector using modern C++ syntax.
 
OSIMMOCO_API SimTK::Vector interpolate (const SimTK::Vector &x, const SimTK::Vector &y, const SimTK::Vector &newX, const bool ignoreNaNs=false)
 Linearly interpolate y(x) at new values of x. More...
 
template<typename FunctionType >
std::unique_ptr< FunctionSet > createFunctionSet (const TimeSeriesTable &table)
 
template<>
std::unique_ptr< FunctionSet > createFunctionSet< GCVSpline > (const TimeSeriesTable &table)
 
template<typename TimeVector , typename FunctionType = GCVSpline>
TimeSeriesTable resample (const TimeSeriesTable &in, const TimeVector &newTime)
 Resample (interpolate) the table at the provided times. More...
 
OSIMMOCO_API Storage convertTableToStorage (const TimeSeriesTable &)
 Create a Storage from a TimeSeriesTable. More...
 
OSIMMOCO_API TimeSeriesTable filterLowpass (const TimeSeriesTable &table, double cutoffFreq, bool padData=false)
 Lowpass filter the data in a TimeSeriesTable at a provided cutoff frequency. More...
 
template<typename T >
TimeSeriesTable_< T > readTableFromFileT (const std::string &filepath)
 Read in a table of type TimeSeriesTable_<T> from file, where T is the type of the elements contained in the table's columns. More...
 
OSIMMOCO_API TimeSeriesTable readTableFromFile (const std::string &filepath)
 Read in a TimeSeriesTable from file containing scalar elements. More...
 
OSIMMOCO_API void writeTableToFile (const TimeSeriesTable &, const std::string &)
 Write a single TimeSeriesTable to a file, using the FileAdapter associated with the provided file extension.
 
OSIMMOCO_API void visualize (Model, Storage)
 Play back a motion (from the Storage) in the simbody-visuailzer. More...
 
OSIMMOCO_API void visualize (Model, TimeSeriesTable)
 This function is the same as visualize(Model, Storage), except that the states are provided in a TimeSeriesTable.
 
template<typename T >
TimeSeriesTable_< T > analyze (Model model, const MocoTrajectory &iterate, std::vector< std::string > outputPaths)
 Calculate the requested outputs using the model in the problem and the states and controls in the MocoTrajectory. More...
 
OSIMMOCO_API void prescribeControlsToModel (const MocoTrajectory &iterate, Model &model, std::string functionType="GCVSpline")
 Given a MocoTrajectory and the associated OpenSim model, return the model with a prescribed controller appended that will compute the control values from the MocoSolution. More...
 
OSIMMOCO_API MocoTrajectory simulateIterateWithTimeStepping (const MocoTrajectory &iterate, Model model, double integratorAccuracy=-1)
 Use the controls and initial state in the provided iterate to simulate the model using an ODE time stepping integrator (OpenSim::Manager), and return the resulting states and controls. More...
 
OSIMMOCO_API std::vector< std::string > createStateVariableNamesInSystemOrder (const Model &model)
 The map provides the index of each state variable in SimTK::State::getY() from its each state variable path string. More...
 
OSIMMOCO_API std::vector< std::string > createStateVariableNamesInSystemOrder (const Model &model, std::unordered_map< int, int > &yIndexMap)
 Same as above, but you can obtain a map from the returned state variable names to the index in SimTK::State::getY() that accounts for empty slots in Y.
 
OSIMMOCO_API std::unordered_map< std::string, int > createSystemYIndexMap (const Model &model)
 The map provides the index of each state variable in SimTK::State::getY() from its state variable path string.
 
OSIMMOCO_API std::vector< std::string > createControlNamesFromModel (const Model &model, std::vector< int > &modelControlIndices)
 Create a vector of control names based on the actuators in the model for which appliesForce == True. More...
 
OSIMMOCO_API std::vector< std::string > createControlNamesFromModel (const Model &model)
 Same as above, but when there is no mapping to the modelControlIndices.
 
OSIMMOCO_API std::unordered_map< std::string, int > createSystemControlIndexMap (const Model &model)
 The map provides the index of each control variable in the SimTK::Vector return by OpenSim::Model::getControls() from its control name.
 
OSIMMOCO_API void checkOrderSystemControls (const Model &model)
 Throws an exception if the order of the controls in the model is not the same as the order of the actuators in the model.
 
OSIMMOCO_API void checkRedundantLabels (std::vector< std::string > labels)
 Throws an exception if the same label appears twice in the list of labels. More...
 
template<typename T = double>
std::vector< SimTK::ReferencePtr< const Output< T > > > getModelOutputReferencePtrs (const Component &component, const std::string &pattern, bool includeDescendents=false)
 Get a list of reference pointers to all outputs whose names (not paths) match a substring defined by a provided regex string pattern. More...
 
OSIMMOCO_API MocoTrajectory createPeriodicTrajectory (const MocoTrajectory &halfPeriodTrajectory, std::vector< std::string > addPatterns={".*pelvis_tx/value"}, std::vector< std::string > negatePatterns={".*pelvis_list.*", ".*pelvis_rotation.*", ".*pelvis_tz.*"}, std::vector< std::pair< std::string, std::string >> symmetryPatterns={{R"(_r(\/|$))", "_l$1"}, {R"(_l(\/|$))", "_r$1"}})
 Convert a trajectory covering half the period of a symmetric motion into a trajectory over the full period. More...
 
template<typename T >
void checkPropertyInSet (const Object &obj, const Property< T > &p, const std::set< T > &set)
 Throw an exception if the property's value is not in the provided set. More...
 
template<typename T >
void checkPropertyIsPositive (const Object &obj, const Property< T > &p)
 Throw an exception if the property's value is not positive. More...
 
template<typename T >
void checkPropertyInRangeOrSet (const Object &obj, const Property< T > &p, const T &lower, const T &upper, const std::set< T > &set)
 Throw an exception if the property's value is neither in the provided range nor in the provided set. More...
 
OSIMMOCO_API int getMocoParallelEnvironmentVariable ()
 This obtains the value of the OPENSIM_MOCO_PARALLEL environment variable. More...
 
OSIMMOCO_API TimeSeriesTable createExternalLoadsTableForGait (Model model, const MocoTrajectory &trajectory, const std::vector< std::string > &forceNamesRightFoot, const std::vector< std::string > &forceNamesLeftFoot)
 Obtain the ground reaction forces, centers of pressure, and torques resulting from Force elements (e.g., SmoothSphereHalfSpaceForce), using the model and the trajectory. More...
 
Filling in a string with variables.
template<typename T >
make_printable_return< T >::type make_printable (const T &x)
 Convert to types that can be printed with sprintf() (vsnprintf()). More...
 
template<>
make_printable_return< std::string >::type make_printable (const std::string &x)
 Specialization for std::string.
 
OSIMMOCO_API std::string format_c (const char *,...)
 Format a char array using (C interface; mainly for internal use).
 
template<typename... Types>
std::string format (const std::string &formatString, Types... args)
 Format a string in the style of sprintf. More...
 
template<typename... Types>
void printMessage (const std::string &formatString, Types... args)
 Print a formatted string to std::cout. More...
 

Detailed Description

The Moco interface is contained within the OpenSim namespace.

Enumeration Type Documentation

◆ KinematicLevel

The kinematic level for a scalar kinematic constraint within a MocoKinematicConstraint.

Each scalar constraint is automatically assigned a KinematicLevel enum value when a MocoKinematicConstraint is instantiated.

Function Documentation

◆ analyze()

template<typename T >
TimeSeriesTable_<T> OpenSim::analyze ( Model  model,
const MocoTrajectory iterate,
std::vector< std::string >  outputPaths 
)

Calculate the requested outputs using the model in the problem and the states and controls in the MocoTrajectory.

The output paths can be regular expressions. For example, ".*activation" gives the activation of all muscles. Constraints are not enforced but prescribed motion (e.g., PositionMotion) is. The output paths must correspond to outputs that match the type provided in the template argument, otherwise they are not included in the report.

Note
Parameters in the MocoTrajectory are not applied to the model.

◆ checkPropertyInRangeOrSet()

template<typename T >
void OpenSim::checkPropertyInRangeOrSet ( const Object &  obj,
const Property< T > &  p,
const T &  lower,
const T &  upper,
const std::set< T > &  set 
)

Throw an exception if the property's value is neither in the provided range nor in the provided set.

We assume that p is a single-value property.

◆ checkPropertyInSet()

template<typename T >
void OpenSim::checkPropertyInSet ( const Object &  obj,
const Property< T > &  p,
const std::set< T > &  set 
)

Throw an exception if the property's value is not in the provided set.

We assume that p is a single-value property.

◆ checkPropertyIsPositive()

template<typename T >
void OpenSim::checkPropertyIsPositive ( const Object &  obj,
const Property< T > &  p 
)

Throw an exception if the property's value is not positive.

We assume that p is a single-value property.

◆ checkRedundantLabels()

OSIMMOCO_API void OpenSim::checkRedundantLabels ( std::vector< std::string >  labels)

Throws an exception if the same label appears twice in the list of labels.

The argument copies the provided labels since we need to sort them to check for redundancies.

◆ convertTableToStorage()

OSIMMOCO_API Storage OpenSim::convertTableToStorage ( const TimeSeriesTable &  )

Create a Storage from a TimeSeriesTable.

Metadata from the TimeSeriesTable is not copied to the Storage. You should use TimeSeriesTable if possible, as support for Storage may be reduced in future versions of OpenSim. However, Storage supports some operations not supported by TimeSeriesTable (e.g., filtering, resampling).

◆ createControlNamesFromModel()

OSIMMOCO_API std::vector<std::string> OpenSim::createControlNamesFromModel ( const Model &  model,
std::vector< int > &  modelControlIndices 
)

Create a vector of control names based on the actuators in the model for which appliesForce == True.

For actuators with one control (e.g. ScalarActuator) the control name is simply the actuator name. For actuators with multiple controls, each control name is the actuator name appended by the control index (e.g. "/actuator_0"); modelControlIndices has length equal to the number of controls associated with actuators that apply a force (appliesForce == True). Its elements are the indices of the controls in the Model::updControls() that are associated with actuators that apply a force.

◆ createExternalLoadsTableForGait()

OSIMMOCO_API TimeSeriesTable OpenSim::createExternalLoadsTableForGait ( Model  model,
const MocoTrajectory trajectory,
const std::vector< std::string > &  forceNamesRightFoot,
const std::vector< std::string > &  forceNamesLeftFoot 
)

Obtain the ground reaction forces, centers of pressure, and torques resulting from Force elements (e.g., SmoothSphereHalfSpaceForce), using the model and the trajectory.

Forces and torques are expressed in the ground frame with respect to the ground origin. Hence, the centers of pressure are at the origin. Names of Force elements should be provided separately for elements of the right and left feet. The output is a table formated for use with OpenSim tools; the labels of the columns distinguish between right ("<>_r") and left ("<>_l") forces, centers of pressure, and torques. The forces and torques used are taken from the first six outputs of getRecordValues(); this order is of use for, for example, the SmoothSphereHalfSpaceForce contact model but might have a different meaning for different contact models.

Examples
example2DWalking.cpp.

◆ createPeriodicTrajectory()

OSIMMOCO_API MocoTrajectory OpenSim::createPeriodicTrajectory ( const MocoTrajectory halfPeriodTrajectory,
std::vector< std::string >  addPatterns = {".*pelvis_tx/value"},
std::vector< std::string >  negatePatterns = {".*pelvis_list.*", ".*pelvis_rotation.*", ".*pelvis_tz.*"},
std::vector< std::pair< std::string, std::string >>  symmetryPatterns = {{R"(_r(\/|$))", "_l$1"}, {R"(_l(\/|$))", "_r$1"}} 
)

Convert a trajectory covering half the period of a symmetric motion into a trajectory over the full period.

This is useful for simulations of half a gait cycle. This converts time, states, controls, and derivatives; all other quanties from the input trajectory are ignored. If a column in the trajectory does not match addPatterns, negatePatterns, or symmetryPatterns, then the second half of the period contains the same data as the first half.

Parameters
halfPeriodTrajectoryThe input trajectory covering half a period.
addPatternsIf a column label matches an addPattern, then the second half of the period for that column is (first_half_trajectory + half_period_value - initial_value).
negatePatternsIf a column label matches a negatePattern, then the second half of the period for that column is (-first_half_trajectory + 2 * half_period_value). This is usually relevant for only 3D models.
symmetryPatternsThis argument is a list of pairs, where the first element of the pair is a pattern to match, and the second is a substitution to convert the column label into the opposite column label of the symmetric pair. If a column label matches a symmetryPattern, then its first half-period is copied into the second half of the period for the column identified by the substitution.

The default values for the patterns are intended to handle the column labels for typical 2D or 3D OpenSim gait models. The default value for symmetryPatterns warrants an explanation. R"()" is a string literal that permits us to not escape backslash characters. The regex "_r(\/|$)" matches "_r" followed by either a forward slash (which is escaped) OR the end of the string ($). Since the forward slash and end of the string are within parentheses, whatever matches this is captured and is available in the substitution (the second element of the pair) as $1. The default symmetry patterns cause the following replacements:

  • "/jointset/hip_r/hip_flexion_r/value" becomes "/jointset/hip_l/hip_flexion_l/value"
  • "/forceset/soleus_r" becomes "/forceset/soleus_l"
Examples
example2DWalking.cpp.

◆ createStateVariableNamesInSystemOrder()

OSIMMOCO_API std::vector<std::string> OpenSim::createStateVariableNamesInSystemOrder ( const Model &  model)

The map provides the index of each state variable in SimTK::State::getY() from its each state variable path string.

Empty slots in Y (e.g., for quaternions) are ignored.

◆ endsWith()

bool OpenSim::endsWith ( const std::string &  string,
const std::string &  ending 
)
inline

◆ filterLowpass()

OSIMMOCO_API TimeSeriesTable OpenSim::filterLowpass ( const TimeSeriesTable &  table,
double  cutoffFreq,
bool  padData = false 
)

Lowpass filter the data in a TimeSeriesTable at a provided cutoff frequency.

The table is converted to a Storage object to use the lowpassIIR() method to filter, and then converted back to TimeSeriesTable.

◆ format()

template<typename... Types>
std::string OpenSim::format ( const std::string &  formatString,
Types...  args 
)

Format a string in the style of sprintf.

For example, the code format("%s %d and %d yields %d", "adding", 2, 2, 4) will produce "adding 2 and 2 yields 4".

Examples
exampleCustomImplicitAuxiliaryDynamics.cpp.

◆ getFormattedDateTime()

OSIMMOCO_API std::string OpenSim::getFormattedDateTime ( bool  appendMicroseconds = false,
std::string  format = "%Y-%m-%dT%H%M%S" 
)

Get a string with the current date and time formatted as Y-m-dTHMS (year, month, day, "T", hour, minute, second).

You can change the datetime format via the format parameter. If you specify "ISO", then we use the ISO 8601 extended datetime format Y-m-dTH:M:S. See https://en.cppreference.com/w/cpp/io/manip/put_time.

◆ getMocoParallelEnvironmentVariable()

OSIMMOCO_API int OpenSim::getMocoParallelEnvironmentVariable ( )

This obtains the value of the OPENSIM_MOCO_PARALLEL environment variable.

The value has the following meanings:

  • 0: run in series (not parallel).
  • 1: run in parallel using all cores.
  • greater than 1: run in parallel with this number of threads. If the environment variable is not set, this function returns -1.

This variable does not indicate which calculations are parallelized or how the parallelization is achieved. Moco may even ignore or override the setting from the environment variable. See documentation elsewhere (e.g., from a specific MocoSolver) for more information.

◆ getModelOutputReferencePtrs()

template<typename T = double>
std::vector<SimTK::ReferencePtr<const Output<T> > > OpenSim::getModelOutputReferencePtrs ( const Component &  component,
const std::string &  pattern,
bool  includeDescendents = false 
)

Get a list of reference pointers to all outputs whose names (not paths) match a substring defined by a provided regex string pattern.

The regex string pattern could be the full name of the output. Only Outputs that match the template argument type will be returned (double is the default type). Set the argument 'includeDescendents' to true to include outputs from all descendents from the provided component.

◆ interpolate()

OSIMMOCO_API SimTK::Vector OpenSim::interpolate ( const SimTK::Vector &  x,
const SimTK::Vector &  y,
const SimTK::Vector &  newX,
const bool  ignoreNaNs = false 
)

Linearly interpolate y(x) at new values of x.

The optional 'ignoreNaNs' argument will ignore any NaN values contained in the input vectors and create the interpolant from the non-NaN values only. Note that this option does not necessarily prevent NaN values from being returned in 'newX', which will have NaN for any values of newX outside of the range of x.

Exceptions
Exceptionif x and y are different sizes, or x or y is empty.

◆ make_printable()

template<typename T >
make_printable_return<T>::type OpenSim::make_printable ( const T &  x)
inline

Convert to types that can be printed with sprintf() (vsnprintf()).

The generic template does not alter the type.

◆ prescribeControlsToModel()

OSIMMOCO_API void OpenSim::prescribeControlsToModel ( const MocoTrajectory iterate,
Model &  model,
std::string  functionType = "GCVSpline" 
)

Given a MocoTrajectory and the associated OpenSim model, return the model with a prescribed controller appended that will compute the control values from the MocoSolution.

This can be useful when computing state-dependent model quantities that require realization to the Dynamics stage or later. The function used to fit the controls can either be GCVSpline or PiecewiseLinearFunction.

◆ printMessage()

template<typename... Types>
void OpenSim::printMessage ( const std::string &  formatString,
Types...  args 
)

Print a formatted string to std::cout.

A newline is not included, but the stream is flushed.

◆ readTableFromFile()

OSIMMOCO_API TimeSeriesTable OpenSim::readTableFromFile ( const std::string &  filepath)
inline

Read in a TimeSeriesTable from file containing scalar elements.

The filepath argument should refer to a STO or CSV file (or other file types for which there is a FileAdapter). This function assumes that only one table is contained in the file, and will throw an exception otherwise.

◆ readTableFromFileT()

template<typename T >
TimeSeriesTable_<T> OpenSim::readTableFromFileT ( const std::string &  filepath)

Read in a table of type TimeSeriesTable_<T> from file, where T is the type of the elements contained in the table's columns.

The filepath argument should refer to a STO or CSV file (or other file types for which there is a FileAdapter). This function assumes that only one table is contained in the file, and will throw an exception otherwise.

◆ resample()

template<typename TimeVector , typename FunctionType = GCVSpline>
TimeSeriesTable OpenSim::resample ( const TimeSeriesTable &  in,
const TimeVector &  newTime 
)

Resample (interpolate) the table at the provided times.

In general, a 5th-order GCVSpline is used as the interpolant; a lower order is used if the table has too few points for a 5th-order spline. Alternatively, you can provide a different function type as a template argument (e.g., PiecewiseLinearFunction).

Exceptions
Exceptionif new times are not within existing initial and final times, if the new times are decreasing, or if getNumTimes() < 2.

◆ simulateIterateWithTimeStepping()

OSIMMOCO_API MocoTrajectory OpenSim::simulateIterateWithTimeStepping ( const MocoTrajectory iterate,
Model  model,
double  integratorAccuracy = -1 
)

Use the controls and initial state in the provided iterate to simulate the model using an ODE time stepping integrator (OpenSim::Manager), and return the resulting states and controls.

We return a MocoTrajectory (rather than a StatesTrajectory) to facilitate comparing optimal control solutions with time stepping. Use integratorAccuracy to override the default setting.

◆ startsWith()

bool OpenSim::startsWith ( const std::string &  string,
const std::string &  start 
)
inline

◆ visualize()

OSIMMOCO_API void OpenSim::visualize ( Model  ,
Storage   
)

Play back a motion (from the Storage) in the simbody-visuailzer.

The Storage should contain all generalized coordinates. The visualizer window allows the user to control playback speed. This function blocks until the user exits the simbody-visualizer window.