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

more map shifting fixes #791

Merged
merged 8 commits into from
Apr 28, 2021
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
8 changes: 4 additions & 4 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ All text added must be human readable.

Copy and pasting the git commit messages is __NOT__ enough.

## [Unrealeased]
## [Unreleased]
### Added
- Added `sanity-test` script and asked new users to run `sanity-test` instead of `make test` to ease the setup
process
Expand All @@ -17,14 +17,14 @@ process
- Added reference to SMARTS paper in front page of docs
- Only create `Renderer` on demand if vehicles are using camera-based sensors. See issue #725.
- Added glb models for pedestrians and motorcycles
- Added `--allow-offset-map` option for `scl scenario build` to prevent auto-shifting of Sumo road networks
### Changed
- Refactored SMARTS class to not inherit from Panda3D's ShowBase; it's aggregated instead. See issue #597.
### Fixed
- Fixed the bug of events such as off_road not registering in observation when off_road is set to false in DoneCriteria
- Fixed sumo road network offset bug for shifted maps. See issue #716.
- Fixed Sumo road network offset bug for shifted maps. See issue #716.
- Fixed traffic generation offset bug for shifted maps. See issue #790.
- Fixed bugs in traffic history and changed interface to it. See issue #732.

### Fixed
- Update `ego_open_agent` to use the package instead of the zoo directory version.

## [0.4.15] - 2021-03-18
Expand Down
42 changes: 35 additions & 7 deletions cli/studio.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,16 @@
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
# THE SOFTWARE.
import multiprocessing
import os
import subprocess
import sys
from pathlib import Path
from threading import Thread

import click

from smarts.core.sumo_road_network import SumoRoadNetwork


@click.group(name="scenario")
def scenario_cli():
Expand All @@ -38,12 +41,20 @@ def scenario_cli():
default=False,
help="Clean previously generated artifacts first",
)
@click.option(
"--allow-offset-map",
is_flag=True,
default=False,
help="Allows Sumo's road network (map.net.xml) to be offset from the origin. if not specified, creates '{}' if necessary.".format(
SumoRoadNetwork.shifted_net_file_name
),
)
@click.argument("scenario", type=click.Path(exists=True), metavar="<scenario>")
def build_scenario(clean, scenario):
_build_single_scenario(clean, scenario)
def build_scenario(clean, allow_offset_map, scenario):
_build_single_scenario(clean, allow_offset_map, scenario)


def _build_single_scenario(clean, scenario):
def _build_single_scenario(clean, allow_offset_map, scenario):
import importlib.resources as pkg_resources

from smarts.sstudio.sumo2mesh import generate_glb_from_sumo_network
Expand All @@ -53,9 +64,17 @@ def _build_single_scenario(clean, scenario):
_clean(scenario)

scenario_root = Path(scenario)
map_net = scenario_root / "map.net.xml"
map_net = str(scenario_root / "map.net.xml")
if not allow_offset_map:
SumoRoadNetwork.from_file(map_net, shift_to_origin=True)
elif os.path.isfile(SumoRoadNetwork.shifted_net_file_path(map_net)):
click.echo(
"WARNING: {} already exists. Remove it if you want to use unshifted/offset map.net.xml instead.".format(
SumoRoadNetwork.shifted_net_file_name
)
)
map_glb = scenario_root / "map.glb"
generate_glb_from_sumo_network(str(map_net), str(map_glb))
generate_glb_from_sumo_network(map_net, str(map_glb))

requirements_txt = scenario_root / "requirements.txt"
if requirements_txt.exists():
Expand Down Expand Up @@ -105,8 +124,16 @@ def _build_single_scenario(clean, scenario):
default=False,
help="Clean previously generated artifacts first",
)
@click.option(
"--allow-offset-maps",
is_flag=True,
default=False,
help="Allows Sumo's road networks (map.net.xml) to be offset from the origin. if not specified, creates '{}' if necessary.".format(
SumoRoadNetwork.shifted_net_file_name
),
)
@click.argument("scenarios", nargs=-1, metavar="<scenarios>")
def build_all_scenarios(clean, scenarios):
def build_all_scenarios(clean, allow_offset_maps, scenarios):
if not scenarios:
# nargs=-1 in combination with a default value is not supported
# if scenarios is not given, set /scenarios as default
Expand All @@ -117,7 +144,7 @@ def build_all_scenarios(clean, scenarios):
for p in path.rglob("*.net.xml"):
scenario = f"{scenarios_path}/{p.parent.relative_to(scenarios_path)}"
builder_thread = Thread(
target=_build_single_scenario, args=(clean, scenario)
target=_build_single_scenario, args=(clean, allow_offset_maps, scenario)
)
builder_thread.start()
builder_threads[p] = builder_thread
Expand All @@ -136,6 +163,7 @@ def clean_scenario(scenario):
def _clean(scenario):
to_be_removed = [
"map.glb",
SumoRoadNetwork.shifted_net_file_name,
"bubbles.pkl",
"missions.pkl",
"flamegraph-perf.log",
Expand Down
4 changes: 3 additions & 1 deletion smarts/core/scenario.py
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,9 @@ def __init__(
self.traffic_history_lane_width if traffic_history else None
)
net_file = os.path.join(self._root, "map.net.xml")
self._road_network = SumoRoadNetwork.from_file(net_file, default_lane_width)
self._road_network = SumoRoadNetwork.from_file(
net_file, default_lane_width=default_lane_width
)
self._net_file_hash = file_md5_hash(self._road_network.net_file)
self._waypoints = Waypoints(self._road_network, spacing=1.0)
self._scenario_hash = path2hash(str(Path(self.root_filepath).resolve()))
Expand Down
42 changes: 20 additions & 22 deletions smarts/core/sumo_road_network.py
Original file line number Diff line number Diff line change
Expand Up @@ -107,14 +107,19 @@ def _check_net_origin(bbox):
assert len(bbox) == 4
return bbox[0] <= 0.0 and bbox[1] <= 0.0 and bbox[2] >= 0.0 and bbox[3] >= 0.0

shifted_net_file_name = "shifted_map-AUTOGEN.net.xml"

@classmethod
@lru_cache(maxsize=1)
def _shift_coordinates(cls, net_file_path):
def shifted_net_file_path(cls, net_file_path):
net_file_folder = os.path.dirname(net_file_path)
out_path = os.path.join(net_file_folder, f"shifted_map-AUTOGEN.net.xml")
assert out_path != net_file_path
return os.path.join(net_file_folder, cls.shifted_net_file_name)

@classmethod
@lru_cache(maxsize=1)
def _shift_coordinates(cls, net_file_path, shifted_path):
assert shifted_path != net_file_path
logger = logging.getLogger(cls.__name__)
logger.info(f"normalizing net coordinates into {out_path}...")
logger.info(f"normalizing net coordinates into {shifted_path}...")
## Translate the map's origin to remove huge (imprecise) offsets.
## See https://sumo.dlr.de/docs/netconvert.html#usage_description
## for netconvert options description.
Expand All @@ -126,37 +131,29 @@ def _shift_coordinates(cls, net_file_path):
"-s",
net_file_path,
"-o",
out_path,
shifted_path,
]
)
logger.debug(f"netconvert output: {stdout}")
return out_path
return True
except Exception as e:
logger.warning(
f"unable to use netconvert tool to normalize coordinates: {e}"
)
return None
return False

