Private API
This page lists non-exported (internal) symbols of CTModels.
From CTModels
AbstractBuilder
CTModels.AbstractBuilder — Type
abstract type AbstractBuilderCommon supertype for builder objects used in the NLP back-end infrastructure.
AbstractBuilder itself does not impose a concrete calling interface; specialized subtypes such as AbstractModelBuilder and AbstractOCPSolutionBuilder define looser contracts that are documented on their own abstract types and concrete implementations.
AbstractConstraintsModel
CTModels.AbstractConstraintsModel — Type
abstract type AbstractConstraintsModelAbstract base type for constraint models in optimal control problems.
Subtypes store all constraint information including path constraints, boundary constraints, and box constraints on state, control, and variables.
See also: ConstraintsModel.
AbstractControlModel
CTModels.AbstractControlModel — Type
abstract type AbstractControlModelAbstract base type for control variable models in optimal control problems.
Subtypes describe the control space structure including dimension, naming, and optionally the control trajectory itself.
See also: ControlModel, ControlModelSolution.
AbstractDualModel
CTModels.AbstractDualModel — Type
abstract type AbstractDualModelAbstract base type for dual variable models in optimal control solutions.
Subtypes store Lagrange multipliers (dual variables) associated with constraints.
See also: DualModel.
AbstractModel
CTModels.AbstractModel — Type
AbstractModelBuilder
CTModels.AbstractModelBuilder — Type
abstract type AbstractModelBuilder <: CTModels.AbstractBuilderAbstract base type for builders that construct NLP back-end models from an AbstractOptimizationProblem.
Concrete subtypes (for example ADNLPModelBuilder and ExaModelBuilder) are expected to be callable objects that encapsulate the logic for building a model for a specific NLP back-end. The exact call signature is back-end dependent and therefore not fixed at the level of AbstractModelBuilder.
AbstractOCPSolutionBuilder
CTModels.AbstractOCPSolutionBuilder — Type
abstract type AbstractOCPSolutionBuilder <: CTModels.AbstractSolutionBuilderAbstract base type for builders that turn NLP back-end execution statistics into objects associated with a discretized optimal control problem (for example, an OCP solution or intermediate representation).
Concrete subtypes are expected to be callable on a SolverCore.AbstractExecutionStats value. A generic fallback method is provided (see below) that throws CTBase.NotImplemented if a concrete builder does not implement the call.
See also: ADNLPSolutionBuilder, ExaSolutionBuilder.
AbstractOCPTool
CTModels.AbstractOCPTool — Type
abstract type AbstractOCPToolAbstract base type for configurable tools in CTModels (backends, discretizers, solvers, etc.).
Subtypes of AbstractOCPTool are expected to follow a common options interface so they can be configured and introspected in a uniform way.
Interface contract
Concrete subtypes T <: AbstractOCPTool are expected to:
- store two fields
options_values::NamedTuple— current option values.options_sources::NamedTuple— provenance for each option (:ct_defaultor:user).
- optionally provide option metadata by specializing
_option_specs, returning aNamedTupleofOptionSpecvalues. - typically define a keyword-only constructor
T(; kwargs...)implemented using_build_ocp_tool_options, so that user-supplied keywords are validated and merged with tool defaults.
Most helper functions in the options schema (see nlp/options_schema.jl) operate generically on any subtype that satisfies this contract.
AbstractObjectiveModel
CTModels.AbstractObjectiveModel — Type
abstract type AbstractObjectiveModelAbstract base type for objective function models in optimal control problems.
Subtypes represent different forms of the cost functional: Mayer (terminal cost), Lagrange (integral cost), or Bolza (both).
See also: MayerObjectiveModel, LagrangeObjectiveModel, BolzaObjectiveModel.
AbstractOptimalControlInitialGuess
CTModels.AbstractOptimalControlInitialGuess — Type
abstract type AbstractOptimalControlInitialGuessAbstract base type for initial guesses used in optimal control problem solvers.
Subtypes provide initial trajectories for state, control, and optimisation variables to warm-start numerical solvers.
See also: OptimalControlInitialGuess.
AbstractOptimalControlPreInit
CTModels.AbstractOptimalControlPreInit — Type
abstract type AbstractOptimalControlPreInitAbstract base type for pre-initialisation data used before constructing a full initial guess.
Subtypes store raw or partial information that will be processed into an OptimalControlInitialGuess.
See also: OptimalControlPreInit.
AbstractOptimizationModeler
CTModels.AbstractOptimizationModeler — Type
abstract type AbstractOptimizationModeler <: CTModels.AbstractOCPToolAbstract base type for NLP modelers built on top of AbstractOptimizationProblem.
Subtypes of AbstractOptimizationModeler are also AbstractOCPTools and therefore follow the generic options interface: they store options_values and options_sources fields and are typically constructed using _build_ocp_tool_options.
Concrete modelers such as ADNLPModeler and ExaModeler dispatch on an AbstractOptimizationProblem to build NLP models and map NLP solutions back to OCP solutions.
AbstractOptimizationProblem
CTModels.AbstractOptimizationProblem — Type
abstract type AbstractOptimizationProblemAbstract base type for optimization problems built from optimal control problems.
Subtypes of AbstractOptimizationProblem are typically paired with AbstractModelBuilder and AbstractSolutionBuilder implementations that know how to construct and interpret NLP back-end models and solutions.
AbstractSolution
CTModels.AbstractSolution — Type
abstract type AbstractSolutionAbstract base type for optimal control problem solutions.
Subtypes store the complete solution including primal trajectories, dual variables, and solver information.
See also: Solution.
AbstractSolutionBuilder
CTModels.AbstractSolutionBuilder — Type
abstract type AbstractSolutionBuilder <: CTModels.AbstractBuilderAbstract base type for builders that transform NLP solutions into other representations (for example, solutions of an optimal control problem).
Subtypes are expected to be callable, but the abstract type does not fix the argument types. More specific contracts are documented on AbstractOCPSolutionBuilder and related concrete types.
AbstractSolverInfos
CTModels.AbstractSolverInfos — Type
abstract type AbstractSolverInfosAbstract base type for solver information associated with an optimal control solution.
Subtypes store metadata about the numerical solution process.
See also: SolverInfos.
AbstractStateModel
CTModels.AbstractStateModel — Type
abstract type AbstractStateModelAbstract base type for state variable models in optimal control problems.
Subtypes describe the state space structure including dimension, naming, and optionally the state trajectory itself.
See also: StateModel, StateModelSolution.
AbstractTimeGridModel
CTModels.AbstractTimeGridModel — Type
abstract type AbstractTimeGridModelAbstract base type for time grid models used in optimal control solutions.
Subtypes store the discretised time points at which the solution is evaluated.
See also: TimeGridModel, EmptyTimeGridModel.
AbstractTimeModel
CTModels.AbstractTimeModel — Type
abstract type AbstractTimeModelAbstract base type for time boundary models (initial or final time).
Subtypes represent either fixed or free time boundaries in an optimal control problem.
See also: FixedTimeModel, FreeTimeModel.
AbstractTimesModel
CTModels.AbstractTimesModel — Type
abstract type AbstractTimesModelAbstract base type for combined initial and final time models.
See also: TimesModel.
AbstractVariableModel
CTModels.AbstractVariableModel — Type
abstract type AbstractVariableModelAbstract base type for optimisation variable models in optimal control problems.
Optimisation variables are decision variables that do not depend on time, such as free final time or unknown parameters.
See also: VariableModel, EmptyVariableModel, VariableModelSolution.
Autonomous
CTModels.Autonomous — Type
abstract type Autonomous <: CTModels.TimeDependenceType tag indicating that the dynamics and other functions of an optimal control problem do not explicitly depend on time.
For autonomous systems, the dynamics have the form ẋ = f(x, u) rather than ẋ = f(t, x, u).
See also: TimeDependence, NonAutonomous.
BolzaObjectiveModel
CTModels.BolzaObjectiveModel — Type
struct BolzaObjectiveModel{TM<:Function, TL<:Function} <: CTModels.AbstractObjectiveModelObjective model with both Mayer and Lagrange costs (Bolza form): g(x(t₀), x(tf), v) + ∫ f⁰(t, x, u, v) dt.
Fields
mayer::TM: The Mayer cost function(x0, xf, v) -> g(x0, xf, v).lagrange::TL: The Lagrange integrand(t, x, u, v) -> f⁰(t, x, u, v).criterion::Symbol: Optimisation direction, either:minor:max.
Example
julia> using CTModels
julia> g = (x0, xf, v) -> xf[1]^2
julia> f0 = (t, x, u, v) -> u[1]^2
julia> obj = CTModels.BolzaObjectiveModel(g, f0, :min)ConstraintsModel
CTModels.ConstraintsModel — Type
struct ConstraintsModel{TP<:Tuple, TB<:Tuple, TS<:Tuple, TC<:Tuple, TV<:Tuple} <: CTModels.AbstractConstraintsModelContainer for all constraints in an optimal control problem.
Fields
path_nl::TP: Tuple of nonlinear path constraints(t, x, u, v) -> c(t, x, u, v).boundary_nl::TB: Tuple of nonlinear boundary constraints(x0, xf, v) -> b(x0, xf, v).state_box::TS: Tuple of box constraints on state variables (lower/upper bounds).control_box::TC: Tuple of box constraints on control variables (lower/upper bounds).variable_box::TV: Tuple of box constraints on optimisation variables (lower/upper bounds).
Example
julia> using CTModels
julia> # Typically constructed internally by the model builder
julia> cm = CTModels.ConstraintsModel((), (), (), (), ())ControlModel
CTModels.ControlModel — Type
struct ControlModel <: CTModels.AbstractControlModelControl model describing the structure of the control variable in an optimal control problem definition.
Fields
name::String: Display name for the control variable (e.g.,"u").components::Vector{String}: Names of individual control components (e.g.,["u₁", "u₂"]).
Example
julia> using CTModels
julia> cm = CTModels.ControlModel("u", ["thrust", "steering"])ControlModelSolution
CTModels.ControlModelSolution — Type
struct ControlModelSolution{TS<:Function} <: CTModels.AbstractControlModelControl model for a solved optimal control problem, including the control trajectory.
Fields
name::String: Display name for the control variable.components::Vector{String}: Names of individual control components.value::TS: A functiont -> u(t)returning the control vector at timet.
Example
julia> using CTModels
julia> u_traj = t -> [sin(t)]
julia> cms = CTModels.ControlModelSolution("u", ["u₁"], u_traj)
julia> cms.value(π/2)
1-element Vector{Float64}:
1.0DiscretizedOptimalControlProblem
CTModels.DiscretizedOptimalControlProblem — Type
struct DiscretizedOptimalControlProblem{TO<:CTModels.AbstractModel, TB<:NamedTuple} <: CTModels.AbstractOptimizationProblemDiscretised optimal control problem ready for NLP solving.
Wraps an optimal control problem together with backend builders for multiple NLP backends (e.g., ADNLPModels and ExaModels).
Fields
optimal_control_problem::TO: The original optimal control problem model.backend_builders::TB: Named tuple mapping backend symbols toOCPBackendBuilders.
Example
julia> using CTModels
julia> # Typically constructed internally by discretisation routines
julia> docp = CTModels.DiscretizedOptimalControlProblem(ocp, backend_builders)DualModel
CTModels.DualModel — Type
struct DualModel{PC_Dual<:Union{Nothing, Function}, BC_Dual<:Union{Nothing, AbstractVector{<:Real}}, SC_LB_Dual<:Union{Nothing, Function}, SC_UB_Dual<:Union{Nothing, Function}, CC_LB_Dual<:Union{Nothing, Function}, CC_UB_Dual<:Union{Nothing, Function}, VC_LB_Dual<:Union{Nothing, AbstractVector{<:Real}}, VC_UB_Dual<:Union{Nothing, AbstractVector{<:Real}}} <: CTModels.AbstractDualModelDual variables (Lagrange multipliers) for all constraints in an optimal control solution.
Fields
path_constraints_dual::PC_Dual: Multipliers for path constraintst -> μ(t), ornothing.boundary_constraints_dual::BC_Dual: Multipliers for boundary constraints (vector), ornothing.state_constraints_lb_dual::SC_LB_Dual: Multipliers for state lower boundst -> ν⁻(t), ornothing.state_constraints_ub_dual::SC_UB_Dual: Multipliers for state upper boundst -> ν⁺(t), ornothing.control_constraints_lb_dual::CC_LB_Dual: Multipliers for control lower boundst -> ω⁻(t), ornothing.control_constraints_ub_dual::CC_UB_Dual: Multipliers for control upper boundst -> ω⁺(t), ornothing.variable_constraints_lb_dual::VC_LB_Dual: Multipliers for variable lower bounds (vector), ornothing.variable_constraints_ub_dual::VC_UB_Dual: Multipliers for variable upper bounds (vector), ornothing.
Example
julia> using CTModels
julia> # Typically constructed internally by the solver
julia> dm = CTModels.DualModel(nothing, nothing, nothing, nothing, nothing, nothing, nothing, nothing)EmptyTimeGridModel
CTModels.EmptyTimeGridModel — Type
struct EmptyTimeGridModel <: CTModels.AbstractTimeGridModelSentinel type representing an empty or uninitialised time grid.
Used when a solution does not yet have an associated time discretisation.
Example
julia> using CTModels
julia> etg = CTModels.EmptyTimeGridModel()EmptyVariableModel
CTModels.EmptyVariableModel — Type
struct EmptyVariableModel <: CTModels.AbstractVariableModelSentinel type representing the absence of optimisation variables in an optimal control problem.
Used when the problem has no free parameters or free final time.
Example
julia> using CTModels
julia> evm = CTModels.EmptyVariableModel()FixedTimeModel
CTModels.FixedTimeModel — Type
struct FixedTimeModel{T<:Real} <: CTModels.AbstractTimeModelTime model representing a fixed (known) time boundary.
Fields
time::T: The fixed time value.name::String: Display name for this time (e.g.,"t₀"or"tf").
Example
julia> using CTModels
julia> t0 = CTModels.FixedTimeModel(0.0, "t₀")
julia> t0.time
0.0FreeTimeModel
CTModels.FreeTimeModel — Type
struct FreeTimeModel <: CTModels.AbstractTimeModelTime model representing a free (optimised) time boundary.
The actual time value is stored in the optimisation variable at the given index.
Fields
index::Int: Index into the optimisation variable where this time is stored.name::String: Display name for this time (e.g.,"tf").
Example
julia> using CTModels
julia> tf = CTModels.FreeTimeModel(1, "tf")
julia> tf.index
1LagrangeObjectiveModel
CTModels.LagrangeObjectiveModel — Type
struct LagrangeObjectiveModel{TL<:Function} <: CTModels.AbstractObjectiveModelObjective model with only a Lagrange (integral) cost: ∫ f⁰(t, x, u, v) dt.
Fields
lagrange::TL: The Lagrange integrand(t, x, u, v) -> f⁰(t, x, u, v).criterion::Symbol: Optimisation direction, either:minor:max.
Example
julia> using CTModels
julia> f0 = (t, x, u, v) -> u[1]^2
julia> obj = CTModels.LagrangeObjectiveModel(f0, :min)MayerObjectiveModel
CTModels.MayerObjectiveModel — Type
struct MayerObjectiveModel{TM<:Function} <: CTModels.AbstractObjectiveModelObjective model with only a Mayer (terminal) cost: g(x(t₀), x(tf), v).
Fields
mayer::TM: The Mayer cost function(x0, xf, v) -> g(x0, xf, v).criterion::Symbol: Optimisation direction, either:minor:max.
Example
julia> using CTModels
julia> g = (x0, xf, v) -> xf[1]^2
julia> obj = CTModels.MayerObjectiveModel(g, :min)Model
CTModels.Model — Type
struct Model{TD<:CTModels.TimeDependence, TimesModelType<:CTModels.AbstractTimesModel, StateModelType<:CTModels.AbstractStateModel, ControlModelType<:CTModels.AbstractControlModel, VariableModelType<:CTModels.AbstractVariableModel, DynamicsModelType<:Function, ObjectiveModelType<:CTModels.AbstractObjectiveModel, ConstraintsModelType<:CTModels.AbstractConstraintsModel, BuildExaModelType<:Union{Nothing, Function}} <: CTModels.AbstractModelImmutable optimal control problem model containing all problem components.
A Model is created from a PreModel once all required fields have been set. It is parameterised by the time dependence type (Autonomous or NonAutonomous) and the types of all its components.
Fields
times::TimesModelType: Initial and final time specification.state::StateModelType: State variable structure (name, components).control::ControlModelType: Control variable structure (name, components).variable::VariableModelType: Optimisation variable structure (may be empty).dynamics::DynamicsModelType: System dynamics function(t, x, u, v) -> ẋ.objective::ObjectiveModelType: Cost functional (Mayer, Lagrange, or Bolza).constraints::ConstraintsModelType: All problem constraints.definition::Expr: Original symbolic definition of the problem.build_examodel::BuildExaModelType: Optional ExaModels builder function.
Example
julia> using CTModels
julia> # Models are typically created via the @def macro or PreModel
julia> ocp = CTModels.Model # Type referenceNonAutonomous
CTModels.NonAutonomous — Type
abstract type NonAutonomous <: CTModels.TimeDependenceType tag indicating that the dynamics and other functions of an optimal control problem explicitly depend on time.
For non-autonomous systems, the dynamics have the form ẋ = f(t, x, u).
See also: TimeDependence, Autonomous.
OCPBackendBuilders
CTModels.OCPBackendBuilders — Type
struct OCPBackendBuilders{TM<:CTModels.AbstractModelBuilder, TS<:CTModels.AbstractOCPSolutionBuilder}Container pairing a model builder with its corresponding solution builder.
Fields
model::TM: The model builder (e.g.,ADNLPModelBuilder).solution::TS: The solution builder (e.g.,ADNLPSolutionBuilder).
See also: DiscretizedOptimalControlProblem.
OptimalControlInitialGuess
CTModels.OptimalControlInitialGuess — Type
struct OptimalControlInitialGuess{X<:Function, U<:Function, V} <: CTModels.AbstractOptimalControlInitialGuessConcrete initial guess for an optimal control problem, storing callable trajectories for state and control, and a value for the optimisation variable.
Fields
state::X: A functiont -> x(t)returning the state guess at timet.control::U: A functiont -> u(t)returning the control guess at timet.variable::V: The initial guess for the optimisation variable (scalar or vector).
Example
julia> using CTModels
julia> x_guess = t -> [cos(t), sin(t)]
julia> u_guess = t -> [0.5]
julia> v_guess = [1.0, 2.0]
julia> ig = CTModels.OptimalControlInitialGuess(x_guess, u_guess, v_guess)OptimalControlPreInit
CTModels.OptimalControlPreInit — Type
struct OptimalControlPreInit{SX, SU, SV} <: CTModels.AbstractOptimalControlPreInitPre-initialisation container for initial guess data before validation and interpolation.
Fields
state::SX: Raw state data (e.g., matrix, vector of vectors, or function).control::SU: Raw control data (e.g., matrix, vector of vectors, or function).variable::SV: Raw optimisation variable data (scalar, vector, ornothing).
Example
julia> using CTModels
julia> pre = CTModels.OptimalControlPreInit([1.0 2.0; 3.0 4.0], [0.5, 0.6], [1.0])OptionSpec
CTModels.OptionSpec — Type
struct OptionSpecMetadata for a single named option of an AbstractOCPTool.
Each field describes one aspect of the option:
type— expected Julia type for the option value, ormissingif no static type information is available.default— default value when the option is not supplied by the user, ormissingif there is no default.description— short human-readable description of the option, ormissingif it is not yet documented.
Instances of OptionSpec are typically returned from _option_specs(::Type) in a NamedTuple, one field per option name.
PreModel
CTModels.PreModel — Type
mutable struct PreModel <: CTModels.AbstractModelMutable optimal control problem model under construction.
A PreModel is used to incrementally define an optimal control problem before building it into an immutable Model. Fields can be set in any order and the model is validated before building.
Fields
times::Union{AbstractTimesModel,Nothing}: Initial and final time specification.state::Union{AbstractStateModel,Nothing}: State variable structure.control::Union{AbstractControlModel,Nothing}: Control variable structure.variable::AbstractVariableModel: Optimisation variable (defaults to empty).dynamics::Union{Function,Vector,Nothing}: System dynamics (function or component-wise).objective::Union{AbstractObjectiveModel,Nothing}: Cost functional.constraints::ConstraintsDictType: Dictionary of constraints being built.definition::Union{Expr,Nothing}: Symbolic definition expression.autonomous::Union{Bool,Nothing}: Whether the system is autonomous.
Example
julia> using CTModels
julia> pre = CTModels.PreModel()
julia> # Set fields incrementally...Solution
CTModels.Solution — Type
struct Solution{TimeGridModelType<:CTModels.AbstractTimeGridModel, TimesModelType<:CTModels.AbstractTimesModel, StateModelType<:CTModels.AbstractStateModel, ControlModelType<:CTModels.AbstractControlModel, VariableModelType<:CTModels.AbstractVariableModel, CostateModelType<:Function, ObjectiveValueType<:Real, DualModelType<:CTModels.AbstractDualModel, SolverInfosType<:CTModels.AbstractSolverInfos, ModelType<:CTModels.AbstractModel} <: CTModels.AbstractSolutionComplete solution of an optimal control problem.
Stores the optimal state, control, and costate trajectories, the optimisation variable value, objective value, dual variables, solver information, and a reference to the original model.
Fields
time_grid::TimeGridModelType: Discretised time points.times::TimesModelType: Initial and final time specification.state::StateModelType: State trajectoryt -> x(t)with metadata.control::ControlModelType: Control trajectoryt -> u(t)with metadata.variable::VariableModelType: Optimisation variable value with metadata.costate::CostateModelType: Costate (adjoint) trajectoryt -> p(t).objective::ObjectiveValueType: Optimal objective value.dual::DualModelType: Dual variables for all constraints.solver_infos::SolverInfosType: Solver statistics and status.model::ModelType: Reference to the original optimal control problem.
Example
julia> using CTModels
julia> # Solutions are typically returned by solvers
julia> sol = solve(ocp, ...) # Returns a Solution
julia> CTModels.objective(sol)SolverInfos
CTModels.SolverInfos — Type
struct SolverInfos{V, TI<:Dict{Symbol, V}} <: CTModels.AbstractSolverInfosSolver information and statistics from the numerical solution process.
Fields
iterations::Int: Number of iterations performed by the solver.status::Symbol: Termination status (e.g.,:first_order,:max_iter).message::String: Human-readable message describing the termination status.successful::Bool: Whether the solver converged successfully.constraints_violation::Float64: Maximum constraint violation at the solution.infos::TI: Dictionary of additional solver-specific information.
Example
julia> using CTModels
julia> si = CTModels.SolverInfos(100, :first_order, "Converged", true, 1e-8, Dict{Symbol,Any}())
julia> si.successful
trueStateModel
CTModels.StateModel — Type
struct StateModel <: CTModels.AbstractStateModelState model describing the structure of the state variable in an optimal control problem definition.
Fields
name::String: Display name for the state variable (e.g.,"x").components::Vector{String}: Names of individual state components (e.g.,["x₁", "x₂"]).
Example
julia> using CTModels
julia> sm = CTModels.StateModel("x", ["position", "velocity"])StateModelSolution
CTModels.StateModelSolution — Type
struct StateModelSolution{TS<:Function} <: CTModels.AbstractStateModelState model for a solved optimal control problem, including the state trajectory.
Fields
name::String: Display name for the state variable.components::Vector{String}: Names of individual state components.value::TS: A functiont -> x(t)returning the state vector at timet.
Example
julia> using CTModels
julia> x_traj = t -> [cos(t), sin(t)]
julia> sms = CTModels.StateModelSolution("x", ["x₁", "x₂"], x_traj)
julia> sms.value(0.0)
2-element Vector{Float64}:
1.0
0.0TimeDependence
CTModels.TimeDependence — Type
abstract type TimeDependenceAbstract base type representing time dependence of an optimal control problem.
Used as a type parameter to distinguish between autonomous and non-autonomous systems at the type level, enabling dispatch and compile-time optimisations.
See also: Autonomous, NonAutonomous.
TimeGridModel
CTModels.TimeGridModel — Type
struct TimeGridModel{T<:Union{StepRangeLen, AbstractVector{<:Real}}} <: CTModels.AbstractTimeGridModelTime grid model storing the discretised time points of a solution.
Fields
value::T: Vector or range of time points (e.g.,LinRange(0, 1, 100)).
Example
julia> using CTModels
julia> tg = CTModels.TimeGridModel(LinRange(0, 1, 101))
julia> length(tg.value)
101TimesModel
CTModels.TimesModel — Type
struct TimesModel{TI<:CTModels.AbstractTimeModel, TF<:CTModels.AbstractTimeModel} <: CTModels.AbstractTimesModelCombined model for initial and final times in an optimal control problem.
Fields
initial::TI: The initial time model (fixed or free).final::TF: The final time model (fixed or free).time_name::String: Display name for the time variable (e.g.,"t").
Example
julia> using CTModels
julia> t0 = CTModels.FixedTimeModel(0.0, "t₀")
julia> tf = CTModels.FixedTimeModel(1.0, "tf")
julia> times = CTModels.TimesModel(t0, tf, "t")VariableModel
CTModels.VariableModel — Type
struct VariableModel <: CTModels.AbstractVariableModelVariable model describing the structure of the optimisation variable in an optimal control problem definition.
Fields
name::String: Display name for the variable (e.g.,"v").components::Vector{String}: Names of individual variable components (e.g.,["tf", "λ"]).
Example
julia> using CTModels
julia> vm = CTModels.VariableModel("v", ["final_time", "parameter"])VariableModelSolution
CTModels.VariableModelSolution — Type
struct VariableModelSolution{TS<:Union{Real, AbstractVector{<:Real}}} <: CTModels.AbstractVariableModelVariable model for a solved optimal control problem, including the variable value.
Fields
name::String: Display name for the variable.components::Vector{String}: Names of individual variable components.value::TS: The optimisation variable value (scalar or vector).
Example
julia> using CTModels
julia> vms = CTModels.VariableModelSolution("v", ["tf"], 2.5)
julia> vms.value
2.5__is_autonomous_set
CTModels.__is_autonomous_set — Function
__is_autonomous_set(ocp::CTModels.PreModel) -> Bool
Return true if the autonomous flag has been set in the PreModel.
__is_complete
CTModels.__is_complete — Function
__is_complete(ocp::CTModels.PreModel) -> Bool
Return true if the PreModel can be built into a Model.
__is_consistent
CTModels.__is_consistent — Function
__is_consistent(ocp::CTModels.PreModel) -> Bool
Return true if all the required fields are set in the PreModel.
__is_control_set
CTModels.__is_control_set — Function
__is_control_set(ocp::CTModels.Model) -> Bool
Return true since control is always set in a built Model.
__is_control_set(ocp::CTModels.PreModel) -> Bool
Return true if control has been set in the PreModel.
__is_definition_set
CTModels.__is_definition_set — Function
__is_definition_set(ocp::CTModels.Model) -> Bool
Return true since definition is always set in a built Model.
__is_definition_set(ocp::CTModels.PreModel) -> Bool
Return true if definition has been set in the PreModel.
__is_dynamics_complete
CTModels.__is_dynamics_complete — Function
__is_dynamics_complete(ocp::CTModels.PreModel) -> Bool
Return true if dynamics cover all state components in the PreModel.
For component-wise dynamics, checks that all state indices are covered.
__is_dynamics_set
CTModels.__is_dynamics_set — Function
__is_dynamics_set(ocp::CTModels.Model) -> Bool
Return true since dynamics is always set in a built Model.
__is_dynamics_set(ocp::CTModels.PreModel) -> Bool
Return true if dynamics have been set in the PreModel.
__is_empty
CTModels.__is_empty — Function
__is_empty(ocp::CTModels.PreModel) -> Bool
Return true if nothing has been set.
__is_objective_set
CTModels.__is_objective_set — Function
__is_objective_set(ocp::CTModels.Model) -> Bool
Return true since objective is always set in a built Model.
__is_objective_set(ocp::CTModels.PreModel) -> Bool
Return true if objective has been set in the PreModel.
__is_set
CTModels.__is_set — Function
__is_set(x) -> Bool
Return true if x is not nothing.
__is_state_set
CTModels.__is_state_set — Function
__is_state_set(ocp::CTModels.Model) -> Bool
Return true since state is always set in a built Model.
__is_state_set(ocp::CTModels.PreModel) -> Bool
Return true if state has been set in the PreModel.
__is_times_set
CTModels.__is_times_set — Function
__is_times_set(ocp::CTModels.Model) -> Bool
Return true since times are always set in a built Model.
__is_times_set(ocp::CTModels.PreModel) -> Bool
Return true if times have been set in the PreModel.
__is_variable_empty
CTModels.__is_variable_empty — Function
__is_variable_empty(v) -> Bool
Return true if v is an EmptyVariableModel.
__is_variable_set
CTModels.__is_variable_set — Function
__is_variable_set(ocp::CTModels.Model) -> Bool
Return true since variable is always set in a built Model.
__is_variable_set(ocp::CTModels.PreModel) -> Bool
Return true if a non-empty variable has been set in the PreModel.
is_empty_time_grid
CTModels.is_empty_time_grid — Function
is_empty_time_grid(sol::CTModels.Solution) -> Bool
Check if the time grid is empty from the solution.
state_dimension
CTModels.state_dimension — Function
state_dimension(ocp::CTModels.PreModel) -> Int64
Return the state dimension of the PreModel.
Throws CTBase.UnauthorizedCall if state has not been set.
state_dimension(ocp::CTModels.Model) -> Int64
Return the state dimension.
state_dimension(sol::CTModels.Solution) -> Int64
Return the dimension of the state.