Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Global Path Bug #448

Merged
merged 2 commits into from
Oct 27, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions src/local_pathfinding/local_pathfinding/local_path.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ def __init__(
HelperLatLon(latitude=waypoint.latitude, longitude=waypoint.longitude)
for waypoint in global_path.waypoints
]
else:
self.global_path = global_path

if filtered_wind_sensor: # TODO: remove when mock can be run
self.wind_speed = filtered_wind_sensor.speed.speed
Expand Down
5 changes: 3 additions & 2 deletions src/local_pathfinding/local_pathfinding/ompl_path.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,18 @@
won't work). The C++ API is documented on the OMPL website:
https://ompl.kavrakilab.org/api_overview.html.
"""

from __future__ import annotations

from typing import TYPE_CHECKING, List, Tuple, Type

from custom_interfaces.msg import HelperLatLon
from ompl import base as ob
from ompl import geometric as og
from ompl import util as ou
from rclpy.impl.rcutils_logger import RcutilsLogger

import local_pathfinding.coord_systems as cs
from custom_interfaces.msg import HelperLatLon
from local_pathfinding.objectives import get_sailing_objective

if TYPE_CHECKING:
Expand All @@ -39,7 +40,7 @@ def __init__(self, local_path_state: LocalPathState, logger: RcutilsLogger):

self.reference_latlon = (
local_path_state.global_path[-1]
if local_path_state and len(local_path_state.global_path) > 0
if local_path_state.global_path and len(local_path_state.global_path) > 0
else HelperLatLon(latitude=0.0, longitude=0.0)
)

Expand Down
9 changes: 8 additions & 1 deletion src/local_pathfinding/test/test_ompl_path.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,14 @@


def test_OMPLPathState():
state = ompl_path.OMPLPathState(local_path_state=None, logger=RcutilsLogger())
local_path_state = LocalPathState(
gps=GPS(),
ais_ships=AISShips(),
global_path=Path(),
filtered_wind_sensor=WindSensor(),
planner="rrtstar",
)
state = ompl_path.OMPLPathState(local_path_state, logger=RcutilsLogger())
assert state.state_domain == (-1, 1), "incorrect value for attribute state_domain"
assert state.state_range == (-1, 1), "incorrect value for attribute start_state"
assert state.start_state == pytest.approx(
Expand Down
Loading