set_meas¶
Class method.
-
do_mpc.model.Model.
set_meas
(self, meas_name, expr, meas_noise=True)¶ Introduce new measurable output to the model class.
\[y = h(x(t),u(t),z(t),p(t),p_{\text{tv}}(t)) + v(t)\]or in case of discrete dynamics:
\[y_k = h(x_k,u_k,z_k,p_k,p_{\text{tv},k}) + v_k\]By default, the model assumes state-feedback (all states are measured outputs). Expressions must be formulated with respect to
_x
,_u
,_z
,_tvp
,_p
.Be default, it is assumed that the measurements experience additive noise \(v_k\). This can be deactivated for individual measured variables by changing the boolean variable
meas_noise
toFalse
. Note that measurement noise is only meaningful for state-estimation and will not affect the controller. Furthermore, it can be set with eachdo_mpc.simulator.Simulator
call to obtain imperfect outputs.Note
For moving horizon estimation it is suggested to declare all inputs (
_u
) and e.g. a subset of states (_x
) as measurable output. Some other MHE formulations treat inputs separately.Note
It is often suggested to deactivate measurement noise for “measured” inputs (
_u
). These can typically seen as certain variables.Example:
# Introduce states: x_meas = model.set_variable('_x', 'x', 3) # 3 measured states (vector) x_est = model.set_variable('_x', 'x', 3) # 3 estimated states (vector) # and inputs: u = model.set_variable('_u', 'u', 2) # 2 inputs (vector) # define measurements: model.set_meas('x_meas', x_meas) model.set_meas('u', u)
Parameters: - expr_name (string) – Arbitrary name for the given expression. Names are used for key word indexing.
- expr (CasADi SX or MX) – CasADi SX or MX function depending on
_x
,_u
,_z
,_tvp
,_p
. - meas_noise (bool) – Set if the measurement equation is disturbed by additive noise.
Raises: - assertion – expr_name must be str
- assertion – expr must be a casadi SX or MX type
- assertion – Cannot call after
setup()
.
Returns: Returns the newly created measurement expression.
Return type: casadi.SX
This page is auto-generated. Page source is not available on Github.