mirror of
https://github.com/AtsushiSakai/PythonRobotics.git
synced 2026-04-22 03:00:22 -04:00
clean up clothoidal_paths.py (#638)
* clean up clothoidal_paths.py * add unit tests for clothoid_paths * add unit tests for clothoid_paths * add unit tests for clothoid_paths * code clean up * code clean up * code clean up * code clean up * code clean up * code clean up * code clean up * code clean up
This commit is contained in:
@@ -34,7 +34,7 @@ So
|
||||
& \ddot{\theta} = \frac{g(M + m)sin{\theta} - \dot{\theta}^2lmsin{\theta}cos{\theta} + ucos{\theta}}{l(M + m - mcos^2{\theta})}
|
||||
|
||||
|
||||
Linearlied model when :math:`\theta` small, :math:`cos{\theta} \approx 1`, :math:`sin{\theta} \approx \theta`, :math:`\dot{\theta}^2 \approx 0`.
|
||||
Linearized model when :math:`\theta` small, :math:`cos{\theta} \approx 1`, :math:`sin{\theta} \approx \theta`, :math:`\dot{\theta}^2 \approx 0`.
|
||||
|
||||
.. math::
|
||||
& \ddot{x} = \frac{gm}{M}\theta + \frac{1}{M}u\\
|
||||
@@ -68,16 +68,20 @@ If control x and \theta
|
||||
LQR control
|
||||
~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
|
||||
The LQR cotroller minimize this cost function defined as:
|
||||
The LQR controller minimize this cost function defined as:
|
||||
|
||||
.. math:: J = x^T Q x + u^T R u
|
||||
|
||||
the feedback control law that minimizes the value of the cost is:
|
||||
|
||||
.. math:: u = -K x
|
||||
|
||||
where:
|
||||
|
||||
.. math:: K = (B^T P B + R)^{-1} B^T P A
|
||||
and :math:`P` is the unique positive definite solution to the discrete time `algebraic Riccati equation <https://en.wikipedia.org/wiki/Inverted_pendulum#From_Lagrange's_equations>`__ (DARE):
|
||||
|
||||
and :math:`P` is the unique positive definite solution to the discrete time
|
||||
`algebraic Riccati equation <https://en.wikipedia.org/wiki/Inverted_pendulum#From_Lagrange's_equations>`__ (DARE):
|
||||
|
||||
.. math:: P = A^T P A - A^T P B ( R + B^T P B )^{-1} B^T P A + Q
|
||||
|
||||
@@ -85,13 +89,13 @@ and :math:`P` is the unique positive definite solution to the discrete time `alg
|
||||
|
||||
MPC control
|
||||
~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
The MPC cotroller minimize this cost function defined as:
|
||||
The MPC controller minimize this cost function defined as:
|
||||
|
||||
.. math:: J = x^T Q x + u^T R u
|
||||
|
||||
subject to:
|
||||
|
||||
- Linearlied Inverted Pendulum model
|
||||
- Linearized Inverted Pendulum model
|
||||
- Initial state
|
||||
|
||||
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif
|
||||
|
||||
Reference in New Issue
Block a user