@classmethod
def from_file(cls, net_file, default_lane_width=None):
def from_file(cls, net_file, shift_to_origin=False, default_lane_width=None):
# Connections to internal lanes are implicit. If `withInternal=True` is
# set internal junctions and the connections from internal lanes are
# loaded into the network graph.
G = sumolib.net.readNet(net_file, withInternal=True)

# check to see if we need to shift the map...
# if it already has an offset, it's probably been shifted
# correctly already, so we don't need to do it. if not,
# then we check to see if the graph's bounding box includes
# the origin, and then shift it ourselves if not.
original_offset = G.getLocationOffset()
if (
original_offset[0] == 0
and original_offset[1] == 0
and not cls._check_net_origin(G.getBoundary())
):
shifted_net_file = cls._shift_coordinates(net_file)
if shifted_net_file:
if not cls._check_net_origin(G.getBoundary()):
shifted_net_file = cls.shifted_net_file_path(net_file)
if os.path.isfile(shifted_net_file) or (
shift_to_origin and cls._shift_coordinates(net_file, shifted_net_file)
):
G = sumolib.net.readNet(shifted_net_file, withInternal=True)
assert cls._check_net_origin(G.getBoundary())
net_file = shifted_net_file
Expand All @@ -167,6 +164,7 @@ def from_file(cls, net_file, default_lane_width=None):
# the offset should not be used (because all their other
# coordinates are relative to the origin).
G._shifted_by_smarts = True

return cls(G, net_file, default_lane_width)

@property
Expand Down
5 changes: 0 additions & 5 deletions smarts/core/sumo_traffic_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -597,11 +597,6 @@ def _compute_traffic_vehicles(self) -> List[VehicleState]:
speed = sumo_vehicle[tc.VAR_SPEED]
vehicle_type = sumo_vehicle[tc.VAR_VEHICLECLASS]
dimensions = VEHICLE_CONFIGS[vehicle_type].dimensions
# adjust sumo vehicle location if we shifted the map
map_offset = self._scenario.road_network.net_offset
assert len(map_offset) == 2
front_bumper_pos[0] += map_offset[0]
front_bumper_pos[1] += map_offset[1]
Copy link
Contributor

@JingfeiPeng JingfeiPeng Apr 26, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

To confirm, the reason why these are no longer needs is because when building the scenario, it is already using the shifted map thus traffic vehicle coordinates are shifted when built? Please correct me if otherwise.

This part is also somewhat needed when running third-party simulators that add traffic directly to sumo right? if so, it is possible to have a configurable option in sumo_traffic_simulation to control shift coordinates or not.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, actually the reason is that, as of PR #727 , Sumo is started with the shifted map (thanks to the update to the --net-file parameter in _base_sumo_load_params() in sumo_traffic_simulation.py), so its coordinate system matches the coordinate system in use within Smarts. Vehicle locations coming from Sumo via Traci will be relative to the shifted/offset map already.

However, any third-party simulator that is adding vehicles to Sumo directly (outside of Smarts) may not know about the fact that the scenario map was shifted before Sumo was started. If they were to try to add vehicles to the map via Traci using the original coordinate system, things would seem off to them. So that's what necessitated adding the option to prevent map shifting entirely (i.e., not here, but where the scenario is built) in such situations.

provider_vehicles.append(
VehicleState(
# XXX: In the case of the SUMO traffic provider, the vehicle ID is
Expand Down
2 changes: 1 addition & 1 deletion smarts/sstudio/generators.py
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ def plan_and_save(
# Validates, and runs route planner
self._duarouter(
unsorted_input=True,
net_file=self._road_network_path,
net_file=self.road_network.net_file,
route_files=trips_path,
output_file=route_path,
seed=seed,
Expand Down