Skip to content

Commit 73e1c0b

Browse files
authored
Add "Code Link" sections and rename classes for consistency (#1214)
This commit adds "Code Link" sections to documentation across various path planning modules, linking to relevant class and function APIs. Additionally, several class renaming changes were made, such as `Dijkstra` to `DijkstraPlanner` and `eta3_trajectory` to `Eta3SplineTrajectory`, to enhance naming consistency. Minor fixes include file restructuring and image renaming for the RRT module.
1 parent a38da41 commit 73e1c0b

File tree

33 files changed

+277
-25
lines changed

33 files changed

+277
-25
lines changed

PathPlanning/Dijkstra/dijkstra.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
show_animation = True
1313

1414

15-
class Dijkstra:
15+
class DijkstraPlanner:
1616

1717
def __init__(self, ox, oy, resolution, robot_radius):
1818
"""
@@ -246,7 +246,7 @@ def main():
246246
plt.grid(True)
247247
plt.axis("equal")
248248

249-
dijkstra = Dijkstra(ox, oy, grid_size, robot_radius)
249+
dijkstra = DijkstraPlanner(ox, oy, grid_size, robot_radius)
250250
rx, ry = dijkstra.planning(sx, sy, gx, gy)
251251

252252
if show_animation: # pragma: no cover

PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ def __init__(self, actual_vel, max_vel):
2929
self.message = f'Actual velocity {actual_vel} does not equal desired max velocity {max_vel}!'
3030

3131

32-
class eta3_trajectory(Eta3Path):
32+
class Eta3SplineTrajectory(Eta3Path):
3333
"""
3434
eta3_trajectory
3535
@@ -300,8 +300,8 @@ def test1(max_vel=0.5):
300300
trajectory_segments.append(Eta3PathSegment(
301301
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
302302

303-
traj = eta3_trajectory(trajectory_segments,
304-
max_vel=max_vel, max_accel=0.5)
303+
traj = Eta3SplineTrajectory(trajectory_segments,
304+
max_vel=max_vel, max_accel=0.5)
305305

306306
# interpolate at several points along the path
307307
times = np.linspace(0, traj.total_time, 101)
@@ -334,8 +334,8 @@ def test2(max_vel=0.5):
334334
trajectory_segments.append(Eta3PathSegment(
335335
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
336336

337-
traj = eta3_trajectory(trajectory_segments,
338-
max_vel=max_vel, max_accel=0.5)
337+
traj = Eta3SplineTrajectory(trajectory_segments,
338+
max_vel=max_vel, max_accel=0.5)
339339

340340
# interpolate at several points along the path
341341
times = np.linspace(0, traj.total_time, 101)
@@ -400,8 +400,8 @@ def test3(max_vel=2.0):
400400
start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa))
401401

402402
# construct the whole path
403-
traj = eta3_trajectory(trajectory_segments,
404-
max_vel=max_vel, max_accel=0.5, max_jerk=1)
403+
traj = Eta3SplineTrajectory(trajectory_segments,
404+
max_vel=max_vel, max_accel=0.5, max_jerk=1)
405405

406406
# interpolate at several points along the path
407407
times = np.linspace(0, traj.total_time, 1001)

docs/modules/5_path_planning/bezier_path/bezier_path_main.rst

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,15 @@ You can get different Beizer course:
1313

1414
.. image:: Figure_2.png
1515

16+
Code Link
17+
~~~~~~~~~~~~~~~
18+
19+
.. autofunction:: PathPlanning.BezierPath.bezier_path.calc_4points_bezier_path
20+
21+
1622
Reference
23+
~~~~~~~~~~~~~~~
1724

1825
- `Continuous Curvature Path Generation Based on Bezier Curves for
1926
Autonomous
20-
Vehicles <https://citeseerx.ist.psu.edu/document?repid=rep1&type=pdf&doi=b00b657c3e0e828c589132a14825e7119772003d>`
27+
Vehicles <https://citeseerx.ist.psu.edu/document?repid=rep1&type=pdf&doi=b00b657c3e0e828c589132a14825e7119772003d>`__

docs/modules/5_path_planning/bspline_path/bspline_path_main.rst

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -105,8 +105,8 @@ The default spline degree is 3, so curvature changes smoothly.
105105

106106
.. image:: interp_and_curvature.png
107107

108-
API
109-
++++
108+
Code link
109+
++++++++++
110110

111111
.. autofunction:: PathPlanning.BSplinePath.bspline_path.interpolate_b_spline_path
112112

@@ -133,8 +133,8 @@ The default spline degree is 3, so curvature changes smoothly.
133133

134134
.. image:: approx_and_curvature.png
135135

136-
API
137-
++++
136+
Code Link
137+
++++++++++
138138

139139
.. autofunction:: PathPlanning.BSplinePath.bspline_path.approximate_b_spline_path
140140

docs/modules/5_path_planning/bugplanner/bugplanner_main.rst

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,4 +5,12 @@ This is a 2D planning with Bug algorithm.
55

66
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BugPlanner/animation.gif
77

8+
Code Link
9+
~~~~~~~~~~~~~~~
10+
11+
.. autofunction:: PathPlanning.BugPlanning.bug.main
12+
13+
Reference
14+
~~~~~~~~~~~~
15+
816
- `ECE452 Bug Algorithms <https://web.archive.org/web/20201103052224/https://sites.google.com/site/ece452bugalgorithms/>`_

docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -88,8 +88,8 @@ Catmull-Rom Spline API
8888

8989
This section provides an overview of the functions used for Catmull-Rom spline path planning.
9090

91-
API
92-
++++
91+
Code Link
92+
++++++++++
9393

9494
.. autofunction:: PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path.catmull_rom_point
9595

docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,11 @@ The final clothoid path can be calculated with the path parameters and Fresnel i
7373
&y(s)=y_{0}+\int_{0}^{s} \sin \left(\frac{1}{2} \kappa^{\prime} \tau^{2}+\kappa \tau+\vartheta_{0}\right) \mathrm{d} \tau
7474
\end{aligned}
7575
76+
Code Link
77+
~~~~~~~~~~~~~
78+
79+
.. autofunction:: PathPlanning.ClothoidPath.clothoid_path_planner.generate_clothoid_path
80+
7681

7782
References
7883
~~~~~~~~~~

docs/modules/5_path_planning/coverage_path/coverage_path_main.rst

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,11 @@ This is a 2D grid based sweep coverage path planner simulation:
88

99
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/GridBasedSweepCPP/animation.gif
1010

11+
Code Link
12+
+++++++++++++
13+
14+
.. autofunction:: PathPlanning.GridBasedSweepCPP.grid_based_sweep_coverage_path_planner.planning
15+
1116
Spiral Spanning Tree
1217
~~~~~~~~~~~~~~~~~~~~
1318

@@ -17,6 +22,14 @@ This is a 2D grid based spiral spanning tree coverage path planner simulation:
1722
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation2.gif
1823
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation3.gif
1924

25+
Code Link
26+
+++++++++++++
27+
28+
.. autofunction:: PathPlanning.SpiralSpanningTreeCPP.spiral_spanning_tree_coverage_path_planner.main
29+
30+
Reference
31+
+++++++++++++
32+
2033
- `Spiral-STC: An On-Line Coverage Algorithm of Grid Environments by a Mobile Robot <https://ieeexplore.ieee.org/abstract/document/1013479>`_
2134

2235

@@ -29,6 +42,14 @@ This is a 2D grid based wavefront coverage path planner simulation:
2942
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation2.gif
3043
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation3.gif
3144

45+
Code Link
46+
+++++++++++++
47+
48+
.. autofunction:: PathPlanning.WavefrontCPP.wavefront_coverage_path_planner.wavefront
49+
50+
Reference
51+
+++++++++++++
52+
3253
- `Planning paths of complete coverage of an unstructured environment by a mobile robot <https://pinkwink.kr/attachment/[email protected]>`_
3354

3455

docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -171,8 +171,8 @@ the second derivative by:
171171

172172
These equations can be calculated by differentiating the cubic polynomial.
173173

174-
API
175-
===
174+
Code Link
175+
==========
176176

177177
This is the 1D cubic spline class API:
178178

@@ -199,8 +199,8 @@ Curvature of each point can be also calculated analytically by:
199199

200200
:math:`\kappa=\frac{y^{\prime \prime} x^{\prime}-x^{\prime \prime} y^{\prime}}{\left(x^{\prime2}+y^{\prime2}\right)^{\frac{2}{3}}}`
201201

202-
API
203-
===
202+
Code Link
203+
==========
204204

205205
.. autoclass:: PathPlanning.CubicSpline.cubic_spline_planner.CubicSpline2D
206206
:members:

0 commit comments

Comments
 (0)