Taking account of the very last waypoint buffer (#2407)
* Taking account for the very last waypoint buffer * Update CHANGELOG.md * Removing unused variables (Travis) * Update CHANGELOG.md Co-authored-by: Praveen Kumar <35625166+pravinblaze@users.noreply.github.com> Co-authored-by: bernat <bernatx@gmail.com> Co-authored-by: Marc Garcia Puig <marcgpuig@gmail.com>
This commit is contained in:
parent
c4bf8d3f58
commit
9c70de31b1
|
@ -27,6 +27,7 @@
|
||||||
* New python clients:
|
* New python clients:
|
||||||
- `weather.py`: allows weather changes using the new weather parameters
|
- `weather.py`: allows weather changes using the new weather parameters
|
||||||
* Fixed docker build of .BIN for pedestrian navigation
|
* Fixed docker build of .BIN for pedestrian navigation
|
||||||
|
* Fixed local_planner.py: agent will now stop when it reaches the desired destination
|
||||||
* Fixed crash when missing elevation profile and lane offset in OpenDRIVE
|
* Fixed crash when missing elevation profile and lane offset in OpenDRIVE
|
||||||
* Fixed typos
|
* Fixed typos
|
||||||
* Fixed agent failures due to API changes in is_within_distance_ahead()
|
* Fixed agent failures due to API changes in is_within_distance_ahead()
|
||||||
|
|
|
@ -14,7 +14,7 @@ import random
|
||||||
|
|
||||||
import carla
|
import carla
|
||||||
from agents.navigation.controller import VehiclePIDController
|
from agents.navigation.controller import VehiclePIDController
|
||||||
from agents.tools.misc import distance_vehicle, draw_waypoints
|
from agents.tools.misc import draw_waypoints
|
||||||
|
|
||||||
|
|
||||||
class RoadOption(Enum):
|
class RoadOption(Enum):
|
||||||
|
@ -199,7 +199,7 @@ class LocalPlanner(object):
|
||||||
if not self._global_plan and len(self._waypoints_queue) < int(self._waypoints_queue.maxlen * 0.5):
|
if not self._global_plan and len(self._waypoints_queue) < int(self._waypoints_queue.maxlen * 0.5):
|
||||||
self._compute_next_waypoints(k=100)
|
self._compute_next_waypoints(k=100)
|
||||||
|
|
||||||
if len(self._waypoints_queue) == 0:
|
if len(self._waypoints_queue) == 0 and len(self._waypoint_buffer) == 0:
|
||||||
control = carla.VehicleControl()
|
control = carla.VehicleControl()
|
||||||
control.steer = 0.0
|
control.steer = 0.0
|
||||||
control.throttle = 0.0
|
control.throttle = 0.0
|
||||||
|
@ -242,8 +242,7 @@ class LocalPlanner(object):
|
||||||
return control
|
return control
|
||||||
|
|
||||||
def done(self):
|
def done(self):
|
||||||
vehicle_transform = self._vehicle.get_transform()
|
return len(self._waypoints_queue) == 0 and len(self._waypoint_buffer) == 0
|
||||||
return len(self._waypoints_queue) == 0 and all([distance_vehicle(wp, vehicle_transform) < self._min_distance for wp in self._waypoints_queue])
|
|
||||||
|
|
||||||
def _retrieve_options(list_waypoints, current_waypoint):
|
def _retrieve_options(list_waypoints, current_waypoint):
|
||||||
"""
|
"""
|
||||||
|
|
Loading…
Reference in New Issue