From ce1d17b99c86c95ecf2b72837ff535fbb9e52dd7 Mon Sep 17 00:00:00 2001 From: adai Date: Mon, 28 Mar 2022 23:39:01 +0000 Subject: [PATCH] GitHub Actions: Format --- envision/server.py | 3 ++- smarts/core/agent_manager.py | 11 +++++--- smarts/core/bubble_manager.py | 6 ++--- smarts/core/chassis.py | 1 + smarts/core/plan.py | 3 ++- smarts/core/sensors.py | 4 ++- smarts/core/tests/test_notebook.py | 1 + smarts/core/tests/test_observations.py | 2 +- smarts/core/tests/test_renderers.py | 3 ++- .../test_trajectory_interpolation_provider.py | 2 +- smarts/core/utils/import_utils.py | 2 +- smarts/core/vehicle.py | 11 +++++--- smarts/core/vehicle_index.py | 2 +- smarts/env/wrappers/frame_stack.py | 2 +- .../ros/src/smarts_ros/scripts/ros_driver.py | 26 +++++++++++-------- .../src/smarts_ros/scripts/test_smarts_ros.py | 2 +- ultra/tests/test_episode.py | 7 ++--- ultra/tests/test_evaluate.py | 7 +++-- ultra/ultra/evaluate.py | 2 +- zoo/policies/open-agent/open_agent/agent.py | 1 + 20 files changed, 58 insertions(+), 40 deletions(-) diff --git a/envision/server.py b/envision/server.py index 0a07044839..7f6ddb7dae 100644 --- a/envision/server.py +++ b/envision/server.py @@ -53,7 +53,8 @@ # Mapping of simulation ID to the Frames data store FRAMES = {} -class AllowCORSMixin(): + +class AllowCORSMixin: """A mixin that adds CORS headers to the page.""" _HAS_DYNAMIC_ATTRIBUTES = True diff --git a/smarts/core/agent_manager.py b/smarts/core/agent_manager.py index 0c4ef84203..a73ffc29a2 100644 --- a/smarts/core/agent_manager.py +++ b/smarts/core/agent_manager.py @@ -19,7 +19,7 @@ # THE SOFTWARE. import logging -from typing import Any, Dict, Set, Tuple, Optional, Union +from typing import Any, Dict, Optional, Set, Tuple, Union import cloudpickle @@ -161,7 +161,10 @@ def observe_from( def observe( self, sim ) -> Tuple[ - Dict[str, Union[Dict[str, Observation], Observation]], Dict[str, Union[Dict[str, float], float]], Dict[str, Union[Dict[str, float], float]], Dict[str, Union[Dict[str, bool], bool]] + Dict[str, Union[Dict[str, Observation], Observation]], + Dict[str, Union[Dict[str, float], float]], + Dict[str, Union[Dict[str, float], float]], + Dict[str, Union[Dict[str, bool], bool]], ]: """Generate observations from all vehicles associated with an active agent.""" observations = {} @@ -224,7 +227,7 @@ def observe( else: logging.log( logging.DEBUG, - f"Agent `{agent_id}` has raised done with {obs.events}", + f"Agent `{agent_id}` has raised done with {obs.events}", ) rewards[agent_id] = vehicle.trip_meter_sensor(increment=True) @@ -234,7 +237,7 @@ def observe( dones = {agent_id: True for agent_id in self.agent_ids} dones["__sim__"] = True - return observations, rewards, scores, dones + return observations, rewards, scores, dones def _vehicle_reward(self, vehicle_id, sim) -> float: return sim.vehicle_index.vehicle_by_id(vehicle_id).trip_meter_sensor( diff --git a/smarts/core/bubble_manager.py b/smarts/core/bubble_manager.py index f0a0c75565..f6779c887e 100644 --- a/smarts/core/bubble_manager.py +++ b/smarts/core/bubble_manager.py @@ -187,12 +187,12 @@ def admissibility( # pytype: disable=unsupported-operands all_hijacked_vehicle_ids = ( current_hijacked_vehicle_ids - | vehicle_ids_by_bubble_state[BubbleState.InAirlock][self] + | vehicle_ids_by_bubble_state[BubbleState.InAirlock][self] ) - {vehicle_id} all_shadowed_vehicle_ids = ( current_shadowed_vehicle_ids - | vehicle_ids_by_bubble_state[BubbleState.InBubble][self] + | vehicle_ids_by_bubble_state[BubbleState.InBubble][self] ) - {vehicle_id} # pytype: enable=unsupported-operands @@ -510,7 +510,7 @@ def _airlock_social_vehicle_with_social_agent( ) if social_agent is None: - return + return self._start_social_agent( sim, agent_id, social_agent, social_agent_actor, bubble diff --git a/smarts/core/chassis.py b/smarts/core/chassis.py index f4aabca2da..37c7ecc61f 100644 --- a/smarts/core/chassis.py +++ b/smarts/core/chassis.py @@ -183,6 +183,7 @@ def set_pose(self, pose: Pose): chassis.""" raise NotImplementedError + class BoxChassis(Chassis): """Control a vehicle by setting its absolute position and heading. The collision shape of the vehicle is a box of the provided dimensions. diff --git a/smarts/core/plan.py b/smarts/core/plan.py index 7197d0aee3..dd114e90e5 100644 --- a/smarts/core/plan.py +++ b/smarts/core/plan.py @@ -23,10 +23,11 @@ import math import random -import numpy as np from dataclasses import dataclass, field from typing import Optional, Tuple, Union +import numpy as np + from smarts.sstudio.types import EntryTactic, TrapEntryTactic from .coordinates import Dimensions, Heading, Point, Pose, RefLinePoint diff --git a/smarts/core/sensors.py b/smarts/core/sensors.py index 4da79ec7bd..c57920e8fb 100644 --- a/smarts/core/sensors.py +++ b/smarts/core/sensors.py @@ -217,7 +217,9 @@ class Sensors: _log = logging.getLogger("Sensors") @staticmethod - def observe_batch(sim, agent_id, sensor_states, vehicles) -> Tuple[Dict[str, Observation], Dict[str, bool]]: + def observe_batch( + sim, agent_id, sensor_states, vehicles + ) -> Tuple[Dict[str, Observation], Dict[str, bool]]: """Operates all sensors on a batch of vehicles for a single agent.""" # TODO: Replace this with a more efficient implementation that _actually_ # does batching diff --git a/smarts/core/tests/test_notebook.py b/smarts/core/tests/test_notebook.py index e310c2a607..25c707bbdd 100644 --- a/smarts/core/tests/test_notebook.py +++ b/smarts/core/tests/test_notebook.py @@ -92,6 +92,7 @@ def notebook(): _, tmppath = tempfile.mkstemp(suffix=".ipynb") with open(tmppath, "w") as f: import smarts.core.tests + # pytype: disable=module-attr f.write(importlib_resources.read_text(smarts.core.tests, NOTEBOOK_NAME)) # pytype: enable=module-attr diff --git a/smarts/core/tests/test_observations.py b/smarts/core/tests/test_observations.py index 104c2dbb5c..f1f2cf5fd1 100644 --- a/smarts/core/tests/test_observations.py +++ b/smarts/core/tests/test_observations.py @@ -24,7 +24,7 @@ import gym import numpy as np import pytest -from panda3d.core import OrthographicLens, Point2, Point3 +from panda3d.core import OrthographicLens, Point2, Point3 from smarts.core.agent import Agent from smarts.core.agent_interface import ( diff --git a/smarts/core/tests/test_renderers.py b/smarts/core/tests/test_renderers.py index a5eb95b7ba..eaf7e93000 100644 --- a/smarts/core/tests/test_renderers.py +++ b/smarts/core/tests/test_renderers.py @@ -84,7 +84,8 @@ def smarts_wo_renderer(): @pytest.fixture def scenario(): mission = Mission( - start=Start(np.array([71.65, 63.78]), Heading(math.pi * 0.91)), goal=EndlessGoal() + start=Start(np.array([71.65, 63.78]), Heading(math.pi * 0.91)), + goal=EndlessGoal(), ) scenario = Scenario( scenario_root="scenarios/loop", diff --git a/smarts/core/tests/test_trajectory_interpolation_provider.py b/smarts/core/tests/test_trajectory_interpolation_provider.py index 210d5ba137..737917192b 100644 --- a/smarts/core/tests/test_trajectory_interpolation_provider.py +++ b/smarts/core/tests/test_trajectory_interpolation_provider.py @@ -299,7 +299,7 @@ def test_trajectory_interpolation_provider_in_smarts(smarts, agent_spec, scenari if agent_obs.events.reached_goal: reached_goal = True break - + curr_position = agent_obs.ego_vehicle_state.position curr_heading = agent_obs.ego_vehicle_state.heading curr_speed = agent_obs.ego_vehicle_state.speed diff --git a/smarts/core/utils/import_utils.py b/smarts/core/utils/import_utils.py index 4d3eaf99dd..12d0e5c03e 100644 --- a/smarts/core/utils/import_utils.py +++ b/smarts/core/utils/import_utils.py @@ -33,4 +33,4 @@ def import_module_from_file(module_name, path: Path): spec = importlib.util.spec_from_file_location(module_name, f"{path}") module = importlib.util.module_from_spec(spec) sys.modules[module_name] = module - spec.loader.exec_module(module) # pytype: disable=attribute-error + spec.loader.exec_module(module) # pytype: disable=attribute-error diff --git a/smarts/core/vehicle.py b/smarts/core/vehicle.py index 943ac03c50..6fac53284f 100644 --- a/smarts/core/vehicle.py +++ b/smarts/core/vehicle.py @@ -22,7 +22,7 @@ import os from dataclasses import dataclass from functools import lru_cache -from typing import Any, Dict, List, Tuple, Optional, Sequence, Union +from typing import Any, Dict, List, Optional, Sequence, Tuple, Union import numpy as np @@ -31,7 +31,7 @@ from . import models from .chassis import AckermannChassis, BoxChassis, Chassis -from .colors import SceneColors, Colors +from .colors import Colors, SceneColors from .coordinates import Dimensions, Heading, Pose from .sensors import ( AccelerometerSensor, @@ -142,7 +142,8 @@ class VehicleConfig: class Vehicle: """Represents a single vehicle.""" - _HAS_DYNAMIC_ATTRIBUTES=True + + _HAS_DYNAMIC_ATTRIBUTES = True _HAS_DYNAMIC_ATTRIBUTES = True # pytype dynamic @@ -385,7 +386,9 @@ def build_agent_vehicle( else: start_pose = Pose.from_center(start.position, start.heading) - vehicle_color = SceneColors.Agent.value if trainable else SceneColors.SocialAgent.value + vehicle_color = ( + SceneColors.Agent.value if trainable else SceneColors.SocialAgent.value + ) if agent_interface.vehicle_type == "sedan": urdf_name = "vehicle" diff --git a/smarts/core/vehicle_index.py b/smarts/core/vehicle_index.py index bd9639a655..cf15fc6c1d 100644 --- a/smarts/core/vehicle_index.py +++ b/smarts/core/vehicle_index.py @@ -463,7 +463,7 @@ def stop_agent_observation(self, vehicle_id): vehicle = self._vehicles[vehicle_id] # pytype: disable=attribute-error - Vehicle.detach_all_sensors_from_vehicle(vehicle) + Vehicle.detach_all_sensors_from_vehicle(vehicle) # pytype: enable=attribute-error v_index = self._controlled_by["vehicle_id"] == vehicle_id diff --git a/smarts/env/wrappers/frame_stack.py b/smarts/env/wrappers/frame_stack.py index b20980fd94..d9ab5718d7 100644 --- a/smarts/env/wrappers/frame_stack.py +++ b/smarts/env/wrappers/frame_stack.py @@ -71,7 +71,7 @@ def _get_observations( frames_list = list(self._frames[agent_id]) new_frames[agent_id] = copy.deepcopy(frames_list) - return dict(new_frames) + return dict(new_frames) def step( self, agent_actions: Dict diff --git a/smarts/ros/src/smarts_ros/scripts/ros_driver.py b/smarts/ros/src/smarts_ros/scripts/ros_driver.py index 8205da30bd..f2625513ed 100755 --- a/smarts/ros/src/smarts_ros/scripts/ros_driver.py +++ b/smarts/ros/src/smarts_ros/scripts/ros_driver.py @@ -28,7 +28,7 @@ from threading import Lock from typing import Any, Dict, Optional, Sequence, Tuple -import numpy as np +import numpy as np import rospy from smarts_ros.msg import ( AgentReport, @@ -41,7 +41,7 @@ from smarts_ros.srv import SmartsInfo, SmartsInfoRequest, SmartsInfoResponse from envision.client import Client as Envision -from smarts.core.coordinates import Dimensions, Heading, Pose, Point +from smarts.core.coordinates import Dimensions, Heading, Point, Pose from smarts.core.plan import ( EndlessGoal, Mission, @@ -283,13 +283,17 @@ def _decode_vehicle_type(vehicle_type: int) -> str: @staticmethod def _pose_from_ros(ros_pose) -> Pose: return Pose( - position=np.array([ros_pose.position.x, ros_pose.position.y, ros_pose.position.z]), - orientation=np.array([ - ros_pose.orientation.x, - ros_pose.orientation.y, - ros_pose.orientation.z, - ros_pose.orientation.w, - ]), + position=np.array( + [ros_pose.position.x, ros_pose.position.y, ros_pose.position.z] + ), + orientation=np.array( + [ + ros_pose.orientation.x, + ros_pose.orientation.y, + ros_pose.orientation.z, + ros_pose.orientation.w, + ] + ), ) def _agent_spec_callback(self, ros_agent_spec: AgentSpec): @@ -299,7 +303,7 @@ def _agent_spec_callback(self, ros_agent_spec: AgentSpec): task = ros_agent_spec.tasks[0] task_params = json.loads(task.params_json) if task.params_json else {} task_version = task.task_ver or "latest" - agent_locator = f"{self._zoo_module}:{task.task_ref}-{task_version}" # pytype: disable=attribute-error + agent_locator = f"{self._zoo_module}:{task.task_ref}-{task_version}" # pytype: disable=attribute-error agent_spec = None try: agent_spec = registry.make(agent_locator, **task_params) @@ -647,7 +651,7 @@ def run_forever(self): raise RuntimeError("must call setup_smarts() first.") # pytype: disable=attribute-error - rospy.Service(self._service_name, SmartsInfo, self._get_smarts_info) + rospy.Service(self._service_name, SmartsInfo, self._get_smarts_info) # pytype: enable=attribute-error warned_scenario = False diff --git a/smarts/ros/src/smarts_ros/scripts/test_smarts_ros.py b/smarts/ros/src/smarts_ros/scripts/test_smarts_ros.py index 8d370fe946..b1b868b5a8 100644 --- a/smarts/ros/src/smarts_ros/scripts/test_smarts_ros.py +++ b/smarts/ros/src/smarts_ros/scripts/test_smarts_ros.py @@ -150,7 +150,7 @@ def _reset_callback(self, reset_msg: SmartsReset): self._create_agent() for agent_spec in self._agents.values(): # pytype: disable=attribute-error - self._agent_publisher.publish(agent_spec) + self._agent_publisher.publish(agent_spec) # pytype: enable=attribute-error def run_forever(self): diff --git a/ultra/tests/test_episode.py b/ultra/tests/test_episode.py index 170ff40e3e..a117c61647 100644 --- a/ultra/tests/test_episode.py +++ b/ultra/tests/test_episode.py @@ -28,7 +28,7 @@ import ray from smarts.zoo.registry import make -from ultra.utils.episode import episodes, Episode +from ultra.utils.episode import Episode, episodes AGENT_ID = "001" timestep_sec = 0.1 @@ -36,6 +36,7 @@ task_id = "00" task_level = "easy" + class EpisodeTest(unittest.TestCase): # Put generated files and folders in this directory. OUTPUT_DIRECTORY = "tests/episode_test/" @@ -115,8 +116,8 @@ def run_experiment(): # # abs(result[key] - episode_info["Train"][AGENT_ID].data[key]) <= 0.001 # # ) - @unittest.skip("Experiment test is not necessary at this time.") - def test_episode_counter(self): + @unittest.skip("Experiment test is not necessary at this time.") + def test_episode_counter(self): @ray.remote(max_calls=1, num_gpus=0, num_cpus=1) def run_experiment(): agent, env = prepare_test_env_agent() diff --git a/ultra/tests/test_evaluate.py b/ultra/tests/test_evaluate.py index d75a54f82a..f71be110a2 100644 --- a/ultra/tests/test_evaluate.py +++ b/ultra/tests/test_evaluate.py @@ -27,8 +27,7 @@ import time import unittest - -import dill +import dill import gym import ray @@ -378,7 +377,7 @@ def extract(path): ) try: - policy_class = m.group(0) # pytype: disable=attribute-error + policy_class = m.group(0) # pytype: disable=attribute-error except AttributeError as e: self.assertTrue(False) @@ -472,7 +471,7 @@ def run_experiment(scenario_info, num_agents, log_dir, headless=True): active_agent_ids = observations.keys() & next_observations.keys() # pytype: disable=attribute-error loss_outputs = { - agent_id: agents[agent_id].step( + agent_id: agents[agent_id].step( state=observations[agent_id], action=actions[agent_id], reward=rewards[agent_id], diff --git a/ultra/ultra/evaluate.py b/ultra/ultra/evaluate.py index cb3fd903b5..2c73fd7ce2 100644 --- a/ultra/ultra/evaluate.py +++ b/ultra/ultra/evaluate.py @@ -21,7 +21,7 @@ # THE SOFTWARE. import os import pickle -from typing import Sequence, Tuple, Optional +from typing import Optional, Sequence, Tuple # Set environment to better support Ray os.environ["MKL_NUM_THREADS"] = "1" diff --git a/zoo/policies/open-agent/open_agent/agent.py b/zoo/policies/open-agent/open_agent/agent.py index 0ae9b613b8..f387823624 100644 --- a/zoo/policies/open-agent/open_agent/agent.py +++ b/zoo/policies/open-agent/open_agent/agent.py @@ -23,6 +23,7 @@ # pytype: disable=attribute-error + def angle_error(a, b): return cs.fabs(