BaseCurveGenerator¶
src.python_motion_planning.traj_optimizer.base_curve_generator.BaseCurveGenerator
¶
Bases: ABC
Base class for curve generator (trajectory smoother).
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
step
|
float
|
Step size for interpolation or discretization along the curve. |
0.01
|
Source code in src\python_motion_planning\traj_optimizer\base_curve_generator.py
Python
class BaseCurveGenerator(ABC):
"""
Base class for curve generator (trajectory smoother).
Args:
step: Step size for interpolation or discretization along the curve.
"""
def __init__(self, step: float = 0.01) -> None:
super().__init__()
self.step = step
def __str__(self) -> str:
return "Base Curve Generator"
@abstractmethod
def generate(self, points: List[Tuple[float, ...]]) -> Tuple[List[Tuple[float, ...]], Dict[str, Any]]:
"""
Interface for curve generation.
Args:
points: A list of waypoints in world frame. The exact format (2D position
or 2D pose with orientation) depends on the concrete generator.
Returns:
path: A list containing the smoothed path waypoints in world frame.
curve_info: A dictionary containing the curve information (success, length).
"""
raise NotImplementedError
def length(self, path: List[Tuple[float, ...]]) -> float:
"""
Calculate the length of a path.
Args:
path: A list containing the path waypoints.
Returns:
length: Length of the path.
"""
dist = 0.0
for i in range(len(path) - 1):
dist += math.hypot(path[i + 1][0] - path[i][0], path[i + 1][1] - path[i][1])
return dist
generate(points)
abstractmethod
¶
Interface for curve generation.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
points
|
List[Tuple[float, ...]]
|
A list of waypoints in world frame. The exact format (2D position or 2D pose with orientation) depends on the concrete generator. |
required |
Returns:
| Name | Type | Description |
|---|---|---|
path |
List[Tuple[float, ...]]
|
A list containing the smoothed path waypoints in world frame. |
curve_info |
Dict[str, Any]
|
A dictionary containing the curve information (success, length). |
Source code in src\python_motion_planning\traj_optimizer\base_curve_generator.py
Python
@abstractmethod
def generate(self, points: List[Tuple[float, ...]]) -> Tuple[List[Tuple[float, ...]], Dict[str, Any]]:
"""
Interface for curve generation.
Args:
points: A list of waypoints in world frame. The exact format (2D position
or 2D pose with orientation) depends on the concrete generator.
Returns:
path: A list containing the smoothed path waypoints in world frame.
curve_info: A dictionary containing the curve information (success, length).
"""
raise NotImplementedError
length(path)
¶
Calculate the length of a path.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
path
|
List[Tuple[float, ...]]
|
A list containing the path waypoints. |
required |
Returns:
| Name | Type | Description |
|---|---|---|
length |
float
|
Length of the path. |
Source code in src\python_motion_planning\traj_optimizer\base_curve_generator.py
Python
def length(self, path: List[Tuple[float, ...]]) -> float:
"""
Calculate the length of a path.
Args:
path: A list containing the path waypoints.
Returns:
length: Length of the path.
"""
dist = 0.0
for i in range(len(path) - 1):
dist += math.hypot(path[i + 1][0] - path[i][0], path[i + 1][1] - path[i][1])
return dist