Add code links to documentation and fix naming inconsistencies (#1213)

Added references to related Python functions in documentation for better navigation and usability. Corrected inconsistencies in module and test names to align with their respective directories and improve clarity.
This commit is contained in:
Atsushi Sakai
2025-05-04 20:32:11 +09:00
committed by GitHub
parent d2fe5ae8f0
commit a38da41baf
22 changed files with 102 additions and 17 deletions

View File

@@ -89,6 +89,12 @@ and :math:`P` is the unique positive definite solution to the discrete time
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation_lqr.gif
Code Link
^^^^^^^^^^^
.. autofunction:: InvertedPendulum.inverted_pendulum_lqr_control.main
MPC control
~~~~~~~~~~~~~~~~~~~~~~~~~~~
The MPC controller minimize this cost function defined as:
@@ -101,3 +107,9 @@ subject to:
- Initial state
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif
Code Link
^^^^^^^^^^^
.. autofunction:: InvertedPendulum.inverted_pendulum_mpc_control.main

View File

@@ -5,7 +5,7 @@ Behavior Tree is a modular, hierarchical decision model that is widely used in r
It present some similarities to hierarchical state machines with the key difference that the main building block of a behavior is a task rather than a state.
Behavior Tree have been shown to generalize several other control architectures (https://ieeexplore.ieee.org/document/7790863)
Core Concepts
Code Link
~~~~~~~~~~~~~
Control Node

View File

@@ -12,8 +12,8 @@ Core Concepts
- **Action**: An operation executed during transition (before entering new state)
- **Guard**: A precondition that must be satisfied to allow transition
API
~~~
Code Link
~~~~~~~~~~~
.. autoclass:: MissionPlanning.StateMachine.state_machine.StateMachine
:members: add_transition, process, register_state

View File

@@ -17,6 +17,11 @@ Nonlinear Model Predictive Control with C-GMRES
.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/cgmres_nmpc/animation.gif
:alt: gif
Code Link
~~~~~~~~~~~~
.. autofunction:: PathTracking.cgmres_nmpc.cgmres_nmpc.NMPCControllerCGMRES
Mathematical Formulation
~~~~~~~~~~~~~~~~~~~~~~~~

View File

@@ -7,7 +7,12 @@ Path tracking simulation with LQR speed and steering control.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif
`[Code Link] <https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py>`_
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: PathTracking.lqr_speed_steer_control.lqr_speed_steer_control.lqr_speed_steering_control
Overview
~~~~~~~~

View File

@@ -8,7 +8,11 @@ control.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif
`[Code Link] <https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/lqr_steer_control/lqr_steer_control.py>`_
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: PathTracking.lqr_steer_control.lqr_steer_control.lqr_steering_control
Overview
~~~~~~~~

View File

@@ -5,13 +5,6 @@ Model predictive speed and steering control
.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/model_predictive_speed_and_steer_control/animation.gif?raw=true
:alt: Model predictive speed and steering control
Model predictive speed and steering control
code:
`PythonRobotics/model_predictive_speed_and_steer_control.py at master ·
AtsushiSakai/PythonRobotics <https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py>`__
This is a path tracking simulation using model predictive control (MPC).
The MPC controller controls vehicle speed and steering base on
@@ -22,6 +15,12 @@ This code uses cvxpy as an optimization modeling tool.
- `Welcome to CVXPY 1.0 — CVXPY 1.0.6
documentation <http://www.cvxpy.org/>`__
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: PathTracking.model_predictive_speed_and_steer_control.model_predictive_speed_and_steer_control.iterative_linear_mpc_control
MPC modeling
~~~~~~~~~~~~

View File

@@ -3,7 +3,13 @@ Move to a Pose Control
In this section, we present the logic of PathFinderController that drives a car from a start pose (x, y, theta) to a goal pose. A simulation of moving to a pose control is presented below.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/move_to_pose/animation.gif
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: PathTracking.move_to_pose.move_to_pose.move_to_pose
Position Control of non-Holonomic Systems
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

View File

@@ -16,4 +16,4 @@ Path tracking is the ability of a robot to follow the reference path generated b
lqr_speed_and_steering_control/lqr_speed_and_steering_control
model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control
cgmres_nmpc/cgmres_nmpc
move_to_a_pose_control/move_to_a_pose_control
move_to_a_pose/move_to_a_pose

View File

@@ -9,6 +9,12 @@ speed control.
The red line is a target course, the green cross means the target point
for pure pursuit control, the blue line is the tracking.
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: PathTracking.pure_pursuit.pure_pursuit.pure_pursuit_steer_control
Reference
~~~~~~~~~~~

View File

@@ -6,6 +6,12 @@ PID speed control.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: PathTracking.rear_wheel_feedback_control.rear_wheel_feedback_control.rear_wheel_feedback_control
Reference
~~~~~~~~~~~
- `A Survey of Motion Planning and Control Techniques for Self-driving

View File

@@ -6,6 +6,12 @@ control.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: PathTracking.stanley_control.stanley_control.stanley_control
Reference
~~~~~~~~~~~

View File

@@ -11,3 +11,10 @@ plotting area.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/n_joint_arm_to_point_control/animation.gif
In this simulation N = 10, however, you can change it.
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: ArmNavigation.n_joint_arm_to_point_control.n_joint_arm_to_point_control.main

View File

@@ -3,4 +3,9 @@ Arm navigation with obstacle avoidance
Arm navigation with obstacle avoidance simulation.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: ArmNavigation.arm_obstacle_navigation.arm_obstacle_navigation.main

View File

@@ -11,6 +11,12 @@ This is a interactive simulation.
You can set the goal position of the end effector with left-click on the plotting area.
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: ArmNavigation.two_joint_arm_to_point_control.two_joint_arm_to_point_control.main
Inverse Kinematics for a Planar Two-Link Robotic Arm
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

View File

@@ -4,3 +4,8 @@ Drone 3d trajectory following
This is a 3d trajectory following simulation for a quadrotor.
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/drone_3d_trajectory_following/animation.gif
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: AerialNavigation.drone_3d_trajectory_following.drone_3d_trajectory_following.quad_sim

View File

@@ -1,6 +1,14 @@
Rocket powered landing
-----------------------------
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/rocket_powered_landing/animation.gif
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: AerialNavigation.rocket_powered_landing.rocket_powered_landing.main
Simulation
~~~~~~~~~~

View File

@@ -4,3 +4,8 @@ Bipedal Planner
Bipedal Walking with modifying designated footsteps
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Bipedal/bipedal_planner/animation.gif
Code Link
~~~~~~~~~~~~~~~
.. autofunction:: Bipedal.bipedal_planner.bipedal_planner.BipedalPlanner

View File

@@ -1,5 +1,5 @@
import conftest # Add root path to sys.path
from PathTracking.rear_wheel_feedback import rear_wheel_feedback as m
from PathTracking.rear_wheel_feedback_control import rear_wheel_feedback_control as m
def test1():

View File

@@ -1,5 +1,5 @@
import conftest # Add root path to sys.path
from PathTracking.stanley_controller import stanley_controller as m
from PathTracking.stanley_control import stanley_control as m
def test1():