@@ -36,55 +36,48 @@ import casadi as ca
3636X = lie.SE3Quat.elem(ca.DM([1 , 2 , 3 , 1 , 0 , 0 , 0 ])) # position + quaternion
3737X_inv = X.inverse()
3838
39- # Type-safe modeling with full autocomplete
40- from cyecca.dynamics import ModelSX, state, input_var, param, output_var, symbolic, EmptyOutputs
41-
42- @symbolic
43- class States :
44- x: ca.SX = state(1 , 1.0 , " position" ) # Start at x=1
45- v: ca.SX = state(1 , 0.0 , " velocity" )
46-
47- @symbolic
48- class Inputs :
49- F: ca.SX = input_var(desc = " force" )
50-
51- @symbolic
52- class Params :
53- m: ca.SX = param(1.0 , " mass" )
54- c: ca.SX = param(0.1 , " damping" )
55- k: ca.SX = param(1.0 , " spring constant" )
56-
57- @symbolic
58- class Outputs :
59- position: ca.SX = output_var(desc = " position output" )
60- velocity: ca.SX = output_var(desc = " velocity output" )
61-
62- # Note: If you don't need outputs, use EmptyOutputs instead:
63- # model = ModelSX.create(States, Inputs, Params, EmptyOutputs)
64-
65- model = ModelSX.create(States, Inputs, Params, Outputs)
66- x, u, p, y = model.x, model.u, model.p, model.y
67-
68- # Mass-spring-damper: mx'' + cx' + kx = F
69- f_x = ca.vertcat(x.v, (u.F - p.c * x.v - p.k * x.x) / p.m)
70-
71- # Output the full state
72- f_y = ca.vertcat(x.x, x.v)
73-
74- model.build(f_x = f_x, f_y = f_y, integrator = ' rk4' )
75-
76- # Simulate free oscillation from x0=1
77- model = model.simulate(0.0 , 10.0 , 0.01 )
78- # Output:
79- # Final position: -0.529209
80- # Final velocity: 0.323980
81- # Access via: model.trajectory.x.x[-1] (final position)
82- # model.trajectory.x.v[-1] (final velocity)
83- # model.trajectory.x.x (full position trajectory, shape: n_steps)
84- #
85- # To compute outputs during simulation (optional, costs performance):
86- # model = model.simulate(0.0, 10.0, 0.01, compute_output=True)
87- # model.trajectory.y.position # output trajectory
39+ # Type-safe modeling with unified namespace (like Modelica)
40+ from cyecca.dynamics.explicit import Model, explicit, state, input_var, param, output_var
41+
42+ @explicit
43+ class MassSpringDamper :
44+ # States
45+ x: float = state(desc = " position" )
46+ v: float = state(desc = " velocity" )
47+ # Inputs
48+ F: float = input_var(desc = " force" )
49+ # Parameters
50+ m: float = param(default = 1.0 , desc = " mass" )
51+ c: float = param(default = 0.1 , desc = " damping" )
52+ k: float = param(default = 1.0 , desc = " spring constant" )
53+ # Outputs
54+ position: float = output_var(desc = " position output" )
55+
56+ # Create model - all variables in unified namespace (model.v)
57+ model = Model(MassSpringDamper)
58+
59+ # Define dynamics using unified namespace
60+ # model.v.x, model.v.v, model.v.F, model.v.m, etc. are symbolic variables
61+ model.ode(model.v.x, model.v.v) # dx/dt = v
62+ model.ode(model.v.v, (model.v.F - model.v.c * model.v.v - model.v.k * model.v.x) / model.v.m)
63+
64+ # Define outputs
65+ model.output(model.v.position, model.v.x)
66+
67+ model.build()
68+
69+ # Set initial conditions and simulate
70+ model.v0.x = 1.0 # Start at x=1
71+ t, data = model.simulate(0.0 , 10.0 , 0.01 )
72+
73+ # Access trajectory data
74+ # data.x is an ndarray of shape (n_steps,)
75+ # data.v is an ndarray of shape (n_steps,)
76+ print (f " Final position: { data.x[- 1 ]:.6f } " )
77+ print (f " Final velocity: { data.v[- 1 ]:.6f } " )
78+
79+ # Linearize at operating point (uses model.v0)
80+ A, B, C, D = model.linearize()
8881```
8982
9083## Documentation
0 commit comments