From 597c83545c39f65e9a8bff587f8aa21e51f10679 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Sun, 4 Aug 2024 03:41:27 -0400 Subject: [PATCH 01/55] Implemented scaling down parameter --- f1tenth_gym/envs/base_classes.py | 10 +- f1tenth_gym/envs/f110_env.py | 169 +++++++++++++++++++++++++---- f1tenth_gym/envs/laser_models.py | 7 +- f1tenth_gym/envs/track/raceline.py | 28 ++++- f1tenth_gym/envs/track/track.py | 12 +- 5 files changed, 193 insertions(+), 33 deletions(-) diff --git a/f1tenth_gym/envs/base_classes.py b/f1tenth_gym/envs/base_classes.py index f5990dc6..ce296f57 100644 --- a/f1tenth_gym/envs/base_classes.py +++ b/f1tenth_gym/envs/base_classes.py @@ -178,14 +178,15 @@ def update_params(self, params): """ self.params = params - def set_map(self, map: str | Track): + def set_map(self, map: str | Track, map_scale: float = 1.0): """ Sets the map for scan simulator Args: map (str | Track): name of the map, or Track object + map_scale (float, default=1.0): scale of the map, larger scale means larger map """ - RaceCar.scan_simulator.set_map(map) + RaceCar.scan_simulator.set_map(map, map_scale) def reset(self, pose): """ @@ -431,18 +432,19 @@ def __init__( num_beams = self.agents[0].scan_simulator.num_beams self.agent_scans = np.empty((self.num_agents, num_beams)) - def set_map(self, map: str | Track): + def set_map(self, map: str | Track, map_scale: float = 1.0): """ Sets the map of the environment and sets the map for scan simulator of each agent Args: map (str | Track): name of the map, or Track object + map_scale (float, default=1.0): scale of the map, larger scale means larger map Returns: None """ for agent in self.agents: - agent.set_map(map) + agent.set_map(map, map_scale) def update_params(self, params, agent_idx=-1): """ diff --git a/f1tenth_gym/envs/f110_env.py b/f1tenth_gym/envs/f110_env.py index b365271e..ba301e76 100644 --- a/f1tenth_gym/envs/f110_env.py +++ b/f1tenth_gym/envs/f110_env.py @@ -143,13 +143,14 @@ def __init__(self, config: dict = None, render_mode=None, **kwargs): model=self.model, action_type=self.action_type, ) - self.sim.set_map(self.map) + self.sim.set_map(self.map, config["scale"]) if isinstance(self.map, Track): self.track = self.map else: self.track = Track.from_track_name( - self.map + self.map, + track_scale=config["scale"], ) # load track in gym env for convenience # observations @@ -188,6 +189,148 @@ def __init__(self, config: dict = None, render_mode=None, **kwargs): render_fps=self.metadata["render_fps"], ) + @classmethod + def fullscale_vehicle_params(cls) -> dict: + params = { + "mu": 1.0489, + "C_Sf": 4.718, + "C_Sr": 5.4562, + "lf": 0.88392, + "lr": 1.50876, + "h": 0.074, + "m": 1225.8878467253344, + "I": 1538.8533713561394, + "width": 1.674, + "length": 4.298, + + # steering constraints + "s_min": -0.91, + "s_max": 0.91, + "sv_min": -0.4, + "sv_max": 0.4, + # maximum curvature change + "kappa_dot_max": 0.4, + # maximum curvature rate rate + "kappa_dot_dot_max": 20, + + # Longitudinal constraints + "v_switch": 4.755, + "a_max": 11.5, + "v_min": -13.9, + "v_max": 45.8, + # maximum longitudinal jerk [m/s^3] + "j_max": 10.0e+3, + # maximum longitudinal jerk change [m/s^4] + "j_dot_max": 10.0e3, + + # Extra parameters (for future use in multibody simulation) + # sprung mass [kg] SMASS + "m_s": 1094.542720290477, + # unsprung mass front [kg] UMASSF + "m_uf": 65.67256321742863, + # unsprung mass rear [kg] UMASSR + "m_ur": 65.67256321742863, + + # moments of inertia of sprung mass + # moment of inertia for sprung mass in roll [kg m^2] IXS + "I_Phi_s": 244.04723069965206, + # moment of inertia for sprung mass in pitch [kg m^2] IYS + "I_y_s": 1342.2597688480864, + # moment of inertia for sprung mass in yaw [kg m^2] IZZ + "I_z": 1538.8533713561394, + # moment of inertia cross product [kg m^2] IXZ + "I_xz_s": 0.0, + + # suspension parameters + # suspension spring rate (front) [N/m] KSF + "K_sf": 21898.332429625985, + # suspension damping rate (front) [N s/m] KSDF + "K_sdf": 1459.3902937206362, + # suspension spring rate (rear) [N/m] KSR + "K_sr": 21898.332429625985, + # suspension damping rate (rear) [N s/m] KSDR + "K_sdr": 1459.3902937206362, + + # geometric parameters + # track width front [m] TRWF + "T_f": 1.389888, + # track width rear [m] TRWB + "T_r": 1.423416, + # lateral spring rate at compliant compliant pin joint between M_s and M_u [N/m] KRAS + "K_ras": 175186.65943700788, + + # auxiliary torsion roll stiffness per axle (normally negative) (front) [N m/rad] KTSF + "K_tsf": -12880.270509148304, + # auxiliary torsion roll stiffness per axle (normally negative) (rear) [N m/rad] KTSR + "K_tsr": 0.0, + # damping rate at compliant compliant pin joint between M_s and M_u [N s/m] KRADP + "K_rad": 10215.732056044453, + # vertical spring rate of tire [N/m] KZT + "K_zt": 189785.5477234252, + + # center of gravity height of total mass [m] HCG (mainly required for conversion to other vehicle models) + "h_cg": 0.5577840000000001, + # height of roll axis above ground (front) [m] HRAF + "h_raf": 0.0, + # height of roll axis above ground (rear) [m] HRAR + "h_rar": 0.0, + + # M_s center of gravity above ground [m] HS + "h_s": 0.59436, + + # moment of inertia for unsprung mass about x-axis (front) [kg m^2] IXUF + "I_uf": 32.53963075995361, + # moment of inertia for unsprung mass about x-axis (rear) [kg m^2] IXUR + "I_ur": 32.53963075995361, + # wheel inertia, from internet forum for 235/65 R 17 [kg m^2] + "I_y_w": 1.7, + + # lateral compliance rate of tire, wheel, and suspension, per tire [m/N] KLT + "K_lt": 1.0278264878518764e-05, + # effective wheel/tire radius chosen as tire rolling radius RR taken from ADAMS documentation [m] + "R_w": 0.344, + + # split of brake and engine torque + "T_sb": 0.76, + "T_se": 1, + + # suspension parameters + # [rad/m] DF + "D_f": -0.6233595800524934, + # [rad/m] DR + "D_r": -0.20997375328083986, + # [needs conversion if nonzero] EF + "E_f": 0, + # [needs conversion if nonzero] ER + "E_r": 0, + + } + return params + + @classmethod + def f1tenth_vehicle_params(cls) -> dict: + params = { + "mu": 1.0489, + "C_Sf": 4.718, + "C_Sr": 5.4562, + "lf": 0.15875, + "lr": 0.17145, + "h": 0.074, + "m": 3.74, + "I": 0.04712, + "s_min": -0.4189, + "s_max": 0.4189, + "sv_min": -3.2, + "sv_max": 3.2, + "v_switch": 7.319, + "a_max": 9.51, + "v_min": -5.0, + "v_max": 20.0, + "width": 0.31, + "length": 0.58, + } + return params + @classmethod def default_config(cls) -> dict: """ @@ -204,26 +347,8 @@ def default_config(cls) -> dict: return { "seed": 12345, "map": "Spielberg", - "params": { - "mu": 1.0489, - "C_Sf": 4.718, - "C_Sr": 5.4562, - "lf": 0.15875, - "lr": 0.17145, - "h": 0.074, - "m": 3.74, - "I": 0.04712, - "s_min": -0.4189, - "s_max": 0.4189, - "sv_min": -3.2, - "sv_max": 3.2, - "v_switch": 7.319, - "a_max": 9.51, - "v_min": -5.0, - "v_max": 20.0, - "width": 0.31, - "length": 0.58, - }, + "scale": 1.0, + "params": cls.f1tenth_vehicle_params(), "num_agents": 2, "timestep": 0.01, "ego_idx": 0, diff --git a/f1tenth_gym/envs/laser_models.py b/f1tenth_gym/envs/laser_models.py index 8d3c2e9b..bd400507 100644 --- a/f1tenth_gym/envs/laser_models.py +++ b/f1tenth_gym/envs/laser_models.py @@ -458,18 +458,19 @@ def __init__(self, num_beams, fov, eps=0.0001, theta_dis=2000, max_range=30.0): self.sines = np.sin(theta_arr) self.cosines = np.cos(theta_arr) - def set_map(self, map: str | Track): + def set_map(self, map: str | Track, map_scale: float = 1.0) -> bool: """ Set the bitmap of the scan simulator by path Args: map (str | Track): path to the map file, or Track object + map_scale (float, default=1.0): scale of the map, larger scale means larger map Returns: flag (bool): if image reading and loading is successful """ if isinstance(map, str): - self.track = Track.from_track_name(map) + self.track = Track.from_track_name(map, map_scale) elif isinstance(map, Track): self.track = map @@ -479,7 +480,7 @@ def set_map(self, map: str | Track): self.map_width = self.map_img.shape[1] # load map specification - self.map_resolution = self.track.spec.resolution + self.map_resolution = self.track.spec.resolution * map_scale self.origin = self.track.spec.origin self.orig_x = self.origin[0] diff --git a/f1tenth_gym/envs/track/raceline.py b/f1tenth_gym/envs/track/raceline.py index 9215596f..6394b878 100644 --- a/f1tenth_gym/envs/track/raceline.py +++ b/f1tenth_gym/envs/track/raceline.py @@ -70,6 +70,7 @@ def from_centerline_file( filepath: pathlib.Path, delimiter: Optional[str] = ",", fixed_speed: Optional[float] = 1.0, + track_scale: Optional[float] = 1.0, ): """ Load raceline from a centerline file. @@ -82,6 +83,8 @@ def from_centerline_file( delimiter used in the file, by default "," fixed_speed : float, optional fixed speed along the raceline, by default 1.0 + track_scale : float, optional + scaling factor for the track, by default 1.0 Returns ------- @@ -94,6 +97,9 @@ def from_centerline_file( # fit cubic spline to waypoints xx, yy = waypoints[:, 0], waypoints[:, 1] + # scale waypoints + xx, yy = xx * track_scale, yy * track_scale + # close loop xx = np.append(xx, xx[0]) yy = np.append(yy, yy[0]) @@ -125,7 +131,7 @@ def from_centerline_file( ) @staticmethod - def from_raceline_file(filepath: pathlib.Path, delimiter: str = ";"): + def from_raceline_file(filepath: pathlib.Path, delimiter: str = ";", track_scale: Optional[float] = 1.0) -> Raceline: """ Load raceline from a raceline file. @@ -135,6 +141,8 @@ def from_raceline_file(filepath: pathlib.Path, delimiter: str = ";"): path to the raceline file delimiter : str, optional delimiter used in the file, by default ";" + track_scale : float, optional + scaling factor for the track, by default 1.0 Returns ------- @@ -143,6 +151,24 @@ def from_raceline_file(filepath: pathlib.Path, delimiter: str = ";"): """ assert filepath.exists(), f"input filepath does not exist ({filepath})" waypoints = np.loadtxt(filepath, delimiter=delimiter).astype(np.float32) + + if track_scale != 1.0: + # scale x-y waypoints and recalculate s, psi, and k + waypoints[:, 1] *= track_scale + waypoints[:, 2] *= track_scale + spline = CubicSpline2D(x=waypoints[:, 1], y=waypoints[:, 2]) + ss, yaws, ks = [], [], [] + for (x, y) in zip(waypoints[:, 1], waypoints[:, 2]): + i_s, _ = spline.calc_arclength(x, y) + yaw = spline.calc_yaw(i_s) + k = spline.calc_curvature(i_s) + yaws.append(yaw) + ks.append(k) + ss.append(i_s) + waypoints[:, 0] = ss + waypoints[:, 3] = yaws + waypoints[:, 4] = ks + assert ( waypoints.shape[1] == 7 ), "expected waypoints as [s, x, y, psi, k, vx, ax]" diff --git a/f1tenth_gym/envs/track/track.py b/f1tenth_gym/envs/track/track.py index c6a0d973..ba2d9108 100644 --- a/f1tenth_gym/envs/track/track.py +++ b/f1tenth_gym/envs/track/track.py @@ -91,7 +91,7 @@ def load_spec(track: str, filespec: str) -> TrackSpec: return track_spec @staticmethod - def from_track_name(track: str): + def from_track_name(track: str, track_scale: float = 1.0) -> Track: """ Load track from track name. @@ -99,6 +99,8 @@ def from_track_name(track: str): ---------- track : str name of the track + track_scale : float, optional + scale of the track, by default 1.0 Returns ------- @@ -121,6 +123,8 @@ def from_track_name(track: str): image = Image.open(track_dir / str(map_filename)).transpose( Transpose.FLIP_TOP_BOTTOM ) + image = image.resize(np.array(track_scale * np.array(image.size, dtype=np.int32), dtype=np.int32), Image.LANCZOS) + occupancy_map = np.array(image).astype(np.float32) occupancy_map[occupancy_map <= 128] = 0.0 occupancy_map[occupancy_map > 128] = 255.0 @@ -128,7 +132,8 @@ def from_track_name(track: str): # if exists, load centerline if (track_dir / f"{track}_centerline.csv").exists(): centerline = Raceline.from_centerline_file( - track_dir / f"{track}_centerline.csv" + track_dir / f"{track}_centerline.csv", + track_scale=track_scale, ) else: centerline = None @@ -136,7 +141,8 @@ def from_track_name(track: str): # if exists, load raceline if (track_dir / f"{track}_raceline.csv").exists(): raceline = Raceline.from_raceline_file( - track_dir / f"{track}_raceline.csv" + track_dir / f"{track}_raceline.csv", + track_scale=track_scale, ) else: raceline = centerline From c625963b2ec3f9911056453ee9673af5b9163d52 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 00:00:10 -0400 Subject: [PATCH 02/55] Add pyqt rendering skeleton code --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 361 +++++++++++++++++++ 1 file changed, 361 insertions(+) create mode 100644 f1tenth_gym/envs/rendering/rendering_pyqt.py diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py new file mode 100644 index 00000000..1a99c809 --- /dev/null +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -0,0 +1,361 @@ +from __future__ import annotations +import logging +import math +from typing import Any, Callable, Optional + +import cv2 +import numpy as np +from PyQt6 import QtWidgets +import pyqtgraph as pg +from PIL import ImageColor + +from .pyqt_objects import ( + Map, + Car, + TextObject, +) +from ..track import Track +from .renderer import EnvRenderer, RenderSpec + +# one-line instructions visualized at the top of the screen (if show_info=True) +INSTRUCTION_TEXT = "Mouse click (L/M/R): Change POV - 'S' key: On/Off" + + +class PyQtEnvRenderer(EnvRenderer): + """ + Renderer of the environment using PyQtGraph. + """ + + def __init__( + self, + params: dict[str, Any], + track: Track, + agent_ids: list[str], + render_spec: RenderSpec, + render_mode: str, + render_fps: int, + ): + """ + Initialize the Pygame renderer. + + Parameters + ---------- + params : dict + dictionary of simulation parameters (including vehicle dimensions, etc.) + track : Track + track object + agent_ids : list + list of agent ids to render + render_spec : RenderSpec + rendering specification + render_mode : str + rendering mode in ["human", "human_fast", "rgb_array"] + render_fps : int + number of frames per second + """ + super().__init__() + self.params = params + self.agent_ids = agent_ids + + self.cars = None + self.sim_time = None + self.window = None + self.canvas = None + + self.render_spec = render_spec + self.render_mode = render_mode + self.render_fps = render_fps + + colors_rgb = [ + [rgb for rgb in ImageColor.getcolor(c, "RGB")] + for c in render_spec.vehicle_palette + ] + self.car_colors = [ + colors_rgb[i % len(colors_rgb)] for i in range(len(self.agent_ids)) + ] + + width, height = render_spec.window_size, render_spec.window_size + + # map metadata + self.map_origin = track.spec.origin + self.map_resolution = track.spec.resolution + + # load map image + original_img = track.occupancy_map + + # callbacks for custom visualization, called at every rendering step + self.callbacks = [] + + # event handling flags + self.draw_flag: bool = True + if render_spec.focus_on: + self.active_map_renderer = "car" + self.follow_agent_flag: bool = True + self.agent_to_follow: int = self.agent_ids.index(render_spec.focus_on) + else: + self.active_map_renderer = "map" + self.follow_agent_flag: bool = False + self.agent_to_follow: int = None + + def update(self, state: dict) -> None: + """ + Update the simulation state to be rendered. + + Parameters + ---------- + state: simulation state as dictionary + """ + # if self.cars is None: + # self.cars = [ + # Car( + # car_length=self.params["length"], + # car_width=self.params["width"], + # color=self.car_colors[ic], + # render_spec=self.render_spec, + # map_origin=self.map_origin[:2], + # resolution=self.map_resolution, + # ppu=self.ppus[self.active_map_renderer], + # ) + # for ic in range(len(self.agent_ids)) + # ] + + # # update cars state and zoom level (updating points-per-unit) + # for i in range(len(self.agent_ids)): + # self.cars[i].update(state, i) + + # # update time + # self.sim_time = state["sim_time"] + raise NotImplementedError + + def add_renderer_callback(self, callback_fn: Callable[[EnvRenderer], None]) -> None: + """ + Add a custom callback for visualization. + All the callbacks are called at every rendering step, after having rendered the map and the cars. + + Parameters + ---------- + callback_fn : Callable[[EnvRenderer], None] + callback function to be called at every rendering step + """ + self.callbacks.append(callback_fn) + + def render(self) -> Optional[np.ndarray]: + # """ + # Render the current state in a frame. + # It renders in the order: map, cars, callbacks, info text. + + # Returns + # ------- + # Optional[np.ndarray] + # if render_mode is "rgb_array", returns the rendered frame as an array + # """ + # self.event_handling() + + # self.canvas.fill((255, 255, 255)) # white background + # self.map_canvas = self.map_canvases[self.active_map_renderer] + # self.map_canvas.fill((255, 255, 255)) # white background + + # if self.draw_flag: + # self.map_renderers[self.active_map_renderer].render(self.map_canvas) + + # # draw cars + # for i in range(len(self.agent_ids)): + # self.cars[i].render(self.map_canvas) + + # # call callbacks + # for callback_fn in self.callbacks: + # callback_fn(self) + + # surface_mod_rect = self.map_canvas.get_rect() + # screen_rect = self.canvas.get_rect() + + # if self.follow_agent_flag: + # origin = self.map_origin + # resolution = self.map_resolution * self.ppus[self.active_map_renderer] + # ego_x, ego_y = self.cars[self.agent_to_follow].pose[:2] + # cx = (ego_x - origin[0]) / resolution + # cy = (ego_y - origin[1]) / resolution + # else: + # cx = self.map_canvas.get_width() / 2 + # cy = self.map_canvas.get_height() / 2 + + # surface_mod_rect.x = screen_rect.centerx - cx + # surface_mod_rect.y = screen_rect.centery - cy + + # self.canvas.blit(self.map_canvas, surface_mod_rect) + + # agent_to_follow_id = ( + # self.agent_ids[self.agent_to_follow] + # if self.agent_to_follow is not None + # else None + # ) + # self.bottom_info_renderer.render( + # text=f"Focus on: {agent_to_follow_id}", display=self.canvas + # ) + + # if self.render_spec.show_info: + # self.top_info_renderer.render(text=INSTRUCTION_TEXT, display=self.canvas) + # self.time_renderer.render(text=f"{self.sim_time:.2f}", display=self.canvas) + + # if self.render_mode in ["human", "human_fast"]: + # assert self.window is not None + + # self.fps_renderer.render( + # text=f"FPS: {self.clock.get_fps():.2f}", display=self.canvas + # ) + + # self.window.blit(self.canvas, self.canvas.get_rect()) + + # pygame.event.pump() + # pygame.display.update() + + # # We need to ensure that human-rendering occurs at the predefined framerate. + # # The following line will automatically add a delay to keep the framerate stable. + # self.clock.tick(self.render_fps) + # else: # rgb_array + # frame = np.transpose( + # np.array(pygame.surfarray.pixels3d(self.canvas)), axes=(1, 0, 2) + # ) + # if frame.shape[0] > 2000: + # frame = cv2.resize( + # frame, dsize=(2000, 2000), interpolation=cv2.INTER_AREA + # ) + # return frame + raise NotImplementedError + + def event_handling(self) -> None: + """ + Handle interaction events to change point-of-view. + + Events: + - Left mouse button: follow next agent (according to agent_ids order) + - Right mouse button: follow previous agent + - Middle mouse button: change to map view + - S key: enable/disable rendering + """ + # for event in pygame.event.get(): + # if event.type == pygame.MOUSEBUTTONDOWN and event.button == 1: + # logging.debug("Pressed left button -> Follow Next agent") + + # self.follow_agent_flag = True + # if self.agent_to_follow is None: + # self.agent_to_follow = 0 + # else: + # self.agent_to_follow = (self.agent_to_follow + 1) % len( + # self.agent_ids + # ) + + # self.active_map_renderer = "car" + + # elif event.type == pygame.MOUSEBUTTONDOWN and event.button == 3: + # logging.debug("Pressed right button -> Follow Previous agent") + + # self.follow_agent_flag = True + # if self.agent_to_follow is None: + # self.agent_to_follow = 0 + # else: + # self.agent_to_follow = (self.agent_to_follow - 1) % len( + # self.agent_ids + # ) + + # self.active_map_renderer = "car" + + # elif event.type == pygame.MOUSEBUTTONDOWN and event.button == 2: + # logging.debug("Pressed middle button -> Change to Map View") + + # self.follow_agent_flag = False + # self.agent_to_follow = None + + # self.active_map_renderer = "map" + + # elif event.type == pygame.KEYDOWN and event.key == pygame.K_s: + # logging.debug("Pressed S key -> Enable/disable rendering") + # self.draw_flag = not (self.draw_flag) + + def render_points( + self, + points: list | np.ndarray, + color: Optional[tuple[int, int, int]] = (0, 0, 255), + size: Optional[int] = 1, + ) -> None: + """ + Render a sequence of xy points on screen. + + Parameters + ---------- + points : list | np.ndarray + list of points to render + color : Optional[tuple[int, int, int]], optional + color as rgb tuple, by default blue (0, 0, 255) + size : Optional[int], optional + size of the points in pixels, by default 1 + """ + origin = self.map_origin + ppu = self.ppus[self.active_map_renderer] + resolution = self.map_resolution * ppu + points = ((points - origin[:2]) / resolution).astype(int) + size = math.ceil(size / ppu) + + def render_lines( + self, + points: list | np.ndarray, + color: Optional[tuple[int, int, int]] = (0, 0, 255), + size: Optional[int] = 1, + ) -> None: + """ + Render a sequence of lines segments. + + Parameters + ---------- + points : list | np.ndarray + list of points to render + color : Optional[tuple[int, int, int]], optional + color as rgb tuple, by default blue (0, 0, 255) + size : Optional[int], optional + size of the line, by default 1 + """ + origin = self.map_origin + ppu = self.ppus[self.active_map_renderer] + resolution = self.map_resolution * ppu + points = ((points - origin[:2]) / resolution).astype(int) + size = math.ceil(size / ppu) + + pygame.draw.lines( + self.map_canvas, color, closed=False, points=points, width=size + ) + + def render_closed_lines( + self, + points: list | np.ndarray, + color: Optional[tuple[int, int, int]] = (0, 0, 255), + size: Optional[int] = 1, + ) -> None: + """ + Render a sequence of lines segments forming a closed loop (draw a line between the last and the first point). + + Parameters + ---------- + points : list | np.ndarray + list of 2d points to render + color : Optional[tuple[int, int, int]], optional + color as rgb tuple, by default blue (0, 0, 255) + size : Optional[int], optional + size of the line, by default 1 + """ + origin = (0, 0, 0) + ppu = 1 + resolution = 1 + points = ((points - origin[:2]) / resolution).astype(int) + size = math.ceil(size / ppu) + + pen = pg.mkPen(color=pg.mkColor(*color), width=size) + self.canvas.plot( + points[:, 0], points[:, 1], pen=pen, connect="all", fillLevel=None, antialias=True + ) ## setting pen=None disables line drawing + + + def close(self) -> None: + """ + Close the rendering environment. + """ + self.app.exit() From 8ddc384d17612b173a59de1bc50fbd727b6a9662 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 00:09:52 -0400 Subject: [PATCH 03/55] Add pyqt objects skeleton code --- f1tenth_gym/envs/rendering/pyqt_objects.py | 249 +++++++++++++++++++++ 1 file changed, 249 insertions(+) create mode 100644 f1tenth_gym/envs/rendering/pyqt_objects.py diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py new file mode 100644 index 00000000..b52e48c6 --- /dev/null +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -0,0 +1,249 @@ +from __future__ import annotations +import cv2 +import numpy as np +import pyqtgraph as pg + +from ..collision_models import get_vertices +from . import RenderSpec + + +class TextObject: + """ + Class to display text on the screen at a given position. + + Attributes + ---------- + font : pygame.font.Font + font object + position : str | tuple + position of the text on the screen + text : pygame.Surface + text surface to be displayed + """ + + def __init__( + self, + window_shape: tuple[int, int], + position: str | tuple, + relative_font_size: int = 32, + font_name: str = "Arial", + ) -> None: + """ + Initialize text object. + + Parameters + ---------- + window_shape : tuple + shape of the window (width, height) in pixels + position : str | tuple + position of the text on the screen + relative_font_size : int, optional + font size relative to the window shape, by default 32 + font_name : str, optional + font name, by default "Arial" + """ + font_size = int(relative_font_size * window_shape[0] / 1000) + # self.font = pygame.font.SysFont(font_name, font_size) + self.position = position + + self.text = self.font.render("", True, (125, 125, 125)) + + # def _position_resolver( + # self, position: str | tuple[int, int], display: pygame.Surface + # ) -> tuple[int, int]: + # """ + # This function takes strings like "bottom center" and converts them into a location for the text to be displayed. + # If position is tuple, then passthrough. + + # Parameters + # ---------- + # position : str | tuple + # position of the text on the screen + # display : pygame.Surface + # display surface + + # Returns + # ------- + # tuple + # position of the text on the screen + + # Raises + # ------ + # ValueError + # if position is not a tuple or a string + # NotImplementedError + # if position is a string but not implemented + # """ + # if isinstance(position, tuple) and len(position) == 2: + # return int(position[0]), int(position[1]) + # elif isinstance(position, str): + # position = position.lower() + # if position == "bottom_right": + # display_width, display_height = ( + # display.get_width(), + # display.get_height(), + # ) + # text_width, text_height = self.text.get_width(), self.text.get_height() + # bottom_right = ( + # display_width - text_width, + # display_height - text_height, + # ) + # return bottom_right + # elif position == "bottom_left": + # display_height = display.get_height() + # text_height = self.text.get_height() + # bottom_left = (0, display_height - text_height) + # return bottom_left + # elif position == "bottom_center": + # display_width, display_height = ( + # display.get_width(), + # display.get_height(), + # ) + # text_width, text_height = self.text.get_width(), self.text.get_height() + # bottom_center = ( + # (display_width - text_width) // 2, + # display_height - text_height, + # ) + # return bottom_center + # elif position == "top_right": + # display_width = display.get_width() + # text_width = self.text.get_width() + # top_right = (display_width - text_width, 0) + # return top_right + # elif position == "top_left": + # top_left = (0, 0) + # return top_left + # elif position == "top_center": + # display_width = display.get_width() + # text_width = self.text.get_width() + # top_center = ((display_width - text_width) // 2, 0) + # return top_center + # else: + # raise NotImplementedError(f"Position {position} not implemented.") + # else: + # raise ValueError( + # f"Position expected to be a tuple[int, int] or a string. Got {position}." + # ) + + # def render(self, text: str, display: pygame.Surface) -> None: + # """ + # Render text on the screen. + + # Parameters + # ---------- + # text : str + # text to be displayed + # display : pygame.Surface + # display surface + # """ + # self.text = self.font.render(text, True, (125, 125, 125)) + # position_tuple = self._position_resolver(self.position, display) + # display.blit(self.text, position_tuple) + + +class Map: + """ + Class to display the track map according to the desired zoom level. + """ + + def __init__(self, map_img: np.ndarray, zoom_level: float): + orig_width, orig_height = map_img.shape + scaled_width = int(orig_width * zoom_level) + scaled_height = int(orig_height * zoom_level) + map_img = cv2.resize( + map_img, dsize=(scaled_width, scaled_height), interpolation=cv2.INTER_AREA + ) + + # convert shape from (W, H) to (W, H, 3) + track_map = np.stack([map_img, map_img, map_img], axis=-1) + + # rotate and flip to match the track orientation + track_map = np.rot90(track_map, k=1) # rotate clockwise + track_map = np.flip(track_map, axis=0) # flip vertically + + self.track_map = track_map + # self.map_surface = pygame.surfarray.make_surface(self.track_map) + + # def render(self, display: pygame.Surface): + # display.blit(self.map_surface, (0, 0)) + + +class Car: + """ + Class to display the car. + """ + + def __init__( + self, + render_spec: RenderSpec, + map_origin: tuple[float, float], + resolution: float, + ppu: float, + car_length: float, + car_width: float, + color: list[int] | None = None, + wheel_size: float = 0.2, + ): + self.car_length = car_length + self.car_width = car_width + self.wheel_size = wheel_size + self.car_tickness = render_spec.car_tickness + self.show_wheels = render_spec.show_wheels + + self.origin = map_origin + self.resolution = resolution + self.ppu = ppu + + self.color = color or (0, 0, 0) + self.pose = None + self.steering = None + self.rect = None + + def update(self, state: dict[str, np.ndarray], idx: int): + self.pose = ( + state["poses_x"][idx], + state["poses_y"][idx], + state["poses_theta"][idx], + ) + self.color = (255, 0, 0) if state["collisions"][idx] > 0 else self.color + self.steering = self.pose[2] + state["steering_angles"][idx] + + # def render(self, display: pygame.Surface): + # vertices = get_vertices(self.pose, self.car_length, self.car_width) + # vertices[:, 0] = (vertices[:, 0] - self.origin[0]) / ( + # self.resolution * self.ppu + # ) + # vertices[:, 1] = (vertices[:, 1] - self.origin[1]) / ( + # self.resolution * self.ppu + # ) + + # self.rect = pygame.draw.polygon(display, self.color, vertices) + + # pygame.draw.lines(display, (0, 0, 0), True, vertices, self.car_tickness) + + # # draw two lines in proximity of the front wheels + # # to indicate the steering angle + # if self.show_wheels: + # # percentage along the car length to draw the wheels segments + # lam = 0.15 + + # # find point at perc between front and back vertices + # front_left = (vertices[0] * lam + vertices[3] * (1 - lam)).astype(int) + # front_right = (vertices[1] * lam + vertices[2] * (1 - lam)).astype(int) + # arrow_length = self.wheel_size / self.resolution + + # for mid_point in [front_left, front_right]: + # end_point = mid_point + 0.5 * arrow_length * np.array( + # [np.cos(self.steering), np.sin(self.steering)] + # ) + # base_point = mid_point - 0.5 * arrow_length * np.array( + # [np.cos(self.steering), np.sin(self.steering)] + # ) + + # pygame.draw.line( + # display, + # (0, 0, 0), + # base_point.astype(int), + # end_point.astype(int), + # self.car_tickness + 1, + # ) From 9e709c584f61f6babf78a136e19bd78131df2117 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 00:23:45 -0400 Subject: [PATCH 04/55] Implement render lines and closed lines --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 1a99c809..b0849e1b 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -125,7 +125,7 @@ def update(self, state: dict) -> None: # # update time # self.sim_time = state["sim_time"] - raise NotImplementedError + raise NotImplementedErrorw def add_renderer_callback(self, callback_fn: Callable[[EnvRenderer], None]) -> None: """ @@ -320,9 +320,10 @@ def render_lines( points = ((points - origin[:2]) / resolution).astype(int) size = math.ceil(size / ppu) - pygame.draw.lines( - self.map_canvas, color, closed=False, points=points, width=size - ) + pen = pg.mkPen(color=pg.mkColor(*color), width=size) + self.canvas.plot( + points[:, 0], points[:, 1], pen=pen, fillLevel=None, antialias=True + ) ## setting pen=None disables line drawing def render_closed_lines( self, @@ -342,15 +343,18 @@ def render_closed_lines( size : Optional[int], optional size of the line, by default 1 """ - origin = (0, 0, 0) - ppu = 1 - resolution = 1 + origin = self.map_origin + ppu = self.ppus[self.active_map_renderer] + resolution = self.map_resolution * ppu points = ((points - origin[:2]) / resolution).astype(int) size = math.ceil(size / ppu) + # Append the first point to the end to close the loop + points = np.vstack([points, points[0]]) + pen = pg.mkPen(color=pg.mkColor(*color), width=size) self.canvas.plot( - points[:, 0], points[:, 1], pen=pen, connect="all", fillLevel=None, antialias=True + points[:, 0], points[:, 1], pen=pen, fillLevel=None, antialias=True ) ## setting pen=None disables line drawing From abf0b66bd4b2c0d95f48766544913a9b103bae79 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 01:19:42 -0400 Subject: [PATCH 05/55] Implement pyqt TextObject --- f1tenth_gym/envs/rendering/pyqt_objects.py | 281 +++++++++++---------- 1 file changed, 151 insertions(+), 130 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index b52e48c6..ce9a228a 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -48,97 +48,118 @@ def __init__( self.text = self.font.render("", True, (125, 125, 125)) - # def _position_resolver( - # self, position: str | tuple[int, int], display: pygame.Surface - # ) -> tuple[int, int]: - # """ - # This function takes strings like "bottom center" and converts them into a location for the text to be displayed. - # If position is tuple, then passthrough. - - # Parameters - # ---------- - # position : str | tuple - # position of the text on the screen - # display : pygame.Surface - # display surface - - # Returns - # ------- - # tuple - # position of the text on the screen - - # Raises - # ------ - # ValueError - # if position is not a tuple or a string - # NotImplementedError - # if position is a string but not implemented - # """ - # if isinstance(position, tuple) and len(position) == 2: - # return int(position[0]), int(position[1]) - # elif isinstance(position, str): - # position = position.lower() - # if position == "bottom_right": - # display_width, display_height = ( - # display.get_width(), - # display.get_height(), - # ) - # text_width, text_height = self.text.get_width(), self.text.get_height() - # bottom_right = ( - # display_width - text_width, - # display_height - text_height, - # ) - # return bottom_right - # elif position == "bottom_left": - # display_height = display.get_height() - # text_height = self.text.get_height() - # bottom_left = (0, display_height - text_height) - # return bottom_left - # elif position == "bottom_center": - # display_width, display_height = ( - # display.get_width(), - # display.get_height(), - # ) - # text_width, text_height = self.text.get_width(), self.text.get_height() - # bottom_center = ( - # (display_width - text_width) // 2, - # display_height - text_height, - # ) - # return bottom_center - # elif position == "top_right": - # display_width = display.get_width() - # text_width = self.text.get_width() - # top_right = (display_width - text_width, 0) - # return top_right - # elif position == "top_left": - # top_left = (0, 0) - # return top_left - # elif position == "top_center": - # display_width = display.get_width() - # text_width = self.text.get_width() - # top_center = ((display_width - text_width) // 2, 0) - # return top_center - # else: - # raise NotImplementedError(f"Position {position} not implemented.") - # else: - # raise ValueError( - # f"Position expected to be a tuple[int, int] or a string. Got {position}." - # ) - - # def render(self, text: str, display: pygame.Surface) -> None: - # """ - # Render text on the screen. - - # Parameters - # ---------- - # text : str - # text to be displayed - # display : pygame.Surface - # display surface - # """ - # self.text = self.font.render(text, True, (125, 125, 125)) - # position_tuple = self._position_resolver(self.position, display) - # display.blit(self.text, position_tuple) + def _position_resolver( + self, position: str | tuple[int, int] + ) -> tuple[int, int]: + """ + This function takes strings like "bottom center" and converts them into a location for the text to be displayed. + If position is tuple, then passthrough. + + Parameters + ---------- + position : str | tuple + position of the text on the screen + + Returns + ------- + tuple + position of the text on the screen + + Raises + ------ + ValueError + if position is not a tuple or a string + NotImplementedError + if position is a string but not implemented + """ + if isinstance(position, tuple) and len(position) == 2: + return int(position[0]), int(position[1]) + elif isinstance(position, str): + position = position.lower() + if position == "bottom_right": + return (1, 1) + elif position == "bottom_left": + return (0, 1) + elif position == "bottom_center": + return (0.5, 1) + elif position == "top_right": + return (1, 0) + elif position == "top_left": + return (0, 0) + elif position == "top_center": + return (0.5, 0) + else: + raise NotImplementedError(f"Position {position} not implemented.") + else: + raise ValueError( + f"Position expected to be a tuple[int, int] or a string. Got {position}." + ) + + def _offset_resolver( + self, position: str | tuple[int, int], text_label: pg.LabelItem + ) -> tuple[int, int]: + """ + This function takes strings like "bottom center" and converts them into a location for the text to be displayed. + If position is tuple, then passthrough. + + Parameters + ---------- + position : str | tuple + position of the text on the screen + + Returns + ------- + tuple + position of the text on the screen + + Raises + ------ + ValueError + if position is not a tuple or a string + NotImplementedError + if position is a string but not implemented + """ + if isinstance(position, tuple) and len(position) == 2: + return int(position[0]), int(position[1]) + elif isinstance(position, str): + position = position.lower() + if position == "bottom_right": + return (-text_label.width(), -text_label.height()) + elif position == "bottom_left": + return (0, -text_label.height()) + elif position == "bottom_center": + return (-text_label.width()/2, -text_label.height()) + elif position == "top_right": + return (-text_label.width(), 0) + elif position == "top_left": + return (0, 0) + elif position == "top_center": + return (-text_label.width()/2, 0) + else: + raise NotImplementedError(f"Position {position} not implemented.") + else: + raise ValueError( + f"Position expected to be a tuple[int, int] or a string. Got {position}." + ) + + def render(self, text: str, parent: pg.PlotWidget) -> None: + """ + Render text on the screen. + + Parameters + ---------- + text : str + text to be displayed + parent : pg.PlotWidget + pyqt parent plot widget + """ + text_label = pg.LabelItem(text, color=(125, 125, 125)) # create text label + text_label.setParentItem(parent) # set parent to the plot widget + # Get the position and offset of the text + position_tuple = self._position_resolver(self.position) + offset_tuple = self._offset_resolver(self.position, text_label) + # Set the position and offset of the text + text_label.anchor(itemPos=position_tuple, parentPos=position_tuple, offset=offset_tuple) class Map: @@ -208,42 +229,42 @@ def update(self, state: dict[str, np.ndarray], idx: int): self.color = (255, 0, 0) if state["collisions"][idx] > 0 else self.color self.steering = self.pose[2] + state["steering_angles"][idx] - # def render(self, display: pygame.Surface): - # vertices = get_vertices(self.pose, self.car_length, self.car_width) - # vertices[:, 0] = (vertices[:, 0] - self.origin[0]) / ( - # self.resolution * self.ppu - # ) - # vertices[:, 1] = (vertices[:, 1] - self.origin[1]) / ( - # self.resolution * self.ppu - # ) - - # self.rect = pygame.draw.polygon(display, self.color, vertices) - - # pygame.draw.lines(display, (0, 0, 0), True, vertices, self.car_tickness) - - # # draw two lines in proximity of the front wheels - # # to indicate the steering angle - # if self.show_wheels: - # # percentage along the car length to draw the wheels segments - # lam = 0.15 - - # # find point at perc between front and back vertices - # front_left = (vertices[0] * lam + vertices[3] * (1 - lam)).astype(int) - # front_right = (vertices[1] * lam + vertices[2] * (1 - lam)).astype(int) - # arrow_length = self.wheel_size / self.resolution - - # for mid_point in [front_left, front_right]: - # end_point = mid_point + 0.5 * arrow_length * np.array( - # [np.cos(self.steering), np.sin(self.steering)] - # ) - # base_point = mid_point - 0.5 * arrow_length * np.array( - # [np.cos(self.steering), np.sin(self.steering)] - # ) - - # pygame.draw.line( - # display, - # (0, 0, 0), - # base_point.astype(int), - # end_point.astype(int), - # self.car_tickness + 1, - # ) + def render(self, display: pygame.Surface): + vertices = get_vertices(self.pose, self.car_length, self.car_width) + vertices[:, 0] = (vertices[:, 0] - self.origin[0]) / ( + self.resolution * self.ppu + ) + vertices[:, 1] = (vertices[:, 1] - self.origin[1]) / ( + self.resolution * self.ppu + ) + + self.rect = pygame.draw.polygon(display, self.color, vertices) + + pygame.draw.lines(display, (0, 0, 0), True, vertices, self.car_tickness) + + # draw two lines in proximity of the front wheels + # to indicate the steering angle + if self.show_wheels: + # percentage along the car length to draw the wheels segments + lam = 0.15 + + # find point at perc between front and back vertices + front_left = (vertices[0] * lam + vertices[3] * (1 - lam)).astype(int) + front_right = (vertices[1] * lam + vertices[2] * (1 - lam)).astype(int) + arrow_length = self.wheel_size / self.resolution + + for mid_point in [front_left, front_right]: + end_point = mid_point + 0.5 * arrow_length * np.array( + [np.cos(self.steering), np.sin(self.steering)] + ) + base_point = mid_point - 0.5 * arrow_length * np.array( + [np.cos(self.steering), np.sin(self.steering)] + ) + + pygame.draw.line( + display, + (0, 0, 0), + base_point.astype(int), + end_point.astype(int), + self.car_tickness + 1, + ) From afa7e59c716463e78d7307e6cd59d44bc8a6e970 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 02:43:41 -0400 Subject: [PATCH 06/55] Deprecate pyqt Map object --- f1tenth_gym/envs/rendering/pyqt_objects.py | 28 -------------------- f1tenth_gym/envs/rendering/rendering_pyqt.py | 1 - 2 files changed, 29 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index ce9a228a..92507686 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -161,34 +161,6 @@ def render(self, text: str, parent: pg.PlotWidget) -> None: # Set the position and offset of the text text_label.anchor(itemPos=position_tuple, parentPos=position_tuple, offset=offset_tuple) - -class Map: - """ - Class to display the track map according to the desired zoom level. - """ - - def __init__(self, map_img: np.ndarray, zoom_level: float): - orig_width, orig_height = map_img.shape - scaled_width = int(orig_width * zoom_level) - scaled_height = int(orig_height * zoom_level) - map_img = cv2.resize( - map_img, dsize=(scaled_width, scaled_height), interpolation=cv2.INTER_AREA - ) - - # convert shape from (W, H) to (W, H, 3) - track_map = np.stack([map_img, map_img, map_img], axis=-1) - - # rotate and flip to match the track orientation - track_map = np.rot90(track_map, k=1) # rotate clockwise - track_map = np.flip(track_map, axis=0) # flip vertically - - self.track_map = track_map - # self.map_surface = pygame.surfarray.make_surface(self.track_map) - - # def render(self, display: pygame.Surface): - # display.blit(self.map_surface, (0, 0)) - - class Car: """ Class to display the car. diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index b0849e1b..c086bbd6 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -10,7 +10,6 @@ from PIL import ImageColor from .pyqt_objects import ( - Map, Car, TextObject, ) From 22140940951ae44e240ac8c094d4dd5280aa8658 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 03:25:53 -0400 Subject: [PATCH 07/55] Initial implementation of PyQt Car object --- f1tenth_gym/envs/rendering/pyqt_objects.py | 76 +++++++++++++--------- 1 file changed, 47 insertions(+), 29 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 92507686..3c5c2612 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -3,6 +3,9 @@ import numpy as np import pyqtgraph as pg +from PyQt6.QtWidgets import QGraphicsRectItem +from PyQt6.QtGui import QTransform + from ..collision_models import get_vertices from . import RenderSpec @@ -180,7 +183,7 @@ def __init__( self.car_length = car_length self.car_width = car_width self.wheel_size = wheel_size - self.car_tickness = render_spec.car_tickness + self.car_thickness = render_spec.car_tickness self.show_wheels = render_spec.show_wheels self.origin = map_origin @@ -192,6 +195,10 @@ def __init__( self.steering = None self.rect = None + # Tire params need to be updated + self.tire_width = 0.1 + self.tire_length = 0.1 + def update(self, state: dict[str, np.ndarray], idx: int): self.pose = ( state["poses_x"][idx], @@ -201,7 +208,7 @@ def update(self, state: dict[str, np.ndarray], idx: int): self.color = (255, 0, 0) if state["collisions"][idx] > 0 else self.color self.steering = self.pose[2] + state["steering_angles"][idx] - def render(self, display: pygame.Surface): + def render(self, parent: pg.PlotWidget): vertices = get_vertices(self.pose, self.car_length, self.car_width) vertices[:, 0] = (vertices[:, 0] - self.origin[0]) / ( self.resolution * self.ppu @@ -210,33 +217,44 @@ def render(self, display: pygame.Surface): self.resolution * self.ppu ) - self.rect = pygame.draw.polygon(display, self.color, vertices) - - pygame.draw.lines(display, (0, 0, 0), True, vertices, self.car_tickness) + x, y, th = self.pose[0], self.pose[1], self.pose[2] + # Create a QGraphicsRectItem + self.rect = QGraphicsRectItem(0, 0, self.car_length, self.car_width) # x, y, width, height + self.rect.setBrush(pg.mkBrush(self.color)) + self.rect.setPen(pg.mkPen((0, 0, 0), self.car_thickness)) + + # Apply rotation transformation + transform = QTransform() + transform.rotate(np.degrees(th)) + transform.translate(x, y) + self.rect.setTransform(transform) - # draw two lines in proximity of the front wheels + # draw two rectangles at the front of the rectangle # to indicate the steering angle if self.show_wheels: - # percentage along the car length to draw the wheels segments - lam = 0.15 - - # find point at perc between front and back vertices - front_left = (vertices[0] * lam + vertices[3] * (1 - lam)).astype(int) - front_right = (vertices[1] * lam + vertices[2] * (1 - lam)).astype(int) - arrow_length = self.wheel_size / self.resolution - - for mid_point in [front_left, front_right]: - end_point = mid_point + 0.5 * arrow_length * np.array( - [np.cos(self.steering), np.sin(self.steering)] - ) - base_point = mid_point - 0.5 * arrow_length * np.array( - [np.cos(self.steering), np.sin(self.steering)] - ) - - pygame.draw.line( - display, - (0, 0, 0), - base_point.astype(int), - end_point.astype(int), - self.car_tickness + 1, - ) + # Create two rectangles, one top left and one top right + top_left_rect = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) + top_left_rect.setBrush(pg.mkBrush((0, 0, 0))) + top_left_rect.setPen(pg.mkPen((0, 0, 0), 1)) + + top_right_rect = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) + top_right_rect.setBrush(pg.mkBrush((0, 0, 0))) + top_right_rect.setPen(pg.mkPen((0, 0, 0), 1)) + + # Apply rotation transformation + transform = QTransform() + transform.rotate(np.degrees(self.steering + th)) + transform.translate(x + self.car_length / 2, y + self.car_width / 2) + top_left_rect.setTransform(transform) + + transform = QTransform() + transform.rotate(np.degrees(self.steering + th)) + transform.translate(x + self.car_length / 2, y - self.car_width / 2) + top_right_rect.setTransform(transform) + + # Add the rectangle item to the scene + parent.addItem(top_left_rect) + parent.addItem(top_right_rect) + + + From d984495a7d52fa5a7115d81ee95cf56249a070a0 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 03:39:36 -0400 Subject: [PATCH 08/55] Make update of car consistent with env renderer --- f1tenth_gym/envs/rendering/pyqt_objects.py | 89 +++++++++++--------- f1tenth_gym/envs/rendering/rendering_pyqt.py | 40 +++++---- 2 files changed, 68 insertions(+), 61 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 3c5c2612..e253d5c1 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -1,12 +1,10 @@ from __future__ import annotations -import cv2 import numpy as np import pyqtgraph as pg from PyQt6.QtWidgets import QGraphicsRectItem from PyQt6.QtGui import QTransform -from ..collision_models import get_vertices from . import RenderSpec @@ -174,11 +172,11 @@ def __init__( render_spec: RenderSpec, map_origin: tuple[float, float], resolution: float, - ppu: float, car_length: float, car_width: float, color: list[int] | None = None, wheel_size: float = 0.2, + parent: pg.PlotWidget = None, ): self.car_length = car_length self.car_width = car_width @@ -188,73 +186,84 @@ def __init__( self.origin = map_origin self.resolution = resolution - self.ppu = ppu self.color = color or (0, 0, 0) - self.pose = None - self.steering = None - self.rect = None + self.pose = (0, 0, 0) + self.steering = 0 + self.chassis = None # Tire params need to be updated self.tire_width = 0.1 - self.tire_length = 0.1 - - def update(self, state: dict[str, np.ndarray], idx: int): - self.pose = ( - state["poses_x"][idx], - state["poses_y"][idx], - state["poses_theta"][idx], - ) - self.color = (255, 0, 0) if state["collisions"][idx] > 0 else self.color - self.steering = self.pose[2] + state["steering_angles"][idx] - - def render(self, parent: pg.PlotWidget): - vertices = get_vertices(self.pose, self.car_length, self.car_width) - vertices[:, 0] = (vertices[:, 0] - self.origin[0]) / ( - self.resolution * self.ppu - ) - vertices[:, 1] = (vertices[:, 1] - self.origin[1]) / ( - self.resolution * self.ppu - ) + self.tire_length = self.wheel_size x, y, th = self.pose[0], self.pose[1], self.pose[2] # Create a QGraphicsRectItem - self.rect = QGraphicsRectItem(0, 0, self.car_length, self.car_width) # x, y, width, height - self.rect.setBrush(pg.mkBrush(self.color)) - self.rect.setPen(pg.mkPen((0, 0, 0), self.car_thickness)) + self.chassis = QGraphicsRectItem(0, 0, self.car_length, self.car_width) # x, y, width, height + self.chassis.setBrush(pg.mkBrush(self.color)) + self.chassis.setPen(pg.mkPen((0, 0, 0), self.car_thickness)) # Apply rotation transformation transform = QTransform() transform.rotate(np.degrees(th)) transform.translate(x, y) - self.rect.setTransform(transform) + self.chassis.setTransform(transform) # draw two rectangles at the front of the rectangle # to indicate the steering angle if self.show_wheels: # Create two rectangles, one top left and one top right - top_left_rect = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) - top_left_rect.setBrush(pg.mkBrush((0, 0, 0))) - top_left_rect.setPen(pg.mkPen((0, 0, 0), 1)) + self.left_wheel = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) + self.left_wheel.setBrush(pg.mkBrush((0, 0, 0))) + self.left_wheel.setPen(pg.mkPen((0, 0, 0), 1)) - top_right_rect = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) - top_right_rect.setBrush(pg.mkBrush((0, 0, 0))) - top_right_rect.setPen(pg.mkPen((0, 0, 0), 1)) + self.right_wheel = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) + self.right_wheel.setBrush(pg.mkBrush((0, 0, 0))) + self.right_wheel.setPen(pg.mkPen((0, 0, 0), 1)) # Apply rotation transformation transform = QTransform() transform.rotate(np.degrees(self.steering + th)) transform.translate(x + self.car_length / 2, y + self.car_width / 2) - top_left_rect.setTransform(transform) + self.left_wheel.setTransform(transform) transform = QTransform() transform.rotate(np.degrees(self.steering + th)) transform.translate(x + self.car_length / 2, y - self.car_width / 2) - top_right_rect.setTransform(transform) + self.right_wheel.setTransform(transform) # Add the rectangle item to the scene - parent.addItem(top_left_rect) - parent.addItem(top_right_rect) + parent.addItem(self.left_wheel) + parent.addItem(self.right_wheel) + + def update(self, state: dict[str, np.ndarray], idx: int): + self.pose = ( + state["poses_x"][idx], + state["poses_y"][idx], + state["poses_theta"][idx], + ) + self.color = (255, 0, 0) if state["collisions"][idx] > 0 else self.color + self.steering = self.pose[2] + state["steering_angles"][idx] + + def render(self): + # Updates transforms of all rectangles + x, y, th = self.pose[0], self.pose[1], self.pose[2] + + # Apply rotation transformation + transform = QTransform() + transform.rotate(np.degrees(th)) + transform.translate(x, y) + self.chassis.setTransform(transform) + + if self.show_wheels: + transform = QTransform() + transform.rotate(np.degrees(self.steering + th)) + transform.translate(x + self.car_length / 2, y + self.car_width / 2) + self.left_wheel.setTransform(transform) + + transform = QTransform() + transform.rotate(np.degrees(self.steering + th)) + transform.translate(x + self.car_length / 2, y - self.car_width / 2) + self.right_wheel.setTransform(transform) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index c086bbd6..085eb35f 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -104,27 +104,25 @@ def update(self, state: dict) -> None: ---------- state: simulation state as dictionary """ - # if self.cars is None: - # self.cars = [ - # Car( - # car_length=self.params["length"], - # car_width=self.params["width"], - # color=self.car_colors[ic], - # render_spec=self.render_spec, - # map_origin=self.map_origin[:2], - # resolution=self.map_resolution, - # ppu=self.ppus[self.active_map_renderer], - # ) - # for ic in range(len(self.agent_ids)) - # ] - - # # update cars state and zoom level (updating points-per-unit) - # for i in range(len(self.agent_ids)): - # self.cars[i].update(state, i) - - # # update time - # self.sim_time = state["sim_time"] - raise NotImplementedErrorw + if self.cars is None: + self.cars = [ + Car( + car_length=self.params["length"], + car_width=self.params["width"], + color=self.car_colors[ic], + render_spec=self.render_spec, + map_origin=self.map_origin[:2], + resolution=self.map_resolution, + ) + for ic in range(len(self.agent_ids)) + ] + + # update cars state and zoom level (updating points-per-unit) + for i in range(len(self.agent_ids)): + self.cars[i].update(state, i) + + # update time + self.sim_time = state["sim_time"] def add_renderer_callback(self, callback_fn: Callable[[EnvRenderer], None]) -> None: """ From 9f97e9825dd79407b209325807c6eda52cfd8117 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 03:57:41 -0400 Subject: [PATCH 09/55] Update pyqt text object rendering to be consistent with env renderer --- f1tenth_gym/envs/rendering/pyqt_objects.py | 23 ++++++++++---------- f1tenth_gym/envs/rendering/rendering_pyqt.py | 18 +++++++++++++++ 2 files changed, 30 insertions(+), 11 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index e253d5c1..e093e4dc 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -28,6 +28,7 @@ def __init__( position: str | tuple, relative_font_size: int = 32, font_name: str = "Arial", + parent: pg.PlotWidget = None, ) -> None: """ Initialize text object. @@ -49,6 +50,14 @@ def __init__( self.text = self.font.render("", True, (125, 125, 125)) + self.text_label = pg.LabelItem(self.text, color=(125, 125, 125)) # create text label + self.text_label.setParentItem(parent) # set parent to the plot widget + # Get the position and offset of the text + position_tuple = self._position_resolver(self.position) + offset_tuple = self._offset_resolver(self.position, self.text_label) + # Set the position and offset of the text + self.text_label.anchor(itemPos=position_tuple, parentPos=position_tuple, offset=offset_tuple) + def _position_resolver( self, position: str | tuple[int, int] ) -> tuple[int, int]: @@ -143,24 +152,16 @@ def _offset_resolver( f"Position expected to be a tuple[int, int] or a string. Got {position}." ) - def render(self, text: str, parent: pg.PlotWidget) -> None: + def render(self, text: str) -> None: """ Render text on the screen. Parameters ---------- text : str - text to be displayed - parent : pg.PlotWidget - pyqt parent plot widget + text to be displayed """ - text_label = pg.LabelItem(text, color=(125, 125, 125)) # create text label - text_label.setParentItem(parent) # set parent to the plot widget - # Get the position and offset of the text - position_tuple = self._position_resolver(self.position) - offset_tuple = self._offset_resolver(self.position, text_label) - # Set the position and offset of the text - text_label.anchor(itemPos=position_tuple, parentPos=position_tuple, offset=offset_tuple) + self.text_label.setText(text) class Car: """ diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 085eb35f..a1f463df 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -2,11 +2,13 @@ import logging import math from typing import Any, Callable, Optional +from time import perf_counter import cv2 import numpy as np from PyQt6 import QtWidgets import pyqtgraph as pg +from pyqtgraph.examples.utils import FrameCounter from PIL import ImageColor from .pyqt_objects import ( @@ -65,6 +67,22 @@ def __init__( self.render_mode = render_mode self.render_fps = render_fps + # fps and time renderer + self.clock = FrameCounter() + self.fps_renderer = TextObject( + window_shape=(width, height), position="bottom_left" + ) + self.time_renderer = TextObject( + window_shape=(width, height), position="bottom_right" + ) + self.bottom_info_renderer = TextObject( + window_shape=(width, height), position="bottom_center" + ) + self.top_info_renderer = TextObject( + window_shape=(width, height), position="top_center" + ) + self.clock.sigFpsUpdate.connect(lambda fps: self.top_info_renderer.render(f'FPS: {fps:.1f}')) + colors_rgb = [ [rgb for rgb in ImageColor.getcolor(c, "RGB")] for c in render_spec.vehicle_palette From 75fba6faeb94c52725d1c5eb29719cbb3e600eb0 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 04:08:37 -0400 Subject: [PATCH 10/55] Initial implementation of env renderer render --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 139 ++++++++----------- 1 file changed, 55 insertions(+), 84 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index a1f463df..70b18112 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -2,7 +2,6 @@ import logging import math from typing import Any, Callable, Optional -from time import perf_counter import cv2 import numpy as np @@ -81,7 +80,9 @@ def __init__( self.top_info_renderer = TextObject( window_shape=(width, height), position="top_center" ) - self.clock.sigFpsUpdate.connect(lambda fps: self.top_info_renderer.render(f'FPS: {fps:.1f}')) + + if self.render_mode in ["human", "human_fast"]: + self.clock.sigFpsUpdate.connect(lambda fps: self.top_info_renderer.render(f'FPS: {fps:.1f}')) colors_rgb = [ [rgb for rgb in ImageColor.getcolor(c, "RGB")] @@ -155,88 +156,58 @@ def add_renderer_callback(self, callback_fn: Callable[[EnvRenderer], None]) -> N self.callbacks.append(callback_fn) def render(self) -> Optional[np.ndarray]: - # """ - # Render the current state in a frame. - # It renders in the order: map, cars, callbacks, info text. - - # Returns - # ------- - # Optional[np.ndarray] - # if render_mode is "rgb_array", returns the rendered frame as an array - # """ - # self.event_handling() - - # self.canvas.fill((255, 255, 255)) # white background - # self.map_canvas = self.map_canvases[self.active_map_renderer] - # self.map_canvas.fill((255, 255, 255)) # white background - - # if self.draw_flag: - # self.map_renderers[self.active_map_renderer].render(self.map_canvas) - - # # draw cars - # for i in range(len(self.agent_ids)): - # self.cars[i].render(self.map_canvas) - - # # call callbacks - # for callback_fn in self.callbacks: - # callback_fn(self) - - # surface_mod_rect = self.map_canvas.get_rect() - # screen_rect = self.canvas.get_rect() - - # if self.follow_agent_flag: - # origin = self.map_origin - # resolution = self.map_resolution * self.ppus[self.active_map_renderer] - # ego_x, ego_y = self.cars[self.agent_to_follow].pose[:2] - # cx = (ego_x - origin[0]) / resolution - # cy = (ego_y - origin[1]) / resolution - # else: - # cx = self.map_canvas.get_width() / 2 - # cy = self.map_canvas.get_height() / 2 - - # surface_mod_rect.x = screen_rect.centerx - cx - # surface_mod_rect.y = screen_rect.centery - cy - - # self.canvas.blit(self.map_canvas, surface_mod_rect) - - # agent_to_follow_id = ( - # self.agent_ids[self.agent_to_follow] - # if self.agent_to_follow is not None - # else None - # ) - # self.bottom_info_renderer.render( - # text=f"Focus on: {agent_to_follow_id}", display=self.canvas - # ) - - # if self.render_spec.show_info: - # self.top_info_renderer.render(text=INSTRUCTION_TEXT, display=self.canvas) - # self.time_renderer.render(text=f"{self.sim_time:.2f}", display=self.canvas) - - # if self.render_mode in ["human", "human_fast"]: - # assert self.window is not None - - # self.fps_renderer.render( - # text=f"FPS: {self.clock.get_fps():.2f}", display=self.canvas - # ) - - # self.window.blit(self.canvas, self.canvas.get_rect()) - - # pygame.event.pump() - # pygame.display.update() - - # # We need to ensure that human-rendering occurs at the predefined framerate. - # # The following line will automatically add a delay to keep the framerate stable. - # self.clock.tick(self.render_fps) - # else: # rgb_array - # frame = np.transpose( - # np.array(pygame.surfarray.pixels3d(self.canvas)), axes=(1, 0, 2) - # ) - # if frame.shape[0] > 2000: - # frame = cv2.resize( - # frame, dsize=(2000, 2000), interpolation=cv2.INTER_AREA - # ) - # return frame - raise NotImplementedError + """ + Render the current state in a frame. + It renders in the order: map, cars, callbacks, info text. + + Returns + ------- + Optional[np.ndarray] + if render_mode is "rgb_array", returns the rendered frame as an array + """ + self.event_handling() + + if self.draw_flag: + + # draw cars + for i in range(len(self.agent_ids)): + self.cars[i].render(self.map_canvas) + + # call callbacks + for callback_fn in self.callbacks: + callback_fn(self) + + if self.follow_agent_flag: + origin = self.map_origin + resolution = self.map_resolution * self.ppus[self.active_map_renderer] + ego_x, ego_y = self.cars[self.agent_to_follow].pose[:2] + cx = (ego_x - origin[0]) / resolution + cy = (ego_y - origin[1]) / resolution + else: + cx = self.map_canvas.get_width() / 2 + cy = self.map_canvas.get_height() / 2 + + agent_to_follow_id = ( + self.agent_ids[self.agent_to_follow] + if self.agent_to_follow is not None + else None + ) + self.bottom_info_renderer.render( + text=f"Focus on: {agent_to_follow_id}", display=self.canvas + ) + + if self.render_spec.show_info: + self.top_info_renderer.render(text=INSTRUCTION_TEXT, display=self.canvas) + self.time_renderer.render(text=f"{self.sim_time:.2f}", display=self.canvas) + + if self.render_mode in ["human", "human_fast"]: + assert self.window is not None + + else: + # rgb_array + # TODO: extract the frame from the canvas + frame = None + return frame def event_handling(self) -> None: """ From 448031e0ef6a5da8e8d17e3440b62c379eda6374 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 15:35:34 -0400 Subject: [PATCH 11/55] Fix initialization of TextObject --- f1tenth_gym/envs/rendering/pyqt_objects.py | 14 +++----------- 1 file changed, 3 insertions(+), 11 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index e093e4dc..81c76481 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -5,7 +5,7 @@ from PyQt6.QtWidgets import QGraphicsRectItem from PyQt6.QtGui import QTransform -from . import RenderSpec +from renderer import RenderSpec class TextObject: @@ -24,9 +24,8 @@ class TextObject: def __init__( self, - window_shape: tuple[int, int], position: str | tuple, - relative_font_size: int = 32, + relative_font_size: int = 16, font_name: str = "Arial", parent: pg.PlotWidget = None, ) -> None: @@ -35,8 +34,6 @@ def __init__( Parameters ---------- - window_shape : tuple - shape of the window (width, height) in pixels position : str | tuple position of the text on the screen relative_font_size : int, optional @@ -44,14 +41,9 @@ def __init__( font_name : str, optional font name, by default "Arial" """ - font_size = int(relative_font_size * window_shape[0] / 1000) - # self.font = pygame.font.SysFont(font_name, font_size) self.position = position - self.text = self.font.render("", True, (125, 125, 125)) - - self.text_label = pg.LabelItem(self.text, color=(125, 125, 125)) # create text label - self.text_label.setParentItem(parent) # set parent to the plot widget + self.text_label = pg.LabelItem("", parent=parent, size=str(relative_font_size) + 'pt', family=font_name, color=(125, 125, 125)) # create text label # Get the position and offset of the text position_tuple = self._position_resolver(self.position) offset_tuple = self._offset_resolver(self.position, self.text_label) From b997e536d5d4735c940d66b9893282081e86b695 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 15:36:39 -0400 Subject: [PATCH 12/55] Initial implementation of EnvRender init --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 29 +++++++++++++++----- 1 file changed, 22 insertions(+), 7 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 70b18112..8231720f 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -66,23 +66,37 @@ def __init__( self.render_mode = render_mode self.render_fps = render_fps + # create the canvas + self.app = QtWidgets.QApplication([]) + self.window = pg.GraphicsLayoutWidget() + self.window.setWindowTitle("F1Tenth Gym") + self.window.setGeometry(0, 0, self.render_spec.window_size, self.render_spec.window_size) + self.canvas = self.window.addPlot() + + # Remove axes + self.canvas.hideAxis('bottom') + self.canvas.hideAxis('left') + + # setting plot window background color to yellow + self.window.setBackground('w') + # fps and time renderer self.clock = FrameCounter() self.fps_renderer = TextObject( - window_shape=(width, height), position="bottom_left" + parent=self.canvas, position="bottom_left" ) self.time_renderer = TextObject( - window_shape=(width, height), position="bottom_right" + parent=self.canvas, position="bottom_right" ) self.bottom_info_renderer = TextObject( - window_shape=(width, height), position="bottom_center" + parent=self.canvas, position="bottom_center" ) self.top_info_renderer = TextObject( - window_shape=(width, height), position="top_center" + parent=self.canvas, position="top_center" ) if self.render_mode in ["human", "human_fast"]: - self.clock.sigFpsUpdate.connect(lambda fps: self.top_info_renderer.render(f'FPS: {fps:.1f}')) + self.clock.sigFpsUpdate.connect(lambda fps: self.fps_renderer.render(f'FPS: {fps:.1f}')) colors_rgb = [ [rgb for rgb in ImageColor.getcolor(c, "RGB")] @@ -115,6 +129,9 @@ def __init__( self.follow_agent_flag: bool = False self.agent_to_follow: int = None + self.window.show() + self.app.exec() + def update(self, state: dict) -> None: """ Update the simulation state to be rendered. @@ -165,8 +182,6 @@ def render(self) -> Optional[np.ndarray]: Optional[np.ndarray] if render_mode is "rgb_array", returns the rendered frame as an array """ - self.event_handling() - if self.draw_flag: # draw cars From e255bea3945fe2edb00ad29347a0834303b4b278 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 16:34:05 -0400 Subject: [PATCH 13/55] Disable default mouse interactions for plot --- f1tenth_gym/envs/rendering/pyqt_objects.py | 2 +- f1tenth_gym/envs/rendering/rendering_pyqt.py | 12 +++++++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 81c76481..75c1ff73 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -5,7 +5,7 @@ from PyQt6.QtWidgets import QGraphicsRectItem from PyQt6.QtGui import QTransform -from renderer import RenderSpec +from .renderer import RenderSpec class TextObject: diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 8231720f..c5765646 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -71,7 +71,17 @@ def __init__( self.window = pg.GraphicsLayoutWidget() self.window.setWindowTitle("F1Tenth Gym") self.window.setGeometry(0, 0, self.render_spec.window_size, self.render_spec.window_size) - self.canvas = self.window.addPlot() + self.canvas : pg.PlotItem = self.window.addPlot() + + # Disable interactivity + self.canvas.setMouseEnabled(x=False, y=False) # Disable mouse panning & zooming + self.canvas.hideButtons() # Disable corner auto-scale button + self.canvas.setMenuEnabled(False) # Disable right-click context menu + + legend = self.canvas.addLegend() # This doesn't disable legend interaction + # Override both methods responsible for mouse events + legend.mouseDragEvent = lambda *args, **kwargs: None + legend.hoverEvent = lambda *args, **kwargs: None # Remove axes self.canvas.hideAxis('bottom') From b051635f325ef307a85a39bf50ecb48d19a5a8cb Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 17:22:46 -0400 Subject: [PATCH 14/55] Update render callbacks to update waypoints instead of redrawing --- examples/waypoint_follow.py | 17 ++++++--- f1tenth_gym/envs/rendering/pyqt_objects.py | 7 ++-- f1tenth_gym/envs/rendering/rendering_pyqt.py | 37 ++++++++++---------- f1tenth_gym/envs/track/raceline.py | 7 +++- 4 files changed, 41 insertions(+), 27 deletions(-) diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index f5527472..0d86f602 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -184,8 +184,11 @@ def __init__(self, track, wb): self.max_reacquire = 20.0 self.drawn_waypoints = [] - self.lookahead_point = None - self.current_index = None + self.lookahead_point = np.array([0, 0, 0], dtype=np.float32) + self.current_index = 0 + + self.local_plan_render = None + self.lookahead_point_render = None def load_waypoints(self, conf): """ @@ -202,7 +205,10 @@ def render_lookahead_point(self, e): """ if self.lookahead_point is not None: points = self.lookahead_point[:2][None] # shape (1, 2) - e.render_points(points, color=(0, 0, 128), size=2) + if self.lookahead_point_render is None: + self.lookahead_point_render = e.render_points(points, color=(0, 0, 128), size=2) + else: + self.lookahead_point_render.updateItems(points) def render_local_plan(self, e): """ @@ -210,7 +216,10 @@ def render_local_plan(self, e): """ if self.current_index is not None: points = self.waypoints[self.current_index : self.current_index + 10, :2] - e.render_lines(points, color=(0, 128, 0), size=1) + if self.local_plan_render is None: + self.local_plan_render = e.render_lines(points, color=(0, 128, 0), size=1) + else: + self.local_plan_render.updateItems(points) def _get_current_waypoint( self, waypoints, lookahead_distance, position, theta diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 75c1ff73..1ad067cc 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -193,7 +193,8 @@ def __init__( # Create a QGraphicsRectItem self.chassis = QGraphicsRectItem(0, 0, self.car_length, self.car_width) # x, y, width, height self.chassis.setBrush(pg.mkBrush(self.color)) - self.chassis.setPen(pg.mkPen((0, 0, 0), self.car_thickness)) + self.chassis.setPen(pg.mkPen((0, 0, 0), width=self.car_thickness)) + self.chassis.setParentItem(parent) # Apply rotation transformation transform = QTransform() @@ -207,11 +208,11 @@ def __init__( # Create two rectangles, one top left and one top right self.left_wheel = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) self.left_wheel.setBrush(pg.mkBrush((0, 0, 0))) - self.left_wheel.setPen(pg.mkPen((0, 0, 0), 1)) + self.left_wheel.setPen(pg.mkPen((0, 0, 0), width=1)) self.right_wheel = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) self.right_wheel.setBrush(pg.mkBrush((0, 0, 0))) - self.right_wheel.setPen(pg.mkPen((0, 0, 0), 1)) + self.right_wheel.setPen(pg.mkPen((0, 0, 0), width=1)) # Apply rotation transformation transform = QTransform() diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index c5765646..548124b3 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -140,7 +140,6 @@ def __init__( self.agent_to_follow: int = None self.window.show() - self.app.exec() def update(self, state: dict) -> None: """ @@ -159,6 +158,7 @@ def update(self, state: dict) -> None: render_spec=self.render_spec, map_origin=self.map_origin[:2], resolution=self.map_resolution, + parent=self.canvas, ) for ic in range(len(self.agent_ids)) ] @@ -196,7 +196,7 @@ def render(self) -> Optional[np.ndarray]: # draw cars for i in range(len(self.agent_ids)): - self.cars[i].render(self.map_canvas) + self.cars[i].render() # call callbacks for callback_fn in self.callbacks: @@ -204,7 +204,7 @@ def render(self) -> Optional[np.ndarray]: if self.follow_agent_flag: origin = self.map_origin - resolution = self.map_resolution * self.ppus[self.active_map_renderer] + resolution = self.map_resolution ego_x, ego_y = self.cars[self.agent_to_follow].pose[:2] cx = (ego_x - origin[0]) / resolution cy = (ego_y - origin[1]) / resolution @@ -218,12 +218,14 @@ def render(self) -> Optional[np.ndarray]: else None ) self.bottom_info_renderer.render( - text=f"Focus on: {agent_to_follow_id}", display=self.canvas + text=f"Focus on: {agent_to_follow_id}" ) if self.render_spec.show_info: - self.top_info_renderer.render(text=INSTRUCTION_TEXT, display=self.canvas) - self.time_renderer.render(text=f"{self.sim_time:.2f}", display=self.canvas) + self.top_info_renderer.render(text=INSTRUCTION_TEXT) + self.time_renderer.render(text=f"{self.sim_time:.2f}") + self.clock.update() + self.app.processEvents() if self.render_mode in ["human", "human_fast"]: assert self.window is not None @@ -302,17 +304,16 @@ def render_points( size of the points in pixels, by default 1 """ origin = self.map_origin - ppu = self.ppus[self.active_map_renderer] - resolution = self.map_resolution * ppu + resolution = self.map_resolution points = ((points - origin[:2]) / resolution).astype(int) - size = math.ceil(size / ppu) + size = math.ceil(size) def render_lines( self, points: list | np.ndarray, color: Optional[tuple[int, int, int]] = (0, 0, 255), size: Optional[int] = 1, - ) -> None: + ) -> pg.PlotDataItem: """ Render a sequence of lines segments. @@ -326,13 +327,12 @@ def render_lines( size of the line, by default 1 """ origin = self.map_origin - ppu = self.ppus[self.active_map_renderer] - resolution = self.map_resolution * ppu + resolution = self.map_resolution points = ((points - origin[:2]) / resolution).astype(int) - size = math.ceil(size / ppu) + size = math.ceil(size) pen = pg.mkPen(color=pg.mkColor(*color), width=size) - self.canvas.plot( + return self.canvas.plot( points[:, 0], points[:, 1], pen=pen, fillLevel=None, antialias=True ) ## setting pen=None disables line drawing @@ -341,7 +341,7 @@ def render_closed_lines( points: list | np.ndarray, color: Optional[tuple[int, int, int]] = (0, 0, 255), size: Optional[int] = 1, - ) -> None: + ) -> pg.PlotDataItem: """ Render a sequence of lines segments forming a closed loop (draw a line between the last and the first point). @@ -355,16 +355,15 @@ def render_closed_lines( size of the line, by default 1 """ origin = self.map_origin - ppu = self.ppus[self.active_map_renderer] - resolution = self.map_resolution * ppu + resolution = self.map_resolution points = ((points - origin[:2]) / resolution).astype(int) - size = math.ceil(size / ppu) + size = math.ceil(size) # Append the first point to the end to close the loop points = np.vstack([points, points[0]]) pen = pg.mkPen(color=pg.mkColor(*color), width=size) - self.canvas.plot( + return self.canvas.plot( points[:, 0], points[:, 1], pen=pen, fillLevel=None, antialias=True ) ## setting pen=None disables line drawing diff --git a/f1tenth_gym/envs/track/raceline.py b/f1tenth_gym/envs/track/raceline.py index 9215596f..ba9c0467 100644 --- a/f1tenth_gym/envs/track/raceline.py +++ b/f1tenth_gym/envs/track/raceline.py @@ -65,6 +65,8 @@ def __init__( # compute spline through waypoints if not provided self.spline = spline or CubicSpline2D(x=xs, y=ys) + self.waypoint_render = None + @staticmethod def from_centerline_file( filepath: pathlib.Path, @@ -166,4 +168,7 @@ def render_waypoints(self, e: EnvRenderer) -> None: Environment renderer object. """ points = np.stack([self.xs, self.ys], axis=1) - e.render_closed_lines(points, color=(0, 128, 0), size=1) + if self.waypoint_render is None: + self.waypoint_render = e.render_closed_lines(points, color=(0, 128, 0), size=1) + else: + self.waypoint_render.updateItems(points) From ddacb8a0fb98411b3d9abc9e6b46f66c529346b6 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 5 Aug 2024 23:09:43 -0400 Subject: [PATCH 15/55] Fix issue with jagged lines in rendering --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 25 +++++++++++--------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 548124b3..8b29da5f 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -125,6 +125,16 @@ def __init__( # load map image original_img = track.occupancy_map + # # convert shape from (W, H) to (W, H, 3) + # track_map = np.stack([original_img, original_img, original_img], axis=-1) + + # # rotate and flip to match the track orientation + # track_map = np.rot90(track_map, k=1) # rotate clockwise + # track_map = np.flip(track_map, axis=0) # flip vertically + + # self.image_item = pg.ImageItem(track_map) + # self.canvas.addItem(self.image_item) + # callbacks for custom visualization, called at every rendering step self.callbacks = [] @@ -326,11 +336,6 @@ def render_lines( size : Optional[int], optional size of the line, by default 1 """ - origin = self.map_origin - resolution = self.map_resolution - points = ((points - origin[:2]) / resolution).astype(int) - size = math.ceil(size) - pen = pg.mkPen(color=pg.mkColor(*color), width=size) return self.canvas.plot( points[:, 0], points[:, 1], pen=pen, fillLevel=None, antialias=True @@ -354,17 +359,15 @@ def render_closed_lines( size : Optional[int], optional size of the line, by default 1 """ - origin = self.map_origin - resolution = self.map_resolution - points = ((points - origin[:2]) / resolution).astype(int) - size = math.ceil(size) - # Append the first point to the end to close the loop points = np.vstack([points, points[0]]) pen = pg.mkPen(color=pg.mkColor(*color), width=size) + pen.setCapStyle(pg.QtCore.Qt.PenCapStyle.RoundCap) + pen.setJoinStyle(pg.QtCore.Qt.PenJoinStyle.RoundJoin) + return self.canvas.plot( - points[:, 0], points[:, 1], pen=pen, fillLevel=None, antialias=True + points[:, 0], points[:, 1], pen=pen, cosmetic=True, antialias=True ) ## setting pen=None disables line drawing From e8154e6983658b55c9ab8bde2e4f7a39736a86b5 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 00:59:48 -0400 Subject: [PATCH 16/55] Now renders cars correctly --- f1tenth_gym/envs/rendering/pyqt_objects.py | 74 +++++----------------- 1 file changed, 15 insertions(+), 59 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 1ad067cc..8c26684c 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -2,10 +2,11 @@ import numpy as np import pyqtgraph as pg -from PyQt6.QtWidgets import QGraphicsRectItem -from PyQt6.QtGui import QTransform +from PyQt6.QtWidgets import QGraphicsRectItem, QGraphicsPolygonItem +from PyQt6 import QtGui from .renderer import RenderSpec +from ..collision_models import get_vertices class TextObject: @@ -189,45 +190,12 @@ def __init__( self.tire_width = 0.1 self.tire_length = self.wheel_size - x, y, th = self.pose[0], self.pose[1], self.pose[2] - # Create a QGraphicsRectItem - self.chassis = QGraphicsRectItem(0, 0, self.car_length, self.car_width) # x, y, width, height - self.chassis.setBrush(pg.mkBrush(self.color)) - self.chassis.setPen(pg.mkPen((0, 0, 0), width=self.car_thickness)) - self.chassis.setParentItem(parent) - - # Apply rotation transformation - transform = QTransform() - transform.rotate(np.degrees(th)) - transform.translate(x, y) - self.chassis.setTransform(transform) - - # draw two rectangles at the front of the rectangle - # to indicate the steering angle - if self.show_wheels: - # Create two rectangles, one top left and one top right - self.left_wheel = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) - self.left_wheel.setBrush(pg.mkBrush((0, 0, 0))) - self.left_wheel.setPen(pg.mkPen((0, 0, 0), width=1)) - - self.right_wheel = QGraphicsRectItem(0, 0, self.tire_length, self.tire_width) - self.right_wheel.setBrush(pg.mkBrush((0, 0, 0))) - self.right_wheel.setPen(pg.mkPen((0, 0, 0), width=1)) - - # Apply rotation transformation - transform = QTransform() - transform.rotate(np.degrees(self.steering + th)) - transform.translate(x + self.car_length / 2, y + self.car_width / 2) - self.left_wheel.setTransform(transform) - - transform = QTransform() - transform.rotate(np.degrees(self.steering + th)) - transform.translate(x + self.car_length / 2, y - self.car_width / 2) - self.right_wheel.setTransform(transform) - - # Add the rectangle item to the scene - parent.addItem(self.left_wheel) - parent.addItem(self.right_wheel) + vertices = get_vertices(self.pose, self.car_length, self.car_width) + # vertices are rl, rr, fr, fl => Reorder to be rl, fl, fr, rr + vertices = np.array([vertices[0], vertices[3], vertices[2], vertices[1]]) + # Append the first point to close the polygon + vertices = np.vstack([vertices, vertices[0]]) + self.chassis : pg.PlotDataItem = parent.plot(vertices[:, 0], vertices[:, 1], pen=pg.mkPen(color=(0,0,0), width=self.car_thickness), fillLevel=0, brush=self.color) def update(self, state: dict[str, np.ndarray], idx: int): self.pose = ( @@ -239,25 +207,13 @@ def update(self, state: dict[str, np.ndarray], idx: int): self.steering = self.pose[2] + state["steering_angles"][idx] def render(self): - # Updates transforms of all rectangles - x, y, th = self.pose[0], self.pose[1], self.pose[2] - - # Apply rotation transformation - transform = QTransform() - transform.rotate(np.degrees(th)) - transform.translate(x, y) - self.chassis.setTransform(transform) - - if self.show_wheels: - transform = QTransform() - transform.rotate(np.degrees(self.steering + th)) - transform.translate(x + self.car_length / 2, y + self.car_width / 2) - self.left_wheel.setTransform(transform) + vertices = get_vertices(self.pose, self.car_length, self.car_width) + # vertices are rl, rr, fr, fl => Reorder to be rl, fl, fr, rr + vertices = np.array([vertices[0], vertices[3], vertices[2], vertices[1]]) + # Append the first point to close the polygon + vertices = np.vstack([vertices, vertices[0]]) - transform = QTransform() - transform.rotate(np.degrees(self.steering + th)) - transform.translate(x + self.car_length / 2, y - self.car_width / 2) - self.right_wheel.setTransform(transform) + self.chassis.setData(vertices[:, 0], vertices[:, 1]) From 166f0a5c879dfa3117977c1e1150c6962936efd7 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 01:43:36 -0400 Subject: [PATCH 17/55] Implement scaled and translated image for proper plotting --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 26 +++++++++++++------- 1 file changed, 17 insertions(+), 9 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 8b29da5f..4d8b789b 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -6,6 +6,7 @@ import cv2 import numpy as np from PyQt6 import QtWidgets +from PyQt6 import QtGui import pyqtgraph as pg from pyqtgraph.examples.utils import FrameCounter from PIL import ImageColor @@ -125,15 +126,22 @@ def __init__( # load map image original_img = track.occupancy_map - # # convert shape from (W, H) to (W, H, 3) - # track_map = np.stack([original_img, original_img, original_img], axis=-1) - - # # rotate and flip to match the track orientation - # track_map = np.rot90(track_map, k=1) # rotate clockwise - # track_map = np.flip(track_map, axis=0) # flip vertically - - # self.image_item = pg.ImageItem(track_map) - # self.canvas.addItem(self.image_item) + # convert shape from (W, H) to (W, H, 3) + track_map = np.stack([original_img, original_img, original_img], axis=-1) + + # rotate and flip to match the track orientation + track_map = np.rot90(track_map, k=1) # rotate clockwise + track_map = np.flip(track_map, axis=0) # flip vertically + + self.image_item = pg.ImageItem(track_map) + # Example: Transformed display of ImageItem + tr = QtGui.QTransform() # prepare ImageItem transformation: + # Translate image by the origin of the map + tr.translate(self.map_origin[0], self.map_origin[1]) + # Scale image by the resolution of the map + tr.scale(self.map_resolution, self.map_resolution) + self.image_item.setTransform(tr) + self.canvas.addItem(self.image_item) # callbacks for custom visualization, called at every rendering step self.callbacks = [] From eb95c964160a42cc91c22ca4be559862bf3ced95 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 02:19:08 -0400 Subject: [PATCH 18/55] Added wheels --- f1tenth_gym/envs/rendering/pyqt_objects.py | 79 +++++++++++++++++++++- 1 file changed, 78 insertions(+), 1 deletion(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 8c26684c..5b1a629e 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -6,7 +6,9 @@ from PyQt6 import QtGui from .renderer import RenderSpec -from ..collision_models import get_vertices +from ..collision_models import get_vertices, get_trmtx + +from numba import njit class TextObject: @@ -156,6 +158,50 @@ def render(self, text: str) -> None: """ self.text_label.setText(text) +# @njit(cache=True) +def _get_tire_vertices(pose, length, width, tire_width, tire_length, index, steering): + """ + Utility function to return vertices of the car's tire given pose and size + + Args: + pose (np.ndarray, (3, )): current world coordinate pose of the vehicle + length (float): car length + width (float): car width + + Returns: + vertices (np.ndarray, (4, 2)): corner vertices of the vehicle body + """ + pose_arr = np.array(pose) + pose_arr[2] = pose_arr[2] + steering + H = get_trmtx(pose_arr) + if index == 'fl': + fl = H.dot(np.asarray([[length / 2], [width / 2], [0.0], [1.0]])).flatten() + fr = H.dot(np.asarray([[length / 2], [width / 2 - tire_width], [0.0], [1.0]])).flatten() + rr = H.dot(np.asarray([[length / 2 - tire_length], [width / 2 - tire_width], [0.0], [1.0]])).flatten() + rl = H.dot(np.asarray([[length / 2 - tire_length], [width / 2], [0.0], [1.0]])).flatten() + rl = rl / rl[3] + rr = rr / rr[3] + fl = fl / fl[3] + fr = fr / fr[3] + vertices = np.asarray( + [[rl[0], rl[1]], [fl[0], fl[1]], [fr[0], fr[1]], [rr[0], rr[1]], [rl[0], rl[1]]] + ) + elif index == 'fr': + fl = H.dot(np.asarray([[length / 2], [-width / 2 + tire_width], [0.0], [1.0]])).flatten() + fr = H.dot(np.asarray([[length / 2], [-width / 2], [0.0], [1.0]])).flatten() + rr = H.dot(np.asarray([[length / 2 - tire_length], [-width / 2], [0.0], [1.0]])).flatten() + rl = H.dot(np.asarray([[length / 2 - tire_length], [-width / 2 + tire_width], [0.0], [1.0]])).flatten() + rl = rl / rl[3] + rr = rr / rr[3] + fl = fl / fl[3] + fr = fr / fr[3] + # As it is only used for rendering, we can reorder the vertices and append the first point to close the polygon + vertices = np.asarray( + [[rl[0], rl[1]], [fl[0], fl[1]], [fr[0], fr[1]], [rr[0], rr[1]], [rl[0], rl[1]]] + ) + + return vertices + class Car: """ Class to display the car. @@ -197,6 +243,27 @@ def __init__( vertices = np.vstack([vertices, vertices[0]]) self.chassis : pg.PlotDataItem = parent.plot(vertices[:, 0], vertices[:, 1], pen=pg.mkPen(color=(0,0,0), width=self.car_thickness), fillLevel=0, brush=self.color) + if self.show_wheels: + # Top-left wheel center is at fl - (tire_width/2, tire_length/2) + fl_vertices = _get_tire_vertices(self.pose, self.car_length, self.car_width, self.tire_width, self.tire_length, 'fl', self.steering) + self.fl_wheel = parent.plot( + fl_vertices[:, 0], + fl_vertices[:, 1], + pen=pg.mkPen(color=(0,0,0), width=self.car_thickness), + fillLevel=0, + brush=(0,0,0), # Rubber tire => Black + ) + + # Top-right wheel center is at fr - (tire_width/2, tire_length/2) + fr_vertices = _get_tire_vertices(self.pose, self.car_length, self.car_width, self.tire_width, self.tire_length, 'fr', self.steering) + self.fr_wheel = parent.plot( + fr_vertices[:, 0], + fr_vertices[:, 1], + pen=pg.mkPen(color=(0,0,0), width=self.car_thickness), + fillLevel=0, + brush=(0,0,0), # Rubber tire => Black + ) + def update(self, state: dict[str, np.ndarray], idx: int): self.pose = ( state["poses_x"][idx], @@ -215,5 +282,15 @@ def render(self): self.chassis.setData(vertices[:, 0], vertices[:, 1]) + if self.show_wheels: + # Top-left wheel center is at fl - (tire_width/2, tire_length/2) + fl_vertices = _get_tire_vertices(self.pose, self.car_length, self.car_width, self.tire_width, self.tire_length, 'fl', self.steering) + self.fl_wheel.setData(fl_vertices[:, 0], fl_vertices[:, 1]) + + # Top-right wheel center is at fr - (tire_width/2, tire_length/2) + fr_vertices = _get_tire_vertices(self.pose, self.car_length, self.car_width, self.tire_width, self.tire_length, 'fr', self.steering) + self.fr_wheel.setData(fr_vertices[:, 0], fr_vertices[:, 1]) + + From c12bf0b2c02e2d80627bb7510bc24885495d060c Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 02:21:24 -0400 Subject: [PATCH 19/55] Bugfix wheel orientation --- f1tenth_gym/envs/rendering/pyqt_objects.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 5b1a629e..4f47c087 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -271,7 +271,7 @@ def update(self, state: dict[str, np.ndarray], idx: int): state["poses_theta"][idx], ) self.color = (255, 0, 0) if state["collisions"][idx] > 0 else self.color - self.steering = self.pose[2] + state["steering_angles"][idx] + self.steering = state["steering_angles"][idx] def render(self): vertices = get_vertices(self.pose, self.car_length, self.car_width) From b3647419d173d27f106e0e105a8e234665e4ab12 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 02:40:31 -0400 Subject: [PATCH 20/55] minor fixes --- f1tenth_gym/envs/rendering/pyqt_objects.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 4f47c087..046064d2 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -129,11 +129,11 @@ def _offset_resolver( elif isinstance(position, str): position = position.lower() if position == "bottom_right": - return (-text_label.width(), -text_label.height()) + return (-text_label.width(), 0) elif position == "bottom_left": - return (0, -text_label.height()) + return (0, 0) elif position == "bottom_center": - return (-text_label.width()/2, -text_label.height()) + return (-text_label.width()/2, 0) elif position == "top_right": return (-text_label.width(), 0) elif position == "top_left": @@ -158,7 +158,7 @@ def render(self, text: str) -> None: """ self.text_label.setText(text) -# @njit(cache=True) +@njit(cache=True) def _get_tire_vertices(pose, length, width, tire_width, tire_length, index, steering): """ Utility function to return vertices of the car's tire given pose and size From 134002954a381915d2869c28762ecc75b00b639b Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 02:56:37 -0400 Subject: [PATCH 21/55] Implement focus and mouse click callbacks --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 106 +++++++++---------- 1 file changed, 49 insertions(+), 57 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 4d8b789b..778736c8 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -5,7 +5,7 @@ import cv2 import numpy as np -from PyQt6 import QtWidgets +from PyQt6 import QtWidgets, QtCore from PyQt6 import QtGui import pyqtgraph as pg from pyqtgraph.examples.utils import FrameCounter @@ -83,6 +83,9 @@ def __init__( # Override both methods responsible for mouse events legend.mouseDragEvent = lambda *args, **kwargs: None legend.hoverEvent = lambda *args, **kwargs: None + # self.scene() is a pyqtgraph.GraphicsScene.GraphicsScene.GraphicsScene + self.window.scene().sigMouseClicked.connect(self.mouse_clicked) + # Remove axes self.canvas.hideAxis('bottom') @@ -199,7 +202,48 @@ def add_renderer_callback(self, callback_fn: Callable[[EnvRenderer], None]) -> N callback function to be called at every rendering step """ self.callbacks.append(callback_fn) + + def mouse_clicked(self, event: QtGui.QMouseEvent) -> None: + """ + Handle mouse click events. + + Parameters + ---------- + event : QtGui.QMouseEvent + mouse event + """ + if event.button() == QtCore.Qt.MouseButton.LeftButton: + logging.debug("Pressed left button -> Follow Next agent") + + self.follow_agent_flag = True + if self.agent_to_follow is None: + self.agent_to_follow = 0 + else: + self.agent_to_follow = (self.agent_to_follow + 1) % len( + self.agent_ids + ) + + self.active_map_renderer = "car" + elif event.button() == QtCore.Qt.MouseButton.RightButton: + logging.debug("Pressed right button -> Follow Previous agent") + + self.follow_agent_flag = True + if self.agent_to_follow is None: + self.agent_to_follow = 0 + else: + self.agent_to_follow = (self.agent_to_follow - 1) % len( + self.agent_ids + ) + + self.active_map_renderer = "car" + elif event.button() == QtCore.Qt.MouseButton.MiddleButton: + logging.debug("Pressed middle button -> Change to Map View") + self.follow_agent_flag = False + self.agent_to_follow = None + + self.active_map_renderer = "map" + def render(self) -> Optional[np.ndarray]: """ Render the current state in a frame. @@ -221,15 +265,12 @@ def render(self) -> Optional[np.ndarray]: callback_fn(self) if self.follow_agent_flag: - origin = self.map_origin - resolution = self.map_resolution ego_x, ego_y = self.cars[self.agent_to_follow].pose[:2] - cx = (ego_x - origin[0]) / resolution - cy = (ego_y - origin[1]) / resolution + self.canvas.setXRange(ego_x - 10, ego_x + 10) + self.canvas.setYRange(ego_y - 10, ego_y + 10) else: - cx = self.map_canvas.get_width() / 2 - cy = self.map_canvas.get_height() / 2 - + self.canvas.autoRange() + agent_to_follow_id = ( self.agent_ids[self.agent_to_follow] if self.agent_to_follow is not None @@ -254,55 +295,6 @@ def render(self) -> Optional[np.ndarray]: frame = None return frame - def event_handling(self) -> None: - """ - Handle interaction events to change point-of-view. - - Events: - - Left mouse button: follow next agent (according to agent_ids order) - - Right mouse button: follow previous agent - - Middle mouse button: change to map view - - S key: enable/disable rendering - """ - # for event in pygame.event.get(): - # if event.type == pygame.MOUSEBUTTONDOWN and event.button == 1: - # logging.debug("Pressed left button -> Follow Next agent") - - # self.follow_agent_flag = True - # if self.agent_to_follow is None: - # self.agent_to_follow = 0 - # else: - # self.agent_to_follow = (self.agent_to_follow + 1) % len( - # self.agent_ids - # ) - - # self.active_map_renderer = "car" - - # elif event.type == pygame.MOUSEBUTTONDOWN and event.button == 3: - # logging.debug("Pressed right button -> Follow Previous agent") - - # self.follow_agent_flag = True - # if self.agent_to_follow is None: - # self.agent_to_follow = 0 - # else: - # self.agent_to_follow = (self.agent_to_follow - 1) % len( - # self.agent_ids - # ) - - # self.active_map_renderer = "car" - - # elif event.type == pygame.MOUSEBUTTONDOWN and event.button == 2: - # logging.debug("Pressed middle button -> Change to Map View") - - # self.follow_agent_flag = False - # self.agent_to_follow = None - - # self.active_map_renderer = "map" - - # elif event.type == pygame.KEYDOWN and event.key == pygame.K_s: - # logging.debug("Pressed S key -> Enable/disable rendering") - # self.draw_flag = not (self.draw_flag) - def render_points( self, points: list | np.ndarray, From 450ea141b2a351c911bd790667ed99ef93d43f40 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 03:06:23 -0400 Subject: [PATCH 22/55] Implement keyboard press event handle --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 778736c8..70f572f4 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -85,7 +85,7 @@ def __init__( legend.hoverEvent = lambda *args, **kwargs: None # self.scene() is a pyqtgraph.GraphicsScene.GraphicsScene.GraphicsScene self.window.scene().sigMouseClicked.connect(self.mouse_clicked) - + self.window.keyPressEvent = self.key_pressed # Remove axes self.canvas.hideAxis('bottom') @@ -203,6 +203,20 @@ def add_renderer_callback(self, callback_fn: Callable[[EnvRenderer], None]) -> N """ self.callbacks.append(callback_fn) + def key_pressed(self, event: QtGui.QKeyEvent) -> None: + """ + Handle key press events. + + Parameters + ---------- + event : QtGui.QKeyEvent + key event + """ + if event.key() == QtCore.Qt.Key.Key_S: + logging.debug("Pressed S key -> Enable/disable rendering") + self.draw_flag = not self.draw_flag + self.draw_flag_changed = True + def mouse_clicked(self, event: QtGui.QMouseEvent) -> None: """ Handle mouse click events. From 9e39cbb3968c82478629ccd1b0b7013becba2ce2 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 03:31:34 -0400 Subject: [PATCH 23/55] Add rendering yaml toggle to switch rendering types --- f1tenth_gym/envs/rendering/__init__.py | 11 ++++++++--- f1tenth_gym/envs/rendering/renderer.py | 3 +++ f1tenth_gym/envs/rendering/rendering.yaml | 1 + 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/f1tenth_gym/envs/rendering/__init__.py b/f1tenth_gym/envs/rendering/__init__.py index 9a56bd22..ea6ac128 100644 --- a/f1tenth_gym/envs/rendering/__init__.py +++ b/f1tenth_gym/envs/rendering/__init__.py @@ -28,13 +28,18 @@ def make_renderer( render_fps : int, optional rendering frames per second, by default 100 """ - from .rendering_pygame import PygameEnvRenderer - cfg_file = pathlib.Path(__file__).parent.absolute() / "rendering.yaml" render_spec = RenderSpec.from_yaml(cfg_file) + if render_spec.render_type == "pygame": + from .rendering_pygame import PygameEnvRenderer as EnvRenderer + elif render_spec.render_type == "pyqt6": + from .rendering_pyqt import PyQtEnvRenderer as EnvRenderer + else: + raise ValueError(f"Unknown render type: {render_spec.render_type}") + if render_mode in ["human", "rgb_array", "human_fast"]: - renderer = PygameEnvRenderer( + renderer = EnvRenderer( params=params, track=track, agent_ids=agent_ids, diff --git a/f1tenth_gym/envs/rendering/renderer.py b/f1tenth_gym/envs/rendering/renderer.py index 98305c82..a936ed08 100644 --- a/f1tenth_gym/envs/rendering/renderer.py +++ b/f1tenth_gym/envs/rendering/renderer.py @@ -17,6 +17,7 @@ class RenderSpec: show_wheels: bool show_info: Optional[bool] = True vehicle_palette: Optional[list[str]] = None + render_type: Optional[str] = "pygame" def __init__( self, @@ -27,6 +28,7 @@ def __init__( show_wheels: bool = False, show_info: bool = True, vehicle_palette: list[str] = None, + render_type: str = "pygame", ) -> None: """ Initialize rendering specification. @@ -55,6 +57,7 @@ def __init__( self.show_wheels = show_wheels self.show_info = show_info self.vehicle_palette = vehicle_palette or ["#984ea3"] + self.render_type = render_type @staticmethod def from_yaml(yaml_file: str | pathlib.Path): diff --git a/f1tenth_gym/envs/rendering/rendering.yaml b/f1tenth_gym/envs/rendering/rendering.yaml index 78e3ed69..f434c3f4 100644 --- a/f1tenth_gym/envs/rendering/rendering.yaml +++ b/f1tenth_gym/envs/rendering/rendering.yaml @@ -4,6 +4,7 @@ zoom_in_factor: 1.5 # [float] zoom in factor. 1.0 is no zoom, >1.0 is zoom in, show_wheels: True # [bool] it toggles the visualization of the vehicle wheels car_tickness: 1 # [px] thickness of the car show_info: True # [bool] it toggles the visualization of the instruction text +render_type: "pyqt6" # [str] rendering type. Options: "pygame", "pyqt6" vehicle_palette: # [list] cyclic list of colors for the vehicles - "#984ea3" - "#e41a1c" From 989f8a82109e11e15f076a27fec0a37ed91b5bfa Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 03:54:36 -0400 Subject: [PATCH 24/55] Fixed rendering of scaled track, works only for pyqt6 rendering --- examples/waypoint_follow.py | 22 +++++++++++++--------- f1tenth_gym/envs/track/track.py | 9 +++++++-- 2 files changed, 20 insertions(+), 11 deletions(-) diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index 0d86f602..855b358a 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -5,6 +5,7 @@ import numpy as np from numba import njit +from f1tenth_gym.envs.f110_env import F110Env """ Planner Helpers @@ -184,11 +185,11 @@ def __init__(self, track, wb): self.max_reacquire = 20.0 self.drawn_waypoints = [] - self.lookahead_point = np.array([0, 0, 0], dtype=np.float32) - self.current_index = 0 + self.lookahead_point = None + self.current_index = None - self.local_plan_render = None self.lookahead_point_render = None + self.local_plan_render = None def load_waypoints(self, conf): """ @@ -204,10 +205,11 @@ def render_lookahead_point(self, e): Callback to render the lookahead point. """ if self.lookahead_point is not None: - points = self.lookahead_point[:2][None] # shape (1, 2) if self.lookahead_point_render is None: + points = self.lookahead_point[:2][None] # shape (1, 2) self.lookahead_point_render = e.render_points(points, color=(0, 0, 128), size=2) else: + points = self.lookahead_point[:2][None] # shape (1, 2) self.lookahead_point_render.updateItems(points) def render_local_plan(self, e): @@ -215,10 +217,11 @@ def render_local_plan(self, e): update waypoints being drawn by EnvRenderer """ if self.current_index is not None: - points = self.waypoints[self.current_index : self.current_index + 10, :2] if self.local_plan_render is None: + points = self.waypoints[self.current_index : self.current_index + 10, :2] self.local_plan_render = e.render_lines(points, color=(0, 128, 0), size=1) else: + points = self.waypoints[self.current_index : self.current_index + 10, :2] self.local_plan_render.updateItems(points) def _get_current_waypoint( @@ -296,11 +299,11 @@ def main(): work = { "mass": 3.463388126201571, "lf": 0.15597534362552312, - "tlad": 0.82461887897713965, + "tlad": 0.82461887897713965*10, "vgain": 1, } - num_agents = 3 + num_agents = 1 env = gym.make( "f1tenth_gym:f1tenth-v0", config={ @@ -311,14 +314,15 @@ def main(): "control_input": ["speed", "steering_angle"], "model": "st", "observation_config": {"type": "kinematic_state"}, - "params": {"mu": 1.0}, + "params": F110Env.fullscale_vehicle_params(), "reset_config": {"type": "rl_random_static"}, + "scale": 10.0, }, render_mode="human", ) track = env.unwrapped.track - planner = PurePursuitPlanner(track=track, wb=0.17145 + 0.15875) + planner = PurePursuitPlanner(track=track, wb=(F110Env.fullscale_vehicle_params()["lf"] + F110Env.fullscale_vehicle_params()["lr"])) env.unwrapped.add_render_callback(track.raceline.render_waypoints) env.unwrapped.add_render_callback(planner.render_local_plan) diff --git a/f1tenth_gym/envs/track/track.py b/f1tenth_gym/envs/track/track.py index ba2d9108..f82abbbb 100644 --- a/f1tenth_gym/envs/track/track.py +++ b/f1tenth_gym/envs/track/track.py @@ -117,14 +117,19 @@ def from_track_name(track: str, track_scale: float = 1.0) -> Track: track_spec = Track.load_spec( track=track, filespec=str(track_dir / f"{track_dir.stem}_map.yaml") ) + track_spec.resolution = track_spec.resolution * track_scale + track_spec.origin = ( + track_spec.origin[0] * track_scale, + track_spec.origin[1] * track_scale, + track_spec.origin[2], + ) # load occupancy grid map_filename = pathlib.Path(track_spec.image) image = Image.open(track_dir / str(map_filename)).transpose( Transpose.FLIP_TOP_BOTTOM ) - image = image.resize(np.array(track_scale * np.array(image.size, dtype=np.int32), dtype=np.int32), Image.LANCZOS) - + occupancy_map = np.array(image).astype(np.float32) occupancy_map[occupancy_map <= 128] = 0.0 occupancy_map[occupancy_map > 128] = 255.0 From d8a3a452a793f08acc9715a03fd6474ad4a70dfe Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 13:27:00 -0400 Subject: [PATCH 25/55] Add qt as dependency. Fix render_points --- examples/waypoint_follow.py | 4 ++-- f1tenth_gym/envs/rendering/rendering_pyqt.py | 9 ++++----- pyproject.toml | 2 ++ 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index 0d86f602..a8c9e949 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -208,7 +208,7 @@ def render_lookahead_point(self, e): if self.lookahead_point_render is None: self.lookahead_point_render = e.render_points(points, color=(0, 0, 128), size=2) else: - self.lookahead_point_render.updateItems(points) + self.lookahead_point_render.setData(points) def render_local_plan(self, e): """ @@ -219,7 +219,7 @@ def render_local_plan(self, e): if self.local_plan_render is None: self.local_plan_render = e.render_lines(points, color=(0, 128, 0), size=1) else: - self.local_plan_render.updateItems(points) + self.local_plan_render.setData(points) def _get_current_waypoint( self, waypoints, lookahead_distance, position, theta diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 70f572f4..d4010c28 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -314,7 +314,7 @@ def render_points( points: list | np.ndarray, color: Optional[tuple[int, int, int]] = (0, 0, 255), size: Optional[int] = 1, - ) -> None: + ) -> pg.PlotDataItem: """ Render a sequence of xy points on screen. @@ -327,10 +327,9 @@ def render_points( size : Optional[int], optional size of the points in pixels, by default 1 """ - origin = self.map_origin - resolution = self.map_resolution - points = ((points - origin[:2]) / resolution).astype(int) - size = math.ceil(size) + return self.canvas.plot( + points[:, 0], points[:, 1], pen=None, symbol="o", symbolPen=pg.mkPen(color=color, width=0), symbolBrush=pg.mkBrush(color=color, width=0), symbolSize=size + ) def render_lines( self, diff --git a/pyproject.toml b/pyproject.toml index a558e896..b4d0d4a8 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -45,6 +45,8 @@ opencv-python = "^4.9.0.80" yamldataclassconfig = "^1.5.0" requests = "^2.31.0" shapely = "^2.0.2" +pyqtgraph = "^0.13.7" +PyQT6 = "^6.7.1" [tool.poetry.group.dev.dependencies] pytest = "^7.4.4" From 719465a18e162c15caa97013c5204c640c36d9d1 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 6 Aug 2024 13:33:49 -0400 Subject: [PATCH 26/55] Typo in toml --- pyproject.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pyproject.toml b/pyproject.toml index b4d0d4a8..0af5ef62 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -46,7 +46,7 @@ yamldataclassconfig = "^1.5.0" requests = "^2.31.0" shapely = "^2.0.2" pyqtgraph = "^0.13.7" -PyQT6 = "^6.7.1" +PyQt6 = "^6.7.1" [tool.poetry.group.dev.dependencies] pytest = "^7.4.4" From 35c31254a2208ebc85ad7e2a2a56d4c38d830957 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Fri, 9 Aug 2024 00:35:40 -0400 Subject: [PATCH 27/55] Fix wrong scan simulator resolution --- examples/waypoint_follow.py | 4 ++-- f1tenth_gym/envs/laser_models.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index cf35c128..53b89cd3 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -205,8 +205,8 @@ def render_lookahead_point(self, e): Callback to render the lookahead point. """ if self.lookahead_point is not None: + points = self.lookahead_point[:2][None] # shape (1, 2)~ if self.lookahead_point_render is None: - points = self.lookahead_point[:2][None] # shape (1, 2) self.lookahead_point_render = e.render_points(points, color=(0, 0, 128), size=2) else: self.lookahead_point_render.setData(points) @@ -216,8 +216,8 @@ def render_local_plan(self, e): update waypoints being drawn by EnvRenderer """ if self.current_index is not None: + points = self.waypoints[self.current_index : self.current_index + 10, :2] if self.local_plan_render is None: - points = self.waypoints[self.current_index : self.current_index + 10, :2] self.local_plan_render = e.render_lines(points, color=(0, 128, 0), size=1) else: self.local_plan_render.updateItems(points) diff --git a/f1tenth_gym/envs/laser_models.py b/f1tenth_gym/envs/laser_models.py index bd400507..0e80e6f9 100644 --- a/f1tenth_gym/envs/laser_models.py +++ b/f1tenth_gym/envs/laser_models.py @@ -480,7 +480,7 @@ def set_map(self, map: str | Track, map_scale: float = 1.0) -> bool: self.map_width = self.map_img.shape[1] # load map specification - self.map_resolution = self.track.spec.resolution * map_scale + self.map_resolution = self.track.spec.resolution self.origin = self.track.spec.origin self.orig_x = self.origin[0] From 78591ebafd8e2612b6a6369b20972ad973060b74 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Fri, 9 Aug 2024 01:20:49 -0400 Subject: [PATCH 28/55] Implemented rgb_array mode for rqt6 --- examples/video_recording.py | 2 +- f1tenth_gym/envs/rendering/rendering_pyqt.py | 19 +++++++++++++++---- 2 files changed, 16 insertions(+), 5 deletions(-) diff --git a/examples/video_recording.py b/examples/video_recording.py index f384b979..8fbd67e8 100644 --- a/examples/video_recording.py +++ b/examples/video_recording.py @@ -15,7 +15,7 @@ def main(): } env = gym.make( - "f1tenth_gym:f1tenth-v0, + "f1tenth_gym:f1tenth-v0", config={ "map": "Spielberg", "num_agents": 1, diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index d4010c28..1ea7a593 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -9,6 +9,7 @@ from PyQt6 import QtGui import pyqtgraph as pg from pyqtgraph.examples.utils import FrameCounter +from pyqtgraph.exporters import ImageExporter from PIL import ImageColor from .pyqt_objects import ( @@ -160,7 +161,10 @@ def __init__( self.follow_agent_flag: bool = False self.agent_to_follow: int = None - self.window.show() + if self.render_mode in ["human", "human_fast"]: + self.window.show() + elif self.render_mode == "rgb_array": + self.exporter = ImageExporter(self.canvas) def update(self, state: dict) -> None: """ @@ -304,9 +308,16 @@ def render(self) -> Optional[np.ndarray]: assert self.window is not None else: - # rgb_array - # TODO: extract the frame from the canvas - frame = None + # rgb_array mode => extract the frame from the canvas + qImage = self.exporter.export(toBytes=True) + + width = qImage.width() + height = qImage.height() + + ptr = qImage.bits() + ptr.setsize(height * width * 4) + frame = np.array(ptr).reshape(height, width, 4) # Copies the data + return frame def render_points( From 690daa9c94a91f665abf3b60cd90e7daaf5d884a Mon Sep 17 00:00:00 2001 From: Nandan Tumu Date: Sat, 21 Sep 2024 17:18:53 +0000 Subject: [PATCH 29/55] Updated ST model --- f1tenth_gym/envs/dynamic_models.py | 66 +++++++++--------------------- 1 file changed, 19 insertions(+), 47 deletions(-) diff --git a/f1tenth_gym/envs/dynamic_models.py b/f1tenth_gym/envs/dynamic_models.py index 790de252..91cc91da 100644 --- a/f1tenth_gym/envs/dynamic_models.py +++ b/f1tenth_gym/envs/dynamic_models.py @@ -1,24 +1,3 @@ -# Copyright 2020 Technical University of Munich, Professorship of Cyber-Physical Systems, Matthew O'Kelly, Aman Sinha, Hongrui Zheng - -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: - -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. - -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - - """ Prototype of vehicle dynamics functions and classes for simulating 2D Single Track dynamic model @@ -335,7 +314,7 @@ def vehicle_dynamics_st( ACCL = u[1] # switch to kinematic model for small velocities - if V < 0.5: + if V < 0.1: # wheelbase lwb = lf + lr BETA_HAT = np.arctan(np.tan(DELTA) * lr / lwb) @@ -362,6 +341,8 @@ def vehicle_dynamics_st( ) else: # system dynamics + glr = (g * lr - ACCL * h) + glf = (g * lf + ACCL * h) f = np.array( [ V * np.cos(PSI + BETA), # X_DOT @@ -369,31 +350,22 @@ def vehicle_dynamics_st( STEER_VEL, # DELTA_DOT ACCL, # V_DOT PSI_DOT, # PSI_DOT - ((mu * m) / (I * (lf + lr))) - * ( - lf * C_Sf * (g * lr - ACCL * h) * DELTA - + ( - lr * C_Sr * (g * lf + ACCL * h) - - lf * C_Sf * (g * lr - ACCL * h) - ) - * BETA - - ( - lf * lf * C_Sf * (g * lr - ACCL * h) - + lr * lr * C_Sr * (g * lf + ACCL * h) - ) - * (PSI_DOT / V) - ), # PSI_DOT_DOT - (mu / (V * (lr + lf))) - * ( - C_Sf * (g * lr - ACCL * h) * DELTA - - (C_Sr * (g * lf + ACCL * h) + C_Sf * (g * lr - ACCL * h)) * BETA - + ( - C_Sr * (g * lf + ACCL * h) * lr - - C_Sf * (g * lr - ACCL * h) * lf - ) - * (PSI_DOT / V) - ) - - PSI_DOT, # BETA_DOT + ((mu * m) / (I * (lf + lr))) * ( + lf * C_Sf * (g * lr - ACCL * h) * DELTA + + ( + lr * C_Sr * (g * lf + ACCL * h) - lf * C_Sf * (g * lr - ACCL * h) + ) * BETA + - ( + lf * lf * C_Sf * (g * lr - ACCL * h) + lr * lr * C_Sr * (g * lf + ACCL * h) + ) * (PSI_DOT / V) + ), # PSI_DOT_DOT + (mu / (V * (lr + lf))) * ( + C_Sf * (g * lr - ACCL * h) * DELTA \ + - (C_Sr * (g * lf + ACCL * h) + C_Sf * (g * lr - ACCL * h)) * BETA + + ( + C_Sr * (g * lf + ACCL * h) * lr - C_Sf * (g * lr - ACCL * h) * lf + ) * (PSI_DOT / V) + ) - PSI_DOT, # BETA_DOT ] ) From 0fe5f53f9f3951643fd510fbb79f2a2c49ae6ee1 Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 21 Sep 2024 13:43:47 -0400 Subject: [PATCH 30/55] Updated locked dependencies --- poetry.lock | 1921 +++++++++++++++++++++++++++------------------------ 1 file changed, 1034 insertions(+), 887 deletions(-) diff --git a/poetry.lock b/poetry.lock index c6f66176..d1b4be77 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry 1.8.1 and should not be changed by hand. +# This file is automatically @generated by Poetry 1.7.1 and should not be changed by hand. [[package]] name = "appnope" @@ -31,13 +31,13 @@ test = ["astroid (>=1,<2)", "astroid (>=2,<4)", "pytest"] [[package]] name = "autoflake" -version = "2.3.0" +version = "2.3.1" description = "Removes unused imports and unused variables" optional = false python-versions = ">=3.8" files = [ - {file = "autoflake-2.3.0-py3-none-any.whl", hash = "sha256:79a51eb8c0744759d2efe052455ab20aa6a314763510c3fd897499a402126327"}, - {file = "autoflake-2.3.0.tar.gz", hash = "sha256:8c2011fa34701b9d7dcf05b9873bc4859d4fce4e62dfea90dffefd1576f5f01d"}, + {file = "autoflake-2.3.1-py3-none-any.whl", hash = "sha256:3ae7495db9084b7b32818b4140e6dc4fc280b712fb414f5b8fe57b0a8e85a840"}, + {file = "autoflake-2.3.1.tar.gz", hash = "sha256:c98b75dc5b0a86459c4f01a1d32ac7eb4338ec4317a4469515ff1e687ecd909e"}, ] [package.dependencies] @@ -92,74 +92,89 @@ uvloop = ["uvloop (>=0.15.2)"] [[package]] name = "certifi" -version = "2024.2.2" +version = "2024.8.30" description = "Python package for providing Mozilla's CA Bundle." optional = false python-versions = ">=3.6" files = [ - {file = "certifi-2024.2.2-py3-none-any.whl", hash = "sha256:dc383c07b76109f368f6106eee2b593b04a011ea4d55f652c6ca24a754d1cdd1"}, - {file = "certifi-2024.2.2.tar.gz", hash = "sha256:0569859f95fc761b18b45ef421b1290a0f65f147e92a1e5eb3e635f9a5e4e66f"}, + {file = "certifi-2024.8.30-py3-none-any.whl", hash = "sha256:922820b53db7a7257ffbda3f597266d435245903d80737e34f8a45ff3e3230d8"}, + {file = "certifi-2024.8.30.tar.gz", hash = "sha256:bec941d2aa8195e248a60b31ff9f0558284cf01a52591ceda73ea9afffd69fd9"}, ] [[package]] name = "cffi" -version = "1.16.0" +version = "1.17.1" description = "Foreign Function Interface for Python calling C code." optional = false python-versions = ">=3.8" files = [ - {file = "cffi-1.16.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:6b3d6606d369fc1da4fd8c357d026317fbb9c9b75d36dc16e90e84c26854b088"}, - {file = "cffi-1.16.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ac0f5edd2360eea2f1daa9e26a41db02dd4b0451b48f7c318e217ee092a213e9"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7e61e3e4fa664a8588aa25c883eab612a188c725755afff6289454d6362b9673"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a72e8961a86d19bdb45851d8f1f08b041ea37d2bd8d4fd19903bc3083d80c896"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5b50bf3f55561dac5438f8e70bfcdfd74543fd60df5fa5f62d94e5867deca684"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7651c50c8c5ef7bdb41108b7b8c5a83013bfaa8a935590c5d74627c047a583c7"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e4108df7fe9b707191e55f33efbcb2d81928e10cea45527879a4749cbe472614"}, - {file = "cffi-1.16.0-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:32c68ef735dbe5857c810328cb2481e24722a59a2003018885514d4c09af9743"}, - {file = "cffi-1.16.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:673739cb539f8cdaa07d92d02efa93c9ccf87e345b9a0b556e3ecc666718468d"}, - {file = "cffi-1.16.0-cp310-cp310-win32.whl", hash = "sha256:9f90389693731ff1f659e55c7d1640e2ec43ff725cc61b04b2f9c6d8d017df6a"}, - {file = "cffi-1.16.0-cp310-cp310-win_amd64.whl", hash = "sha256:e6024675e67af929088fda399b2094574609396b1decb609c55fa58b028a32a1"}, - {file = "cffi-1.16.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b84834d0cf97e7d27dd5b7f3aca7b6e9263c56308ab9dc8aae9784abb774d404"}, - {file = "cffi-1.16.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1b8ebc27c014c59692bb2664c7d13ce7a6e9a629be20e54e7271fa696ff2b417"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ee07e47c12890ef248766a6e55bd38ebfb2bb8edd4142d56db91b21ea68b7627"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8a9d3ebe49f084ad71f9269834ceccbf398253c9fac910c4fd7053ff1386936"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e70f54f1796669ef691ca07d046cd81a29cb4deb1e5f942003f401c0c4a2695d"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5bf44d66cdf9e893637896c7faa22298baebcd18d1ddb6d2626a6e39793a1d56"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7b78010e7b97fef4bee1e896df8a4bbb6712b7f05b7ef630f9d1da00f6444d2e"}, - {file = "cffi-1.16.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:c6a164aa47843fb1b01e941d385aab7215563bb8816d80ff3a363a9f8448a8dc"}, - {file = "cffi-1.16.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e09f3ff613345df5e8c3667da1d918f9149bd623cd9070c983c013792a9a62eb"}, - {file = "cffi-1.16.0-cp311-cp311-win32.whl", hash = "sha256:2c56b361916f390cd758a57f2e16233eb4f64bcbeee88a4881ea90fca14dc6ab"}, - {file = "cffi-1.16.0-cp311-cp311-win_amd64.whl", hash = "sha256:db8e577c19c0fda0beb7e0d4e09e0ba74b1e4c092e0e40bfa12fe05b6f6d75ba"}, - {file = "cffi-1.16.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:fa3a0128b152627161ce47201262d3140edb5a5c3da88d73a1b790a959126956"}, - {file = "cffi-1.16.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:68e7c44931cc171c54ccb702482e9fc723192e88d25a0e133edd7aff8fcd1f6e"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:abd808f9c129ba2beda4cfc53bde801e5bcf9d6e0f22f095e45327c038bfe68e"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88e2b3c14bdb32e440be531ade29d3c50a1a59cd4e51b1dd8b0865c54ea5d2e2"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fcc8eb6d5902bb1cf6dc4f187ee3ea80a1eba0a89aba40a5cb20a5087d961357"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b7be2d771cdba2942e13215c4e340bfd76398e9227ad10402a8767ab1865d2e6"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e715596e683d2ce000574bae5d07bd522c781a822866c20495e52520564f0969"}, - {file = "cffi-1.16.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:2d92b25dbf6cae33f65005baf472d2c245c050b1ce709cc4588cdcdd5495b520"}, - {file = "cffi-1.16.0-cp312-cp312-win32.whl", hash = "sha256:b2ca4e77f9f47c55c194982e10f058db063937845bb2b7a86c84a6cfe0aefa8b"}, - {file = "cffi-1.16.0-cp312-cp312-win_amd64.whl", hash = "sha256:68678abf380b42ce21a5f2abde8efee05c114c2fdb2e9eef2efdb0257fba1235"}, - {file = "cffi-1.16.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:0c9ef6ff37e974b73c25eecc13952c55bceed9112be2d9d938ded8e856138bcc"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a09582f178759ee8128d9270cd1344154fd473bb77d94ce0aeb2a93ebf0feaf0"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e760191dd42581e023a68b758769e2da259b5d52e3103c6060ddc02c9edb8d7b"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:80876338e19c951fdfed6198e70bc88f1c9758b94578d5a7c4c91a87af3cf31c"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a6a14b17d7e17fa0d207ac08642c8820f84f25ce17a442fd15e27ea18d67c59b"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6602bc8dc6f3a9e02b6c22c4fc1e47aa50f8f8e6d3f78a5e16ac33ef5fefa324"}, - {file = "cffi-1.16.0-cp38-cp38-win32.whl", hash = "sha256:131fd094d1065b19540c3d72594260f118b231090295d8c34e19a7bbcf2e860a"}, - {file = "cffi-1.16.0-cp38-cp38-win_amd64.whl", hash = "sha256:31d13b0f99e0836b7ff893d37af07366ebc90b678b6664c955b54561fc36ef36"}, - {file = "cffi-1.16.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:582215a0e9adbe0e379761260553ba11c58943e4bbe9c36430c4ca6ac74b15ed"}, - {file = "cffi-1.16.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:b29ebffcf550f9da55bec9e02ad430c992a87e5f512cd63388abb76f1036d8d2"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dc9b18bf40cc75f66f40a7379f6a9513244fe33c0e8aa72e2d56b0196a7ef872"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9cb4a35b3642fc5c005a6755a5d17c6c8b6bcb6981baf81cea8bfbc8903e8ba8"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b86851a328eedc692acf81fb05444bdf1891747c25af7529e39ddafaf68a4f3f"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c0f31130ebc2d37cdd8e44605fb5fa7ad59049298b3f745c74fa74c62fbfcfc4"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f8e709127c6c77446a8c0a8c8bf3c8ee706a06cd44b1e827c3e6a2ee6b8c098"}, - {file = "cffi-1.16.0-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:748dcd1e3d3d7cd5443ef03ce8685043294ad6bd7c02a38d1bd367cfd968e000"}, - {file = "cffi-1.16.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:8895613bcc094d4a1b2dbe179d88d7fb4a15cee43c052e8885783fac397d91fe"}, - {file = "cffi-1.16.0-cp39-cp39-win32.whl", hash = "sha256:ed86a35631f7bfbb28e108dd96773b9d5a6ce4811cf6ea468bb6a359b256b1e4"}, - {file = "cffi-1.16.0-cp39-cp39-win_amd64.whl", hash = "sha256:3686dffb02459559c74dd3d81748269ffb0eb027c39a6fc99502de37d501faa8"}, - {file = "cffi-1.16.0.tar.gz", hash = "sha256:bcb3ef43e58665bbda2fb198698fcae6776483e0c4a631aa5647806c25e02cc0"}, + {file = "cffi-1.17.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:df8b1c11f177bc2313ec4b2d46baec87a5f3e71fc8b45dab2ee7cae86d9aba14"}, + {file = "cffi-1.17.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8f2cdc858323644ab277e9bb925ad72ae0e67f69e804f4898c070998d50b1a67"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:edae79245293e15384b51f88b00613ba9f7198016a5948b5dddf4917d4d26382"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:45398b671ac6d70e67da8e4224a065cec6a93541bb7aebe1b198a61b58c7b702"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ad9413ccdeda48c5afdae7e4fa2192157e991ff761e7ab8fdd8926f40b160cc3"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5da5719280082ac6bd9aa7becb3938dc9f9cbd57fac7d2871717b1feb0902ab6"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2bb1a08b8008b281856e5971307cc386a8e9c5b625ac297e853d36da6efe9c17"}, + {file = "cffi-1.17.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:045d61c734659cc045141be4bae381a41d89b741f795af1dd018bfb532fd0df8"}, + {file = "cffi-1.17.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:6883e737d7d9e4899a8a695e00ec36bd4e5e4f18fabe0aca0efe0a4b44cdb13e"}, + {file = "cffi-1.17.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:6b8b4a92e1c65048ff98cfe1f735ef8f1ceb72e3d5f0c25fdb12087a23da22be"}, + {file = "cffi-1.17.1-cp310-cp310-win32.whl", hash = "sha256:c9c3d058ebabb74db66e431095118094d06abf53284d9c81f27300d0e0d8bc7c"}, + {file = "cffi-1.17.1-cp310-cp310-win_amd64.whl", hash = "sha256:0f048dcf80db46f0098ccac01132761580d28e28bc0f78ae0d58048063317e15"}, + {file = "cffi-1.17.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a45e3c6913c5b87b3ff120dcdc03f6131fa0065027d0ed7ee6190736a74cd401"}, + {file = "cffi-1.17.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:30c5e0cb5ae493c04c8b42916e52ca38079f1b235c2f8ae5f4527b963c401caf"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f75c7ab1f9e4aca5414ed4d8e5c0e303a34f4421f8a0d47a4d019ceff0ab6af4"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a1ed2dd2972641495a3ec98445e09766f077aee98a1c896dcb4ad0d303628e41"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:46bf43160c1a35f7ec506d254e5c890f3c03648a4dbac12d624e4490a7046cd1"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a24ed04c8ffd54b0729c07cee15a81d964e6fee0e3d4d342a27b020d22959dc6"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:610faea79c43e44c71e1ec53a554553fa22321b65fae24889706c0a84d4ad86d"}, + {file = "cffi-1.17.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a9b15d491f3ad5d692e11f6b71f7857e7835eb677955c00cc0aefcd0669adaf6"}, + {file = "cffi-1.17.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:de2ea4b5833625383e464549fec1bc395c1bdeeb5f25c4a3a82b5a8c756ec22f"}, + {file = "cffi-1.17.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:fc48c783f9c87e60831201f2cce7f3b2e4846bf4d8728eabe54d60700b318a0b"}, + {file = "cffi-1.17.1-cp311-cp311-win32.whl", hash = "sha256:85a950a4ac9c359340d5963966e3e0a94a676bd6245a4b55bc43949eee26a655"}, + {file = "cffi-1.17.1-cp311-cp311-win_amd64.whl", hash = "sha256:caaf0640ef5f5517f49bc275eca1406b0ffa6aa184892812030f04c2abf589a0"}, + {file = "cffi-1.17.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:805b4371bf7197c329fcb3ead37e710d1bca9da5d583f5073b799d5c5bd1eee4"}, + {file = "cffi-1.17.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:733e99bc2df47476e3848417c5a4540522f234dfd4ef3ab7fafdf555b082ec0c"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1257bdabf294dceb59f5e70c64a3e2f462c30c7ad68092d01bbbfb1c16b1ba36"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da95af8214998d77a98cc14e3a3bd00aa191526343078b530ceb0bd710fb48a5"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d63afe322132c194cf832bfec0dc69a99fb9bb6bbd550f161a49e9e855cc78ff"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f79fc4fc25f1c8698ff97788206bb3c2598949bfe0fef03d299eb1b5356ada99"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b62ce867176a75d03a665bad002af8e6d54644fad99a3c70905c543130e39d93"}, + {file = "cffi-1.17.1-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:386c8bf53c502fff58903061338ce4f4950cbdcb23e2902d86c0f722b786bbe3"}, + {file = "cffi-1.17.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:4ceb10419a9adf4460ea14cfd6bc43d08701f0835e979bf821052f1805850fe8"}, + {file = "cffi-1.17.1-cp312-cp312-win32.whl", hash = "sha256:a08d7e755f8ed21095a310a693525137cfe756ce62d066e53f502a83dc550f65"}, + {file = "cffi-1.17.1-cp312-cp312-win_amd64.whl", hash = "sha256:51392eae71afec0d0c8fb1a53b204dbb3bcabcb3c9b807eedf3e1e6ccf2de903"}, + {file = "cffi-1.17.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:f3a2b4222ce6b60e2e8b337bb9596923045681d71e5a082783484d845390938e"}, + {file = "cffi-1.17.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:0984a4925a435b1da406122d4d7968dd861c1385afe3b45ba82b750f229811e2"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d01b12eeeb4427d3110de311e1774046ad344f5b1a7403101878976ecd7a10f3"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:706510fe141c86a69c8ddc029c7910003a17353970cff3b904ff0686a5927683"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:de55b766c7aa2e2a3092c51e0483d700341182f08e67c63630d5b6f200bb28e5"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c59d6e989d07460165cc5ad3c61f9fd8f1b4796eacbd81cee78957842b834af4"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd398dbc6773384a17fe0d3e7eeb8d1a21c2200473ee6806bb5e6a8e62bb73dd"}, + {file = "cffi-1.17.1-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:3edc8d958eb099c634dace3c7e16560ae474aa3803a5df240542b305d14e14ed"}, + {file = "cffi-1.17.1-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:72e72408cad3d5419375fc87d289076ee319835bdfa2caad331e377589aebba9"}, + {file = "cffi-1.17.1-cp313-cp313-win32.whl", hash = "sha256:e03eab0a8677fa80d646b5ddece1cbeaf556c313dcfac435ba11f107ba117b5d"}, + {file = "cffi-1.17.1-cp313-cp313-win_amd64.whl", hash = "sha256:f6a16c31041f09ead72d69f583767292f750d24913dadacf5756b966aacb3f1a"}, + {file = "cffi-1.17.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:636062ea65bd0195bc012fea9321aca499c0504409f413dc88af450b57ffd03b"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c7eac2ef9b63c79431bc4b25f1cd649d7f061a28808cbc6c47b534bd789ef964"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e221cf152cff04059d011ee126477f0d9588303eb57e88923578ace7baad17f9"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:31000ec67d4221a71bd3f67df918b1f88f676f1c3b535a7eb473255fdc0b83fc"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:6f17be4345073b0a7b8ea599688f692ac3ef23ce28e5df79c04de519dbc4912c"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0e2b1fac190ae3ebfe37b979cc1ce69c81f4e4fe5746bb401dca63a9062cdaf1"}, + {file = "cffi-1.17.1-cp38-cp38-win32.whl", hash = "sha256:7596d6620d3fa590f677e9ee430df2958d2d6d6de2feeae5b20e82c00b76fbf8"}, + {file = "cffi-1.17.1-cp38-cp38-win_amd64.whl", hash = "sha256:78122be759c3f8a014ce010908ae03364d00a1f81ab5c7f4a7a5120607ea56e1"}, + {file = "cffi-1.17.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:b2ab587605f4ba0bf81dc0cb08a41bd1c0a5906bd59243d56bad7668a6fc6c16"}, + {file = "cffi-1.17.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:28b16024becceed8c6dfbc75629e27788d8a3f9030691a1dbf9821a128b22c36"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1d599671f396c4723d016dbddb72fe8e0397082b0a77a4fab8028923bec050e8"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ca74b8dbe6e8e8263c0ffd60277de77dcee6c837a3d0881d8c1ead7268c9e576"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f7f5baafcc48261359e14bcd6d9bff6d4b28d9103847c9e136694cb0501aef87"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:98e3969bcff97cae1b2def8ba499ea3d6f31ddfdb7635374834cf89a1a08ecf0"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cdf5ce3acdfd1661132f2a9c19cac174758dc2352bfe37d98aa7512c6b7178b3"}, + {file = "cffi-1.17.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:9755e4345d1ec879e3849e62222a18c7174d65a6a92d5b346b1863912168b595"}, + {file = "cffi-1.17.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:f1e22e8c4419538cb197e4dd60acc919d7696e5ef98ee4da4e01d3f8cfa4cc5a"}, + {file = "cffi-1.17.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:c03e868a0b3bc35839ba98e74211ed2b05d2119be4e8a0f224fba9384f1fe02e"}, + {file = "cffi-1.17.1-cp39-cp39-win32.whl", hash = "sha256:e31ae45bc2e29f6b2abd0de1cc3b9d5205aa847cafaecb8af1476a609a2f6eb7"}, + {file = "cffi-1.17.1-cp39-cp39-win_amd64.whl", hash = "sha256:d016c76bdd850f3c626af19b0542c9677ba156e4ee4fccfdd7848803533ef662"}, + {file = "cffi-1.17.1.tar.gz", hash = "sha256:1c39c6016c32bc48dd54561950ebd6836e1670f2ae46128f67cf49e789c52824"}, ] [package.dependencies] @@ -302,13 +317,13 @@ files = [ [[package]] name = "comm" -version = "0.2.1" +version = "0.2.2" description = "Jupyter Python Comm implementation, for usage in ipykernel, xeus-python etc." optional = false python-versions = ">=3.8" files = [ - {file = "comm-0.2.1-py3-none-any.whl", hash = "sha256:87928485c0dfc0e7976fd89fc1e187023cf587e7c353e4a9b417555b44adf021"}, - {file = "comm-0.2.1.tar.gz", hash = "sha256:0bc91edae1344d39d3661dcbc36937181fdaddb304790458f8b044dbc064b89a"}, + {file = "comm-0.2.2-py3-none-any.whl", hash = "sha256:e6fb86cb70ff661ee8c9c14e7d36d6de3b4066f1441be4063df9c5009f0a64d3"}, + {file = "comm-0.2.2.tar.gz", hash = "sha256:3fd7a84065306e07bea1773df6eb8282de51ba82f77c72f9c85716ab11fe980e"}, ] [package.dependencies] @@ -319,66 +334,87 @@ test = ["pytest"] [[package]] name = "contourpy" -version = "1.2.0" +version = "1.3.0" description = "Python library for calculating contours of 2D quadrilateral grids" optional = false python-versions = ">=3.9" files = [ - {file = "contourpy-1.2.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:0274c1cb63625972c0c007ab14dd9ba9e199c36ae1a231ce45d725cbcbfd10a8"}, - {file = "contourpy-1.2.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ab459a1cbbf18e8698399c595a01f6dcc5c138220ca3ea9e7e6126232d102bb4"}, - {file = "contourpy-1.2.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6fdd887f17c2f4572ce548461e4f96396681212d858cae7bd52ba3310bc6f00f"}, - {file = "contourpy-1.2.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5d16edfc3fc09968e09ddffada434b3bf989bf4911535e04eada58469873e28e"}, - {file = "contourpy-1.2.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1c203f617abc0dde5792beb586f827021069fb6d403d7f4d5c2b543d87edceb9"}, - {file = "contourpy-1.2.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b69303ceb2e4d4f146bf82fda78891ef7bcd80c41bf16bfca3d0d7eb545448aa"}, - {file = "contourpy-1.2.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:884c3f9d42d7218304bc74a8a7693d172685c84bd7ab2bab1ee567b769696df9"}, - {file = "contourpy-1.2.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:4a1b1208102be6e851f20066bf0e7a96b7d48a07c9b0cfe6d0d4545c2f6cadab"}, - {file = "contourpy-1.2.0-cp310-cp310-win32.whl", hash = "sha256:34b9071c040d6fe45d9826cbbe3727d20d83f1b6110d219b83eb0e2a01d79488"}, - {file = "contourpy-1.2.0-cp310-cp310-win_amd64.whl", hash = "sha256:bd2f1ae63998da104f16a8b788f685e55d65760cd1929518fd94cd682bf03e41"}, - {file = "contourpy-1.2.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:dd10c26b4eadae44783c45ad6655220426f971c61d9b239e6f7b16d5cdaaa727"}, - {file = "contourpy-1.2.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5c6b28956b7b232ae801406e529ad7b350d3f09a4fde958dfdf3c0520cdde0dd"}, - {file = "contourpy-1.2.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ebeac59e9e1eb4b84940d076d9f9a6cec0064e241818bcb6e32124cc5c3e377a"}, - {file = "contourpy-1.2.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:139d8d2e1c1dd52d78682f505e980f592ba53c9f73bd6be102233e358b401063"}, - {file = "contourpy-1.2.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1e9dc350fb4c58adc64df3e0703ab076f60aac06e67d48b3848c23647ae4310e"}, - {file = "contourpy-1.2.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:18fc2b4ed8e4a8fe849d18dce4bd3c7ea637758c6343a1f2bae1e9bd4c9f4686"}, - {file = "contourpy-1.2.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:16a7380e943a6d52472096cb7ad5264ecee36ed60888e2a3d3814991a0107286"}, - {file = "contourpy-1.2.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:8d8faf05be5ec8e02a4d86f616fc2a0322ff4a4ce26c0f09d9f7fb5330a35c95"}, - {file = "contourpy-1.2.0-cp311-cp311-win32.whl", hash = "sha256:67b7f17679fa62ec82b7e3e611c43a016b887bd64fb933b3ae8638583006c6d6"}, - {file = "contourpy-1.2.0-cp311-cp311-win_amd64.whl", hash = "sha256:99ad97258985328b4f207a5e777c1b44a83bfe7cf1f87b99f9c11d4ee477c4de"}, - {file = "contourpy-1.2.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:575bcaf957a25d1194903a10bc9f316c136c19f24e0985a2b9b5608bdf5dbfe0"}, - {file = "contourpy-1.2.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:9e6c93b5b2dbcedad20a2f18ec22cae47da0d705d454308063421a3b290d9ea4"}, - {file = "contourpy-1.2.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:464b423bc2a009088f19bdf1f232299e8b6917963e2b7e1d277da5041f33a779"}, - {file = "contourpy-1.2.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:68ce4788b7d93e47f84edd3f1f95acdcd142ae60bc0e5493bfd120683d2d4316"}, - {file = "contourpy-1.2.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3d7d1f8871998cdff5d2ff6a087e5e1780139abe2838e85b0b46b7ae6cc25399"}, - {file = "contourpy-1.2.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6e739530c662a8d6d42c37c2ed52a6f0932c2d4a3e8c1f90692ad0ce1274abe0"}, - {file = "contourpy-1.2.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:247b9d16535acaa766d03037d8e8fb20866d054d3c7fbf6fd1f993f11fc60ca0"}, - {file = "contourpy-1.2.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:461e3ae84cd90b30f8d533f07d87c00379644205b1d33a5ea03381edc4b69431"}, - {file = "contourpy-1.2.0-cp312-cp312-win32.whl", hash = "sha256:1c2559d6cffc94890b0529ea7eeecc20d6fadc1539273aa27faf503eb4656d8f"}, - {file = "contourpy-1.2.0-cp312-cp312-win_amd64.whl", hash = "sha256:491b1917afdd8638a05b611a56d46587d5a632cabead889a5440f7c638bc6ed9"}, - {file = "contourpy-1.2.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:5fd1810973a375ca0e097dee059c407913ba35723b111df75671a1976efa04bc"}, - {file = "contourpy-1.2.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:999c71939aad2780f003979b25ac5b8f2df651dac7b38fb8ce6c46ba5abe6ae9"}, - {file = "contourpy-1.2.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b7caf9b241464c404613512d5594a6e2ff0cc9cb5615c9475cc1d9b514218ae8"}, - {file = "contourpy-1.2.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:266270c6f6608340f6c9836a0fb9b367be61dde0c9a9a18d5ece97774105ff3e"}, - {file = "contourpy-1.2.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:dbd50d0a0539ae2e96e537553aff6d02c10ed165ef40c65b0e27e744a0f10af8"}, - {file = "contourpy-1.2.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:11f8d2554e52f459918f7b8e6aa20ec2a3bce35ce95c1f0ef4ba36fbda306df5"}, - {file = "contourpy-1.2.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:ce96dd400486e80ac7d195b2d800b03e3e6a787e2a522bfb83755938465a819e"}, - {file = "contourpy-1.2.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:6d3364b999c62f539cd403f8123ae426da946e142312a514162adb2addd8d808"}, - {file = "contourpy-1.2.0-cp39-cp39-win32.whl", hash = "sha256:1c88dfb9e0c77612febebb6ac69d44a8d81e3dc60f993215425b62c1161353f4"}, - {file = "contourpy-1.2.0-cp39-cp39-win_amd64.whl", hash = "sha256:78e6ad33cf2e2e80c5dfaaa0beec3d61face0fb650557100ee36db808bfa6843"}, - {file = "contourpy-1.2.0-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:be16975d94c320432657ad2402f6760990cb640c161ae6da1363051805fa8108"}, - {file = "contourpy-1.2.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b95a225d4948b26a28c08307a60ac00fb8671b14f2047fc5476613252a129776"}, - {file = "contourpy-1.2.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:0d7e03c0f9a4f90dc18d4e77e9ef4ec7b7bbb437f7f675be8e530d65ae6ef956"}, - {file = "contourpy-1.2.0.tar.gz", hash = "sha256:171f311cb758de7da13fc53af221ae47a5877be5a0843a9fe150818c51ed276a"}, + {file = "contourpy-1.3.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:880ea32e5c774634f9fcd46504bf9f080a41ad855f4fef54f5380f5133d343c7"}, + {file = "contourpy-1.3.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:76c905ef940a4474a6289c71d53122a4f77766eef23c03cd57016ce19d0f7b42"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:92f8557cbb07415a4d6fa191f20fd9d2d9eb9c0b61d1b2f52a8926e43c6e9af7"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:36f965570cff02b874773c49bfe85562b47030805d7d8360748f3eca570f4cab"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:cacd81e2d4b6f89c9f8a5b69b86490152ff39afc58a95af002a398273e5ce589"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:69375194457ad0fad3a839b9e29aa0b0ed53bb54db1bfb6c3ae43d111c31ce41"}, + {file = "contourpy-1.3.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:7a52040312b1a858b5e31ef28c2e865376a386c60c0e248370bbea2d3f3b760d"}, + {file = "contourpy-1.3.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3faeb2998e4fcb256542e8a926d08da08977f7f5e62cf733f3c211c2a5586223"}, + {file = "contourpy-1.3.0-cp310-cp310-win32.whl", hash = "sha256:36e0cff201bcb17a0a8ecc7f454fe078437fa6bda730e695a92f2d9932bd507f"}, + {file = "contourpy-1.3.0-cp310-cp310-win_amd64.whl", hash = "sha256:87ddffef1dbe5e669b5c2440b643d3fdd8622a348fe1983fad7a0f0ccb1cd67b"}, + {file = "contourpy-1.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0fa4c02abe6c446ba70d96ece336e621efa4aecae43eaa9b030ae5fb92b309ad"}, + {file = "contourpy-1.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:834e0cfe17ba12f79963861e0f908556b2cedd52e1f75e6578801febcc6a9f49"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dbc4c3217eee163fa3984fd1567632b48d6dfd29216da3ded3d7b844a8014a66"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4865cd1d419e0c7a7bf6de1777b185eebdc51470800a9f42b9e9decf17762081"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:303c252947ab4b14c08afeb52375b26781ccd6a5ccd81abcdfc1fafd14cf93c1"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:637f674226be46f6ba372fd29d9523dd977a291f66ab2a74fbeb5530bb3f445d"}, + {file = "contourpy-1.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:76a896b2f195b57db25d6b44e7e03f221d32fe318d03ede41f8b4d9ba1bff53c"}, + {file = "contourpy-1.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:e1fd23e9d01591bab45546c089ae89d926917a66dceb3abcf01f6105d927e2cb"}, + {file = "contourpy-1.3.0-cp311-cp311-win32.whl", hash = "sha256:d402880b84df3bec6eab53cd0cf802cae6a2ef9537e70cf75e91618a3801c20c"}, + {file = "contourpy-1.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:6cb6cc968059db9c62cb35fbf70248f40994dfcd7aa10444bbf8b3faeb7c2d67"}, + {file = "contourpy-1.3.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:570ef7cf892f0afbe5b2ee410c507ce12e15a5fa91017a0009f79f7d93a1268f"}, + {file = "contourpy-1.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:da84c537cb8b97d153e9fb208c221c45605f73147bd4cadd23bdae915042aad6"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0be4d8425bfa755e0fd76ee1e019636ccc7c29f77a7c86b4328a9eb6a26d0639"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9c0da700bf58f6e0b65312d0a5e695179a71d0163957fa381bb3c1f72972537c"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:eb8b141bb00fa977d9122636b16aa67d37fd40a3d8b52dd837e536d64b9a4d06"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3634b5385c6716c258d0419c46d05c8aa7dc8cb70326c9a4fb66b69ad2b52e09"}, + {file = "contourpy-1.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0dce35502151b6bd35027ac39ba6e5a44be13a68f55735c3612c568cac3805fd"}, + {file = "contourpy-1.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:aea348f053c645100612b333adc5983d87be69acdc6d77d3169c090d3b01dc35"}, + {file = "contourpy-1.3.0-cp312-cp312-win32.whl", hash = "sha256:90f73a5116ad1ba7174341ef3ea5c3150ddf20b024b98fb0c3b29034752c8aeb"}, + {file = "contourpy-1.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:b11b39aea6be6764f84360fce6c82211a9db32a7c7de8fa6dd5397cf1d079c3b"}, + {file = "contourpy-1.3.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:3e1c7fa44aaae40a2247e2e8e0627f4bea3dd257014764aa644f319a5f8600e3"}, + {file = "contourpy-1.3.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:364174c2a76057feef647c802652f00953b575723062560498dc7930fc9b1cb7"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:32b238b3b3b649e09ce9aaf51f0c261d38644bdfa35cbaf7b263457850957a84"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d51fca85f9f7ad0b65b4b9fe800406d0d77017d7270d31ec3fb1cc07358fdea0"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:732896af21716b29ab3e988d4ce14bc5133733b85956316fb0c56355f398099b"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d73f659398a0904e125280836ae6f88ba9b178b2fed6884f3b1f95b989d2c8da"}, + {file = "contourpy-1.3.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:c6c7c2408b7048082932cf4e641fa3b8ca848259212f51c8c59c45aa7ac18f14"}, + {file = "contourpy-1.3.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:f317576606de89da6b7e0861cf6061f6146ead3528acabff9236458a6ba467f8"}, + {file = "contourpy-1.3.0-cp313-cp313-win32.whl", hash = "sha256:31cd3a85dbdf1fc002280c65caa7e2b5f65e4a973fcdf70dd2fdcb9868069294"}, + {file = "contourpy-1.3.0-cp313-cp313-win_amd64.whl", hash = "sha256:4553c421929ec95fb07b3aaca0fae668b2eb5a5203d1217ca7c34c063c53d087"}, + {file = "contourpy-1.3.0-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:345af746d7766821d05d72cb8f3845dfd08dd137101a2cb9b24de277d716def8"}, + {file = "contourpy-1.3.0-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:3bb3808858a9dc68f6f03d319acd5f1b8a337e6cdda197f02f4b8ff67ad2057b"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:420d39daa61aab1221567b42eecb01112908b2cab7f1b4106a52caaec8d36973"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4d63ee447261e963af02642ffcb864e5a2ee4cbfd78080657a9880b8b1868e18"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:167d6c890815e1dac9536dca00828b445d5d0df4d6a8c6adb4a7ec3166812fa8"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:710a26b3dc80c0e4febf04555de66f5fd17e9cf7170a7b08000601a10570bda6"}, + {file = "contourpy-1.3.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:75ee7cb1a14c617f34a51d11fa7524173e56551646828353c4af859c56b766e2"}, + {file = "contourpy-1.3.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:33c92cdae89ec5135d036e7218e69b0bb2851206077251f04a6c4e0e21f03927"}, + {file = "contourpy-1.3.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:a11077e395f67ffc2c44ec2418cfebed032cd6da3022a94fc227b6faf8e2acb8"}, + {file = "contourpy-1.3.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e8134301d7e204c88ed7ab50028ba06c683000040ede1d617298611f9dc6240c"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e12968fdfd5bb45ffdf6192a590bd8ddd3ba9e58360b29683c6bb71a7b41edca"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fd2a0fc506eccaaa7595b7e1418951f213cf8255be2600f1ea1b61e46a60c55f"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4cfb5c62ce023dfc410d6059c936dcf96442ba40814aefbfa575425a3a7f19dc"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:68a32389b06b82c2fdd68276148d7b9275b5f5cf13e5417e4252f6d1a34f72a2"}, + {file = "contourpy-1.3.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:94e848a6b83da10898cbf1311a815f770acc9b6a3f2d646f330d57eb4e87592e"}, + {file = "contourpy-1.3.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:d78ab28a03c854a873787a0a42254a0ccb3cb133c672f645c9f9c8f3ae9d0800"}, + {file = "contourpy-1.3.0-cp39-cp39-win32.whl", hash = "sha256:81cb5ed4952aae6014bc9d0421dec7c5835c9c8c31cdf51910b708f548cf58e5"}, + {file = "contourpy-1.3.0-cp39-cp39-win_amd64.whl", hash = "sha256:14e262f67bd7e6eb6880bc564dcda30b15e351a594657e55b7eec94b6ef72843"}, + {file = "contourpy-1.3.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:fe41b41505a5a33aeaed2a613dccaeaa74e0e3ead6dd6fd3a118fb471644fd6c"}, + {file = "contourpy-1.3.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eca7e17a65f72a5133bdbec9ecf22401c62bcf4821361ef7811faee695799779"}, + {file = "contourpy-1.3.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:1ec4dc6bf570f5b22ed0d7efba0dfa9c5b9e0431aeea7581aa217542d9e809a4"}, + {file = "contourpy-1.3.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:00ccd0dbaad6d804ab259820fa7cb0b8036bda0686ef844d24125d8287178ce0"}, + {file = "contourpy-1.3.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8ca947601224119117f7c19c9cdf6b3ab54c5726ef1d906aa4a69dfb6dd58102"}, + {file = "contourpy-1.3.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:c6ec93afeb848a0845a18989da3beca3eec2c0f852322efe21af1931147d12cb"}, + {file = "contourpy-1.3.0.tar.gz", hash = "sha256:7ffa0db17717a8ffb127efd0c95a4362d996b892c2904db72428d5b52e1938a4"}, ] [package.dependencies] -numpy = ">=1.20,<2.0" +numpy = ">=1.23" [package.extras] bokeh = ["bokeh", "selenium"] docs = ["furo", "sphinx (>=7.2)", "sphinx-copybutton"] -mypy = ["contourpy[bokeh,docs]", "docutils-stubs", "mypy (==1.6.1)", "types-Pillow"] +mypy = ["contourpy[bokeh,docs]", "docutils-stubs", "mypy (==1.11.1)", "types-Pillow"] test = ["Pillow", "contourpy[test-no-images]", "matplotlib"] -test-no-images = ["pytest", "pytest-cov", "pytest-xdist", "wurlitzer"] +test-no-images = ["pytest", "pytest-cov", "pytest-rerunfailures", "pytest-xdist", "wurlitzer"] [[package]] name = "cycler" @@ -397,48 +433,52 @@ tests = ["pytest", "pytest-cov", "pytest-xdist"] [[package]] name = "dataclasses-json" -version = "0.6.4" -description = "Easily serialize dataclasses to and from JSON." +version = "0.5.9" +description = "Easily serialize dataclasses to and from JSON" optional = false -python-versions = ">=3.7,<4.0" +python-versions = ">=3.6" files = [ - {file = "dataclasses_json-0.6.4-py3-none-any.whl", hash = "sha256:f90578b8a3177f7552f4e1a6e535e84293cd5da421fcce0642d49c0d7bdf8df2"}, - {file = "dataclasses_json-0.6.4.tar.gz", hash = "sha256:73696ebf24936560cca79a2430cbc4f3dd23ac7bf46ed17f38e5e5e7657a6377"}, + {file = "dataclasses-json-0.5.9.tar.gz", hash = "sha256:e9ac87b73edc0141aafbce02b44e93553c3123ad574958f0fe52a534b6707e8e"}, + {file = "dataclasses_json-0.5.9-py3-none-any.whl", hash = "sha256:1280542631df1c375b7bc92e5b86d39e06c44760d7e3571a537b3b8acabf2f0c"}, ] [package.dependencies] -marshmallow = ">=3.18.0,<4.0.0" -typing-inspect = ">=0.4.0,<1" +marshmallow = ">=3.3.0,<4.0.0" +marshmallow-enum = ">=1.5.1,<2.0.0" +typing-inspect = ">=0.4.0" + +[package.extras] +dev = ["flake8", "hypothesis", "ipython", "mypy (>=0.710)", "portray", "pytest (>=7.2.0)", "setuptools", "simplejson", "twine", "types-dataclasses", "wheel"] [[package]] name = "debugpy" -version = "1.8.1" +version = "1.8.5" description = "An implementation of the Debug Adapter Protocol for Python" optional = false python-versions = ">=3.8" files = [ - {file = "debugpy-1.8.1-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:3bda0f1e943d386cc7a0e71bfa59f4137909e2ed947fb3946c506e113000f741"}, - {file = "debugpy-1.8.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dda73bf69ea479c8577a0448f8c707691152e6c4de7f0c4dec5a4bc11dee516e"}, - {file = "debugpy-1.8.1-cp310-cp310-win32.whl", hash = "sha256:3a79c6f62adef994b2dbe9fc2cc9cc3864a23575b6e387339ab739873bea53d0"}, - {file = "debugpy-1.8.1-cp310-cp310-win_amd64.whl", hash = "sha256:7eb7bd2b56ea3bedb009616d9e2f64aab8fc7000d481faec3cd26c98a964bcdd"}, - {file = "debugpy-1.8.1-cp311-cp311-macosx_11_0_universal2.whl", hash = "sha256:016a9fcfc2c6b57f939673c874310d8581d51a0fe0858e7fac4e240c5eb743cb"}, - {file = "debugpy-1.8.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd97ed11a4c7f6d042d320ce03d83b20c3fb40da892f994bc041bbc415d7a099"}, - {file = "debugpy-1.8.1-cp311-cp311-win32.whl", hash = "sha256:0de56aba8249c28a300bdb0672a9b94785074eb82eb672db66c8144fff673146"}, - {file = "debugpy-1.8.1-cp311-cp311-win_amd64.whl", hash = "sha256:1a9fe0829c2b854757b4fd0a338d93bc17249a3bf69ecf765c61d4c522bb92a8"}, - {file = "debugpy-1.8.1-cp312-cp312-macosx_11_0_universal2.whl", hash = "sha256:3ebb70ba1a6524d19fa7bb122f44b74170c447d5746a503e36adc244a20ac539"}, - {file = "debugpy-1.8.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a2e658a9630f27534e63922ebf655a6ab60c370f4d2fc5c02a5b19baf4410ace"}, - {file = "debugpy-1.8.1-cp312-cp312-win32.whl", hash = "sha256:caad2846e21188797a1f17fc09c31b84c7c3c23baf2516fed5b40b378515bbf0"}, - {file = "debugpy-1.8.1-cp312-cp312-win_amd64.whl", hash = "sha256:edcc9f58ec0fd121a25bc950d4578df47428d72e1a0d66c07403b04eb93bcf98"}, - {file = "debugpy-1.8.1-cp38-cp38-macosx_11_0_x86_64.whl", hash = "sha256:7a3afa222f6fd3d9dfecd52729bc2e12c93e22a7491405a0ecbf9e1d32d45b39"}, - {file = "debugpy-1.8.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d915a18f0597ef685e88bb35e5d7ab968964b7befefe1aaea1eb5b2640b586c7"}, - {file = "debugpy-1.8.1-cp38-cp38-win32.whl", hash = "sha256:92116039b5500633cc8d44ecc187abe2dfa9b90f7a82bbf81d079fcdd506bae9"}, - {file = "debugpy-1.8.1-cp38-cp38-win_amd64.whl", hash = "sha256:e38beb7992b5afd9d5244e96ad5fa9135e94993b0c551ceebf3fe1a5d9beb234"}, - {file = "debugpy-1.8.1-cp39-cp39-macosx_11_0_x86_64.whl", hash = "sha256:bfb20cb57486c8e4793d41996652e5a6a885b4d9175dd369045dad59eaacea42"}, - {file = "debugpy-1.8.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:efd3fdd3f67a7e576dd869c184c5dd71d9aaa36ded271939da352880c012e703"}, - {file = "debugpy-1.8.1-cp39-cp39-win32.whl", hash = "sha256:58911e8521ca0c785ac7a0539f1e77e0ce2df753f786188f382229278b4cdf23"}, - {file = "debugpy-1.8.1-cp39-cp39-win_amd64.whl", hash = "sha256:6df9aa9599eb05ca179fb0b810282255202a66835c6efb1d112d21ecb830ddd3"}, - {file = "debugpy-1.8.1-py2.py3-none-any.whl", hash = "sha256:28acbe2241222b87e255260c76741e1fbf04fdc3b6d094fcf57b6c6f75ce1242"}, - {file = "debugpy-1.8.1.zip", hash = "sha256:f696d6be15be87aef621917585f9bb94b1dc9e8aced570db1b8a6fc14e8f9b42"}, + {file = "debugpy-1.8.5-cp310-cp310-macosx_12_0_x86_64.whl", hash = "sha256:7e4d594367d6407a120b76bdaa03886e9eb652c05ba7f87e37418426ad2079f7"}, + {file = "debugpy-1.8.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4413b7a3ede757dc33a273a17d685ea2b0c09dbd312cc03f5534a0fd4d40750a"}, + {file = "debugpy-1.8.5-cp310-cp310-win32.whl", hash = "sha256:dd3811bd63632bb25eda6bd73bea8e0521794cda02be41fa3160eb26fc29e7ed"}, + {file = "debugpy-1.8.5-cp310-cp310-win_amd64.whl", hash = "sha256:b78c1250441ce893cb5035dd6f5fc12db968cc07f91cc06996b2087f7cefdd8e"}, + {file = "debugpy-1.8.5-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:606bccba19f7188b6ea9579c8a4f5a5364ecd0bf5a0659c8a5d0e10dcee3032a"}, + {file = "debugpy-1.8.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:db9fb642938a7a609a6c865c32ecd0d795d56c1aaa7a7a5722d77855d5e77f2b"}, + {file = "debugpy-1.8.5-cp311-cp311-win32.whl", hash = "sha256:4fbb3b39ae1aa3e5ad578f37a48a7a303dad9a3d018d369bc9ec629c1cfa7408"}, + {file = "debugpy-1.8.5-cp311-cp311-win_amd64.whl", hash = "sha256:345d6a0206e81eb68b1493ce2fbffd57c3088e2ce4b46592077a943d2b968ca3"}, + {file = "debugpy-1.8.5-cp312-cp312-macosx_12_0_universal2.whl", hash = "sha256:5b5c770977c8ec6c40c60d6f58cacc7f7fe5a45960363d6974ddb9b62dbee156"}, + {file = "debugpy-1.8.5-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c0a65b00b7cdd2ee0c2cf4c7335fef31e15f1b7056c7fdbce9e90193e1a8c8cb"}, + {file = "debugpy-1.8.5-cp312-cp312-win32.whl", hash = "sha256:c9f7c15ea1da18d2fcc2709e9f3d6de98b69a5b0fff1807fb80bc55f906691f7"}, + {file = "debugpy-1.8.5-cp312-cp312-win_amd64.whl", hash = "sha256:28ced650c974aaf179231668a293ecd5c63c0a671ae6d56b8795ecc5d2f48d3c"}, + {file = "debugpy-1.8.5-cp38-cp38-macosx_12_0_x86_64.whl", hash = "sha256:3df6692351172a42af7558daa5019651f898fc67450bf091335aa8a18fbf6f3a"}, + {file = "debugpy-1.8.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1cd04a73eb2769eb0bfe43f5bfde1215c5923d6924b9b90f94d15f207a402226"}, + {file = "debugpy-1.8.5-cp38-cp38-win32.whl", hash = "sha256:8f913ee8e9fcf9d38a751f56e6de12a297ae7832749d35de26d960f14280750a"}, + {file = "debugpy-1.8.5-cp38-cp38-win_amd64.whl", hash = "sha256:a697beca97dad3780b89a7fb525d5e79f33821a8bc0c06faf1f1289e549743cf"}, + {file = "debugpy-1.8.5-cp39-cp39-macosx_12_0_x86_64.whl", hash = "sha256:0a1029a2869d01cb777216af8c53cda0476875ef02a2b6ff8b2f2c9a4b04176c"}, + {file = "debugpy-1.8.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e84c276489e141ed0b93b0af648eef891546143d6a48f610945416453a8ad406"}, + {file = "debugpy-1.8.5-cp39-cp39-win32.whl", hash = "sha256:ad84b7cde7fd96cf6eea34ff6c4a1b7887e0fe2ea46e099e53234856f9d99a34"}, + {file = "debugpy-1.8.5-cp39-cp39-win_amd64.whl", hash = "sha256:7b0fe36ed9d26cb6836b0a51453653f8f2e347ba7348f2bbfe76bfeb670bfb1c"}, + {file = "debugpy-1.8.5-py2.py3-none-any.whl", hash = "sha256:55919dce65b471eff25901acf82d328bbd5b833526b6c1364bd5133754777a44"}, + {file = "debugpy-1.8.5.zip", hash = "sha256:b2112cfeb34b4507399d298fe7023a16656fc553ed5246536060ca7bd0e668d0"}, ] [[package]] @@ -454,13 +494,13 @@ files = [ [[package]] name = "exceptiongroup" -version = "1.2.0" +version = "1.2.2" description = "Backport of PEP 654 (exception groups)" optional = false python-versions = ">=3.7" files = [ - {file = "exceptiongroup-1.2.0-py3-none-any.whl", hash = "sha256:4bfd3996ac73b41e9b9628b04e079f193850720ea5945fc96a08633c66912f14"}, - {file = "exceptiongroup-1.2.0.tar.gz", hash = "sha256:91f5c769735f051a4290d52edd0858999b57e5876e9f85937691bd4c9fa3ed68"}, + {file = "exceptiongroup-1.2.2-py3-none-any.whl", hash = "sha256:3111b9d131c238bec2f8f516e123e14ba243563fb135d3fe885990585aa7795b"}, + {file = "exceptiongroup-1.2.2.tar.gz", hash = "sha256:47c2edf7c6738fafb49fd34290706d1a1a2f4d1c6df275526b62cbb4aa5393cc"}, ] [package.extras] @@ -468,13 +508,13 @@ test = ["pytest (>=6)"] [[package]] name = "executing" -version = "2.0.1" +version = "2.1.0" description = "Get the currently executing AST node of a frame, and other information" optional = false -python-versions = ">=3.5" +python-versions = ">=3.8" files = [ - {file = "executing-2.0.1-py2.py3-none-any.whl", hash = "sha256:eac49ca94516ccc753f9fb5ce82603156e590b27525a8bc32cce8ae302eb61bc"}, - {file = "executing-2.0.1.tar.gz", hash = "sha256:35afe2ce3affba8ee97f2d69927fa823b08b472b7b994e36a52a964b93d16147"}, + {file = "executing-2.1.0-py2.py3-none-any.whl", hash = "sha256:8d63781349375b5ebccc3142f4b30350c0cd9c79f921cde38be2be4637e98eaf"}, + {file = "executing-2.1.0.tar.gz", hash = "sha256:8ea27ddd260da8150fa5a708269c4a10e76161e2496ec3e587da9e3c0fe4b9ab"}, ] [package.extras] @@ -493,69 +533,69 @@ files = [ [[package]] name = "flake8" -version = "7.0.0" +version = "7.1.1" description = "the modular source code checker: pep8 pyflakes and co" optional = false python-versions = ">=3.8.1" files = [ - {file = "flake8-7.0.0-py2.py3-none-any.whl", hash = "sha256:a6dfbb75e03252917f2473ea9653f7cd799c3064e54d4c8140044c5c065f53c3"}, - {file = "flake8-7.0.0.tar.gz", hash = "sha256:33f96621059e65eec474169085dc92bf26e7b2d47366b70be2f67ab80dc25132"}, + {file = "flake8-7.1.1-py2.py3-none-any.whl", hash = "sha256:597477df7860daa5aa0fdd84bf5208a043ab96b8e96ab708770ae0364dd03213"}, + {file = "flake8-7.1.1.tar.gz", hash = "sha256:049d058491e228e03e67b390f311bbf88fce2dbaa8fa673e7aea87b7198b8d38"}, ] [package.dependencies] mccabe = ">=0.7.0,<0.8.0" -pycodestyle = ">=2.11.0,<2.12.0" +pycodestyle = ">=2.12.0,<2.13.0" pyflakes = ">=3.2.0,<3.3.0" [[package]] name = "fonttools" -version = "4.49.0" +version = "4.53.1" description = "Tools to manipulate font files" optional = false python-versions = ">=3.8" files = [ - {file = "fonttools-4.49.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:d970ecca0aac90d399e458f0b7a8a597e08f95de021f17785fb68e2dc0b99717"}, - {file = "fonttools-4.49.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:ac9a745b7609f489faa65e1dc842168c18530874a5f5b742ac3dd79e26bca8bc"}, - {file = "fonttools-4.49.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0ba0e00620ca28d4ca11fc700806fd69144b463aa3275e1b36e56c7c09915559"}, - {file = "fonttools-4.49.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cdee3ab220283057e7840d5fb768ad4c2ebe65bdba6f75d5d7bf47f4e0ed7d29"}, - {file = "fonttools-4.49.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:ce7033cb61f2bb65d8849658d3786188afd80f53dad8366a7232654804529532"}, - {file = "fonttools-4.49.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:07bc5ea02bb7bc3aa40a1eb0481ce20e8d9b9642a9536cde0218290dd6085828"}, - {file = "fonttools-4.49.0-cp310-cp310-win32.whl", hash = "sha256:86eef6aab7fd7c6c8545f3ebd00fd1d6729ca1f63b0cb4d621bccb7d1d1c852b"}, - {file = "fonttools-4.49.0-cp310-cp310-win_amd64.whl", hash = "sha256:1fac1b7eebfce75ea663e860e7c5b4a8831b858c17acd68263bc156125201abf"}, - {file = "fonttools-4.49.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:edc0cce355984bb3c1d1e89d6a661934d39586bb32191ebff98c600f8957c63e"}, - {file = "fonttools-4.49.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:83a0d9336de2cba86d886507dd6e0153df333ac787377325a39a2797ec529814"}, - {file = "fonttools-4.49.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:36c8865bdb5cfeec88f5028e7e592370a0657b676c6f1d84a2108e0564f90e22"}, - {file = "fonttools-4.49.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:33037d9e56e2562c710c8954d0f20d25b8386b397250d65581e544edc9d6b942"}, - {file = "fonttools-4.49.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:8fb022d799b96df3eaa27263e9eea306bd3d437cc9aa981820850281a02b6c9a"}, - {file = "fonttools-4.49.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:33c584c0ef7dc54f5dd4f84082eabd8d09d1871a3d8ca2986b0c0c98165f8e86"}, - {file = "fonttools-4.49.0-cp311-cp311-win32.whl", hash = "sha256:cbe61b158deb09cffdd8540dc4a948d6e8f4d5b4f3bf5cd7db09bd6a61fee64e"}, - {file = "fonttools-4.49.0-cp311-cp311-win_amd64.whl", hash = "sha256:fc11e5114f3f978d0cea7e9853627935b30d451742eeb4239a81a677bdee6bf6"}, - {file = "fonttools-4.49.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:d647a0e697e5daa98c87993726da8281c7233d9d4ffe410812a4896c7c57c075"}, - {file = "fonttools-4.49.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f3bbe672df03563d1f3a691ae531f2e31f84061724c319652039e5a70927167e"}, - {file = "fonttools-4.49.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bebd91041dda0d511b0d303180ed36e31f4f54b106b1259b69fade68413aa7ff"}, - {file = "fonttools-4.49.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4145f91531fd43c50f9eb893faa08399816bb0b13c425667c48475c9f3a2b9b5"}, - {file = "fonttools-4.49.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:ea329dafb9670ffbdf4dbc3b0e5c264104abcd8441d56de77f06967f032943cb"}, - {file = "fonttools-4.49.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:c076a9e548521ecc13d944b1d261ff3d7825048c338722a4bd126d22316087b7"}, - {file = "fonttools-4.49.0-cp312-cp312-win32.whl", hash = "sha256:b607ea1e96768d13be26d2b400d10d3ebd1456343eb5eaddd2f47d1c4bd00880"}, - {file = "fonttools-4.49.0-cp312-cp312-win_amd64.whl", hash = "sha256:a974c49a981e187381b9cc2c07c6b902d0079b88ff01aed34695ec5360767034"}, - {file = "fonttools-4.49.0-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:b85ec0bdd7bdaa5c1946398cbb541e90a6dfc51df76dfa88e0aaa41b335940cb"}, - {file = "fonttools-4.49.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:af20acbe198a8a790618ee42db192eb128afcdcc4e96d99993aca0b60d1faeb4"}, - {file = "fonttools-4.49.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4d418b1fee41a1d14931f7ab4b92dc0bc323b490e41d7a333eec82c9f1780c75"}, - {file = "fonttools-4.49.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b44a52b8e6244b6548851b03b2b377a9702b88ddc21dcaf56a15a0393d425cb9"}, - {file = "fonttools-4.49.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:7c7125068e04a70739dad11857a4d47626f2b0bd54de39e8622e89701836eabd"}, - {file = "fonttools-4.49.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:29e89d0e1a7f18bc30f197cfadcbef5a13d99806447c7e245f5667579a808036"}, - {file = "fonttools-4.49.0-cp38-cp38-win32.whl", hash = "sha256:9d95fa0d22bf4f12d2fb7b07a46070cdfc19ef5a7b1c98bc172bfab5bf0d6844"}, - {file = "fonttools-4.49.0-cp38-cp38-win_amd64.whl", hash = "sha256:768947008b4dc552d02772e5ebd49e71430a466e2373008ce905f953afea755a"}, - {file = "fonttools-4.49.0-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:08877e355d3dde1c11973bb58d4acad1981e6d1140711230a4bfb40b2b937ccc"}, - {file = "fonttools-4.49.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:fdb54b076f25d6b0f0298dc706acee5052de20c83530fa165b60d1f2e9cbe3cb"}, - {file = "fonttools-4.49.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0af65c720520710cc01c293f9c70bd69684365c6015cc3671db2b7d807fe51f2"}, - {file = "fonttools-4.49.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1f255ce8ed7556658f6d23f6afd22a6d9bbc3edb9b96c96682124dc487e1bf42"}, - {file = "fonttools-4.49.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:d00af0884c0e65f60dfaf9340e26658836b935052fdd0439952ae42e44fdd2be"}, - {file = "fonttools-4.49.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:263832fae27481d48dfafcc43174644b6706639661e242902ceb30553557e16c"}, - {file = "fonttools-4.49.0-cp39-cp39-win32.whl", hash = "sha256:0404faea044577a01bb82d47a8fa4bc7a54067fa7e324785dd65d200d6dd1133"}, - {file = "fonttools-4.49.0-cp39-cp39-win_amd64.whl", hash = "sha256:b050d362df50fc6e38ae3954d8c29bf2da52be384649ee8245fdb5186b620836"}, - {file = "fonttools-4.49.0-py3-none-any.whl", hash = "sha256:af281525e5dd7fa0b39fb1667b8d5ca0e2a9079967e14c4bfe90fd1cd13e0f18"}, - {file = "fonttools-4.49.0.tar.gz", hash = "sha256:ebf46e7f01b7af7861310417d7c49591a85d99146fc23a5ba82fdb28af156321"}, + {file = "fonttools-4.53.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:0679a30b59d74b6242909945429dbddb08496935b82f91ea9bf6ad240ec23397"}, + {file = "fonttools-4.53.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:e8bf06b94694251861ba7fdeea15c8ec0967f84c3d4143ae9daf42bbc7717fe3"}, + {file = "fonttools-4.53.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b96cd370a61f4d083c9c0053bf634279b094308d52fdc2dd9a22d8372fdd590d"}, + {file = "fonttools-4.53.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a1c7c5aa18dd3b17995898b4a9b5929d69ef6ae2af5b96d585ff4005033d82f0"}, + {file = "fonttools-4.53.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:e013aae589c1c12505da64a7d8d023e584987e51e62006e1bb30d72f26522c41"}, + {file = "fonttools-4.53.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:9efd176f874cb6402e607e4cc9b4a9cd584d82fc34a4b0c811970b32ba62501f"}, + {file = "fonttools-4.53.1-cp310-cp310-win32.whl", hash = "sha256:c8696544c964500aa9439efb6761947393b70b17ef4e82d73277413f291260a4"}, + {file = "fonttools-4.53.1-cp310-cp310-win_amd64.whl", hash = "sha256:8959a59de5af6d2bec27489e98ef25a397cfa1774b375d5787509c06659b3671"}, + {file = "fonttools-4.53.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:da33440b1413bad53a8674393c5d29ce64d8c1a15ef8a77c642ffd900d07bfe1"}, + {file = "fonttools-4.53.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5ff7e5e9bad94e3a70c5cd2fa27f20b9bb9385e10cddab567b85ce5d306ea923"}, + {file = "fonttools-4.53.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c6e7170d675d12eac12ad1a981d90f118c06cf680b42a2d74c6c931e54b50719"}, + {file = "fonttools-4.53.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bee32ea8765e859670c4447b0817514ca79054463b6b79784b08a8df3a4d78e3"}, + {file = "fonttools-4.53.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6e08f572625a1ee682115223eabebc4c6a2035a6917eac6f60350aba297ccadb"}, + {file = "fonttools-4.53.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b21952c092ffd827504de7e66b62aba26fdb5f9d1e435c52477e6486e9d128b2"}, + {file = "fonttools-4.53.1-cp311-cp311-win32.whl", hash = "sha256:9dfdae43b7996af46ff9da520998a32b105c7f098aeea06b2226b30e74fbba88"}, + {file = "fonttools-4.53.1-cp311-cp311-win_amd64.whl", hash = "sha256:d4d0096cb1ac7a77b3b41cd78c9b6bc4a400550e21dc7a92f2b5ab53ed74eb02"}, + {file = "fonttools-4.53.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:d92d3c2a1b39631a6131c2fa25b5406855f97969b068e7e08413325bc0afba58"}, + {file = "fonttools-4.53.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:3b3c8ebafbee8d9002bd8f1195d09ed2bd9ff134ddec37ee8f6a6375e6a4f0e8"}, + {file = "fonttools-4.53.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:32f029c095ad66c425b0ee85553d0dc326d45d7059dbc227330fc29b43e8ba60"}, + {file = "fonttools-4.53.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:10f5e6c3510b79ea27bb1ebfcc67048cde9ec67afa87c7dd7efa5c700491ac7f"}, + {file = "fonttools-4.53.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:f677ce218976496a587ab17140da141557beb91d2a5c1a14212c994093f2eae2"}, + {file = "fonttools-4.53.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:9e6ceba2a01b448e36754983d376064730690401da1dd104ddb543519470a15f"}, + {file = "fonttools-4.53.1-cp312-cp312-win32.whl", hash = "sha256:791b31ebbc05197d7aa096bbc7bd76d591f05905d2fd908bf103af4488e60670"}, + {file = "fonttools-4.53.1-cp312-cp312-win_amd64.whl", hash = "sha256:6ed170b5e17da0264b9f6fae86073be3db15fa1bd74061c8331022bca6d09bab"}, + {file = "fonttools-4.53.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:c818c058404eb2bba05e728d38049438afd649e3c409796723dfc17cd3f08749"}, + {file = "fonttools-4.53.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:651390c3b26b0c7d1f4407cad281ee7a5a85a31a110cbac5269de72a51551ba2"}, + {file = "fonttools-4.53.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e54f1bba2f655924c1138bbc7fa91abd61f45c68bd65ab5ed985942712864bbb"}, + {file = "fonttools-4.53.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c9cd19cf4fe0595ebdd1d4915882b9440c3a6d30b008f3cc7587c1da7b95be5f"}, + {file = "fonttools-4.53.1-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:2af40ae9cdcb204fc1d8f26b190aa16534fcd4f0df756268df674a270eab575d"}, + {file = "fonttools-4.53.1-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:35250099b0cfb32d799fb5d6c651220a642fe2e3c7d2560490e6f1d3f9ae9169"}, + {file = "fonttools-4.53.1-cp38-cp38-win32.whl", hash = "sha256:f08df60fbd8d289152079a65da4e66a447efc1d5d5a4d3f299cdd39e3b2e4a7d"}, + {file = "fonttools-4.53.1-cp38-cp38-win_amd64.whl", hash = "sha256:7b6b35e52ddc8fb0db562133894e6ef5b4e54e1283dff606fda3eed938c36fc8"}, + {file = "fonttools-4.53.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:75a157d8d26c06e64ace9df037ee93a4938a4606a38cb7ffaf6635e60e253b7a"}, + {file = "fonttools-4.53.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:4824c198f714ab5559c5be10fd1adf876712aa7989882a4ec887bf1ef3e00e31"}, + {file = "fonttools-4.53.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:becc5d7cb89c7b7afa8321b6bb3dbee0eec2b57855c90b3e9bf5fb816671fa7c"}, + {file = "fonttools-4.53.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:84ec3fb43befb54be490147b4a922b5314e16372a643004f182babee9f9c3407"}, + {file = "fonttools-4.53.1-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:73379d3ffdeecb376640cd8ed03e9d2d0e568c9d1a4e9b16504a834ebadc2dfb"}, + {file = "fonttools-4.53.1-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:02569e9a810f9d11f4ae82c391ebc6fb5730d95a0657d24d754ed7763fb2d122"}, + {file = "fonttools-4.53.1-cp39-cp39-win32.whl", hash = "sha256:aae7bd54187e8bf7fd69f8ab87b2885253d3575163ad4d669a262fe97f0136cb"}, + {file = "fonttools-4.53.1-cp39-cp39-win_amd64.whl", hash = "sha256:e5b708073ea3d684235648786f5f6153a48dc8762cdfe5563c57e80787c29fbb"}, + {file = "fonttools-4.53.1-py3-none-any.whl", hash = "sha256:f1f8758a2ad110bd6432203a344269f445a2907dc24ef6bccfd0ac4e14e0d71d"}, + {file = "fonttools-4.53.1.tar.gz", hash = "sha256:e128778a8e9bc11159ce5447f76766cefbd876f44bd79aff030287254e4752c4"}, ] [package.extras] @@ -605,51 +645,62 @@ toy-text = ["pygame (>=2.1.3)", "pygame (>=2.1.3)"] [[package]] name = "idna" -version = "3.6" +version = "3.10" description = "Internationalized Domain Names in Applications (IDNA)" optional = false -python-versions = ">=3.5" +python-versions = ">=3.6" files = [ - {file = "idna-3.6-py3-none-any.whl", hash = "sha256:c05567e9c24a6b9faaa835c4821bad0590fbb9d5779e7caa6e1cc4978e7eb24f"}, - {file = "idna-3.6.tar.gz", hash = "sha256:9ecdbbd083b06798ae1e86adcbfe8ab1479cf864e4ee30fe4e46a003d12491ca"}, + {file = "idna-3.10-py3-none-any.whl", hash = "sha256:946d195a0d259cbba61165e88e65941f16e9b36ea6ddb97f00452bae8b1287d3"}, + {file = "idna-3.10.tar.gz", hash = "sha256:12f65c9b470abda6dc35cf8e63cc574b1c52b11df2c86030af0ac09b01b13ea9"}, ] +[package.extras] +all = ["flake8 (>=7.1.1)", "mypy (>=1.11.2)", "pytest (>=8.3.2)", "ruff (>=0.6.2)"] + [[package]] name = "importlib-metadata" -version = "7.0.1" +version = "8.5.0" description = "Read metadata from Python packages" optional = false python-versions = ">=3.8" files = [ - {file = "importlib_metadata-7.0.1-py3-none-any.whl", hash = "sha256:4805911c3a4ec7c3966410053e9ec6a1fecd629117df5adee56dfc9432a1081e"}, - {file = "importlib_metadata-7.0.1.tar.gz", hash = "sha256:f238736bb06590ae52ac1fab06a3a9ef1d8dce2b7a35b5ab329371d6c8f5d2cc"}, + {file = "importlib_metadata-8.5.0-py3-none-any.whl", hash = "sha256:45e54197d28b7a7f1559e60b95e7c567032b602131fbd588f1497f47880aa68b"}, + {file = "importlib_metadata-8.5.0.tar.gz", hash = "sha256:71522656f0abace1d072b9e5481a48f07c138e00f079c38c8f883823f9c26bd7"}, ] [package.dependencies] -zipp = ">=0.5" +zipp = ">=3.20" [package.extras] -docs = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (<7.2.5)", "sphinx (>=3.5)", "sphinx-lint"] +check = ["pytest-checkdocs (>=2.4)", "pytest-ruff (>=0.2.1)"] +cover = ["pytest-cov"] +doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] +enabler = ["pytest-enabler (>=2.2)"] perf = ["ipython"] -testing = ["flufl.flake8", "importlib-resources (>=1.3)", "packaging", "pyfakefs", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-mypy (>=0.9.1)", "pytest-perf (>=0.9.2)", "pytest-ruff"] +test = ["flufl.flake8", "importlib-resources (>=1.3)", "jaraco.test (>=5.4)", "packaging", "pyfakefs", "pytest (>=6,!=8.1.*)", "pytest-perf (>=0.9.2)"] +type = ["pytest-mypy"] [[package]] name = "importlib-resources" -version = "6.1.2" +version = "6.4.5" description = "Read resources from Python packages" optional = false python-versions = ">=3.8" files = [ - {file = "importlib_resources-6.1.2-py3-none-any.whl", hash = "sha256:9a0a862501dc38b68adebc82970140c9e4209fc99601782925178f8386339938"}, - {file = "importlib_resources-6.1.2.tar.gz", hash = "sha256:308abf8474e2dba5f867d279237cd4076482c3de7104a40b41426370e891549b"}, + {file = "importlib_resources-6.4.5-py3-none-any.whl", hash = "sha256:ac29d5f956f01d5e4bb63102a5a19957f1b9175e45649977264a1416783bb717"}, + {file = "importlib_resources-6.4.5.tar.gz", hash = "sha256:980862a1d16c9e147a59603677fa2aa5fd82b87f223b6cb870695bcfce830065"}, ] [package.dependencies] zipp = {version = ">=3.1.0", markers = "python_version < \"3.10\""} [package.extras] -docs = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (<7.2.5)", "sphinx (>=3.5)", "sphinx-lint"] -testing = ["pytest (>=6)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-mypy", "pytest-ruff (>=0.2.1)", "zipp (>=3.17)"] +check = ["pytest-checkdocs (>=2.4)", "pytest-ruff (>=0.2.1)"] +cover = ["pytest-cov"] +doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] +enabler = ["pytest-enabler (>=2.2)"] +test = ["jaraco.test (>=5.4)", "pytest (>=6,!=8.1.*)", "zipp (>=3.17)"] +type = ["pytest-mypy"] [[package]] name = "iniconfig" @@ -664,13 +715,13 @@ files = [ [[package]] name = "ipykernel" -version = "6.29.3" +version = "6.29.5" description = "IPython Kernel for Jupyter" optional = false python-versions = ">=3.8" files = [ - {file = "ipykernel-6.29.3-py3-none-any.whl", hash = "sha256:5aa086a4175b0229d4eca211e181fb473ea78ffd9869af36ba7694c947302a21"}, - {file = "ipykernel-6.29.3.tar.gz", hash = "sha256:e14c250d1f9ea3989490225cc1a542781b095a18a19447fcf2b5eaf7d0ac5bd2"}, + {file = "ipykernel-6.29.5-py3-none-any.whl", hash = "sha256:afdb66ba5aa354b09b91379bac28ae4afebbb30e8b39510c9690afb7a10421b5"}, + {file = "ipykernel-6.29.5.tar.gz", hash = "sha256:f093a22c4a40f8828f8e330a9c297cb93dcab13bd9678ded6de8e5cf81c56215"}, ] [package.dependencies] @@ -767,13 +818,13 @@ testing = ["Django", "attrs", "colorama", "docopt", "pytest (<7.0.0)"] [[package]] name = "jupyter-client" -version = "8.6.0" +version = "8.6.3" description = "Jupyter protocol implementation and client libraries" optional = false python-versions = ">=3.8" files = [ - {file = "jupyter_client-8.6.0-py3-none-any.whl", hash = "sha256:909c474dbe62582ae62b758bca86d6518c85234bdee2d908c778db6d72f39d99"}, - {file = "jupyter_client-8.6.0.tar.gz", hash = "sha256:0642244bb83b4764ae60d07e010e15f0e2d275ec4e918a8f7b80fbbef3ca60c7"}, + {file = "jupyter_client-8.6.3-py3-none-any.whl", hash = "sha256:e8a19cc986cc45905ac3362915f410f3af85424b4c0905e94fa5f2cb08e8f23f"}, + {file = "jupyter_client-8.6.3.tar.gz", hash = "sha256:35b3a0947c4a6e9d589eb97d7d4cd5e90f910ee73101611f01283732bd6d9419"}, ] [package.dependencies] @@ -786,17 +837,17 @@ traitlets = ">=5.3" [package.extras] docs = ["ipykernel", "myst-parser", "pydata-sphinx-theme", "sphinx (>=4)", "sphinx-autodoc-typehints", "sphinxcontrib-github-alt", "sphinxcontrib-spelling"] -test = ["coverage", "ipykernel (>=6.14)", "mypy", "paramiko", "pre-commit", "pytest", "pytest-cov", "pytest-jupyter[client] (>=0.4.1)", "pytest-timeout"] +test = ["coverage", "ipykernel (>=6.14)", "mypy", "paramiko", "pre-commit", "pytest (<8.2.0)", "pytest-cov", "pytest-jupyter[client] (>=0.4.1)", "pytest-timeout"] [[package]] name = "jupyter-core" -version = "5.7.1" +version = "5.7.2" description = "Jupyter core package. A base package on which Jupyter projects rely." optional = false python-versions = ">=3.8" files = [ - {file = "jupyter_core-5.7.1-py3-none-any.whl", hash = "sha256:c65c82126453a723a2804aa52409930434598fd9d35091d63dfb919d2b765bb7"}, - {file = "jupyter_core-5.7.1.tar.gz", hash = "sha256:de61a9d7fc71240f688b2fb5ab659fbb56979458dc66a71decd098e03c79e218"}, + {file = "jupyter_core-5.7.2-py3-none-any.whl", hash = "sha256:4f7315d2f6b4bcf2e3e7cb6e46772eba760ae459cd1f59d29eb57b0a01bd7409"}, + {file = "jupyter_core-5.7.2.tar.gz", hash = "sha256:aa5f8d32bbf6b431ac830496da7392035d6f61b4f54872f15c4bd2a9c3f536d9"}, ] [package.dependencies] @@ -806,160 +857,170 @@ traitlets = ">=5.3" [package.extras] docs = ["myst-parser", "pydata-sphinx-theme", "sphinx-autodoc-typehints", "sphinxcontrib-github-alt", "sphinxcontrib-spelling", "traitlets"] -test = ["ipykernel", "pre-commit", "pytest", "pytest-cov", "pytest-timeout"] +test = ["ipykernel", "pre-commit", "pytest (<8)", "pytest-cov", "pytest-timeout"] [[package]] name = "kiwisolver" -version = "1.4.5" +version = "1.4.7" description = "A fast implementation of the Cassowary constraint solver" optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "kiwisolver-1.4.5-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:05703cf211d585109fcd72207a31bb170a0f22144d68298dc5e61b3c946518af"}, - {file = "kiwisolver-1.4.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:146d14bebb7f1dc4d5fbf74f8a6cb15ac42baadee8912eb84ac0b3b2a3dc6ac3"}, - {file = "kiwisolver-1.4.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:6ef7afcd2d281494c0a9101d5c571970708ad911d028137cd558f02b851c08b4"}, - {file = "kiwisolver-1.4.5-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:9eaa8b117dc8337728e834b9c6e2611f10c79e38f65157c4c38e9400286f5cb1"}, - {file = "kiwisolver-1.4.5-cp310-cp310-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:ec20916e7b4cbfb1f12380e46486ec4bcbaa91a9c448b97023fde0d5bbf9e4ff"}, - {file = "kiwisolver-1.4.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:39b42c68602539407884cf70d6a480a469b93b81b7701378ba5e2328660c847a"}, - {file = "kiwisolver-1.4.5-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:aa12042de0171fad672b6c59df69106d20d5596e4f87b5e8f76df757a7c399aa"}, - {file = "kiwisolver-1.4.5-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2a40773c71d7ccdd3798f6489aaac9eee213d566850a9533f8d26332d626b82c"}, - {file = "kiwisolver-1.4.5-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:19df6e621f6d8b4b9c4d45f40a66839294ff2bb235e64d2178f7522d9170ac5b"}, - {file = "kiwisolver-1.4.5-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:83d78376d0d4fd884e2c114d0621624b73d2aba4e2788182d286309ebdeed770"}, - {file = "kiwisolver-1.4.5-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:e391b1f0a8a5a10ab3b9bb6afcfd74f2175f24f8975fb87ecae700d1503cdee0"}, - {file = "kiwisolver-1.4.5-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:852542f9481f4a62dbb5dd99e8ab7aedfeb8fb6342349a181d4036877410f525"}, - {file = "kiwisolver-1.4.5-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:59edc41b24031bc25108e210c0def6f6c2191210492a972d585a06ff246bb79b"}, - {file = "kiwisolver-1.4.5-cp310-cp310-win32.whl", hash = "sha256:a6aa6315319a052b4ee378aa171959c898a6183f15c1e541821c5c59beaa0238"}, - {file = "kiwisolver-1.4.5-cp310-cp310-win_amd64.whl", hash = "sha256:d0ef46024e6a3d79c01ff13801cb19d0cad7fd859b15037aec74315540acc276"}, - {file = "kiwisolver-1.4.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:11863aa14a51fd6ec28688d76f1735f8f69ab1fabf388851a595d0721af042f5"}, - {file = "kiwisolver-1.4.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:8ab3919a9997ab7ef2fbbed0cc99bb28d3c13e6d4b1ad36e97e482558a91be90"}, - {file = "kiwisolver-1.4.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:fcc700eadbbccbf6bc1bcb9dbe0786b4b1cb91ca0dcda336eef5c2beed37b797"}, - {file = "kiwisolver-1.4.5-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dfdd7c0b105af050eb3d64997809dc21da247cf44e63dc73ff0fd20b96be55a9"}, - {file = "kiwisolver-1.4.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76c6a5964640638cdeaa0c359382e5703e9293030fe730018ca06bc2010c4437"}, - {file = "kiwisolver-1.4.5-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:bbea0db94288e29afcc4c28afbf3a7ccaf2d7e027489c449cf7e8f83c6346eb9"}, - {file = "kiwisolver-1.4.5-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ceec1a6bc6cab1d6ff5d06592a91a692f90ec7505d6463a88a52cc0eb58545da"}, - {file = "kiwisolver-1.4.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:040c1aebeda72197ef477a906782b5ab0d387642e93bda547336b8957c61022e"}, - {file = "kiwisolver-1.4.5-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:f91de7223d4c7b793867797bacd1ee53bfe7359bd70d27b7b58a04efbb9436c8"}, - {file = "kiwisolver-1.4.5-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:faae4860798c31530dd184046a900e652c95513796ef51a12bc086710c2eec4d"}, - {file = "kiwisolver-1.4.5-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:b0157420efcb803e71d1b28e2c287518b8808b7cf1ab8af36718fd0a2c453eb0"}, - {file = "kiwisolver-1.4.5-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:06f54715b7737c2fecdbf140d1afb11a33d59508a47bf11bb38ecf21dc9ab79f"}, - {file = "kiwisolver-1.4.5-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:fdb7adb641a0d13bdcd4ef48e062363d8a9ad4a182ac7647ec88f695e719ae9f"}, - {file = "kiwisolver-1.4.5-cp311-cp311-win32.whl", hash = "sha256:bb86433b1cfe686da83ce32a9d3a8dd308e85c76b60896d58f082136f10bffac"}, - {file = "kiwisolver-1.4.5-cp311-cp311-win_amd64.whl", hash = "sha256:6c08e1312a9cf1074d17b17728d3dfce2a5125b2d791527f33ffbe805200a355"}, - {file = "kiwisolver-1.4.5-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:32d5cf40c4f7c7b3ca500f8985eb3fb3a7dfc023215e876f207956b5ea26632a"}, - {file = "kiwisolver-1.4.5-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f846c260f483d1fd217fe5ed7c173fb109efa6b1fc8381c8b7552c5781756192"}, - {file = "kiwisolver-1.4.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5ff5cf3571589b6d13bfbfd6bcd7a3f659e42f96b5fd1c4830c4cf21d4f5ef45"}, - {file = "kiwisolver-1.4.5-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7269d9e5f1084a653d575c7ec012ff57f0c042258bf5db0954bf551c158466e7"}, - {file = "kiwisolver-1.4.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da802a19d6e15dffe4b0c24b38b3af68e6c1a68e6e1d8f30148c83864f3881db"}, - {file = "kiwisolver-1.4.5-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3aba7311af82e335dd1e36ffff68aaca609ca6290c2cb6d821a39aa075d8e3ff"}, - {file = "kiwisolver-1.4.5-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:763773d53f07244148ccac5b084da5adb90bfaee39c197554f01b286cf869228"}, - {file = "kiwisolver-1.4.5-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2270953c0d8cdab5d422bee7d2007f043473f9d2999631c86a223c9db56cbd16"}, - {file = "kiwisolver-1.4.5-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:d099e745a512f7e3bbe7249ca835f4d357c586d78d79ae8f1dcd4d8adeb9bda9"}, - {file = "kiwisolver-1.4.5-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:74db36e14a7d1ce0986fa104f7d5637aea5c82ca6326ed0ec5694280942d1162"}, - {file = "kiwisolver-1.4.5-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:7e5bab140c309cb3a6ce373a9e71eb7e4873c70c2dda01df6820474f9889d6d4"}, - {file = "kiwisolver-1.4.5-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:0f114aa76dc1b8f636d077979c0ac22e7cd8f3493abbab152f20eb8d3cda71f3"}, - {file = "kiwisolver-1.4.5-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:88a2df29d4724b9237fc0c6eaf2a1adae0cdc0b3e9f4d8e7dc54b16812d2d81a"}, - {file = "kiwisolver-1.4.5-cp312-cp312-win32.whl", hash = "sha256:72d40b33e834371fd330fb1472ca19d9b8327acb79a5821d4008391db8e29f20"}, - {file = "kiwisolver-1.4.5-cp312-cp312-win_amd64.whl", hash = "sha256:2c5674c4e74d939b9d91dda0fae10597ac7521768fec9e399c70a1f27e2ea2d9"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:3a2b053a0ab7a3960c98725cfb0bf5b48ba82f64ec95fe06f1d06c99b552e130"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3cd32d6c13807e5c66a7cbb79f90b553642f296ae4518a60d8d76243b0ad2898"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:59ec7b7c7e1a61061850d53aaf8e93db63dce0c936db1fda2658b70e4a1be709"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:da4cfb373035def307905d05041c1d06d8936452fe89d464743ae7fb8371078b"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:2400873bccc260b6ae184b2b8a4fec0e4082d30648eadb7c3d9a13405d861e89"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:1b04139c4236a0f3aff534479b58f6f849a8b351e1314826c2d230849ed48985"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:4e66e81a5779b65ac21764c295087de82235597a2293d18d943f8e9e32746265"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:7931d8f1f67c4be9ba1dd9c451fb0eeca1a25b89e4d3f89e828fe12a519b782a"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-musllinux_1_1_ppc64le.whl", hash = "sha256:b3f7e75f3015df442238cca659f8baa5f42ce2a8582727981cbfa15fee0ee205"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-musllinux_1_1_s390x.whl", hash = "sha256:bbf1d63eef84b2e8c89011b7f2235b1e0bf7dacc11cac9431fc6468e99ac77fb"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:4c380469bd3f970ef677bf2bcba2b6b0b4d5c75e7a020fb863ef75084efad66f"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-win32.whl", hash = "sha256:9408acf3270c4b6baad483865191e3e582b638b1654a007c62e3efe96f09a9a3"}, - {file = "kiwisolver-1.4.5-cp37-cp37m-win_amd64.whl", hash = "sha256:5b94529f9b2591b7af5f3e0e730a4e0a41ea174af35a4fd067775f9bdfeee01a"}, - {file = "kiwisolver-1.4.5-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:11c7de8f692fc99816e8ac50d1d1aef4f75126eefc33ac79aac02c099fd3db71"}, - {file = "kiwisolver-1.4.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:53abb58632235cd154176ced1ae8f0d29a6657aa1aa9decf50b899b755bc2b93"}, - {file = "kiwisolver-1.4.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:88b9f257ca61b838b6f8094a62418421f87ac2a1069f7e896c36a7d86b5d4c29"}, - {file = "kiwisolver-1.4.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3195782b26fc03aa9c6913d5bad5aeb864bdc372924c093b0f1cebad603dd712"}, - {file = "kiwisolver-1.4.5-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fc579bf0f502e54926519451b920e875f433aceb4624a3646b3252b5caa9e0b6"}, - {file = "kiwisolver-1.4.5-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5a580c91d686376f0f7c295357595c5a026e6cbc3d77b7c36e290201e7c11ecb"}, - {file = "kiwisolver-1.4.5-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:cfe6ab8da05c01ba6fbea630377b5da2cd9bcbc6338510116b01c1bc939a2c18"}, - {file = "kiwisolver-1.4.5-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:d2e5a98f0ec99beb3c10e13b387f8db39106d53993f498b295f0c914328b1333"}, - {file = "kiwisolver-1.4.5-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:a51a263952b1429e429ff236d2f5a21c5125437861baeed77f5e1cc2d2c7c6da"}, - {file = "kiwisolver-1.4.5-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:3edd2fa14e68c9be82c5b16689e8d63d89fe927e56debd6e1dbce7a26a17f81b"}, - {file = "kiwisolver-1.4.5-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:74d1b44c6cfc897df648cc9fdaa09bc3e7679926e6f96df05775d4fb3946571c"}, - {file = "kiwisolver-1.4.5-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:76d9289ed3f7501012e05abb8358bbb129149dbd173f1f57a1bf1c22d19ab7cc"}, - {file = "kiwisolver-1.4.5-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:92dea1ffe3714fa8eb6a314d2b3c773208d865a0e0d35e713ec54eea08a66250"}, - {file = "kiwisolver-1.4.5-cp38-cp38-win32.whl", hash = "sha256:5c90ae8c8d32e472be041e76f9d2f2dbff4d0b0be8bd4041770eddb18cf49a4e"}, - {file = "kiwisolver-1.4.5-cp38-cp38-win_amd64.whl", hash = "sha256:c7940c1dc63eb37a67721b10d703247552416f719c4188c54e04334321351ced"}, - {file = "kiwisolver-1.4.5-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:9407b6a5f0d675e8a827ad8742e1d6b49d9c1a1da5d952a67d50ef5f4170b18d"}, - {file = "kiwisolver-1.4.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:15568384086b6df3c65353820a4473575dbad192e35010f622c6ce3eebd57af9"}, - {file = "kiwisolver-1.4.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:0dc9db8e79f0036e8173c466d21ef18e1befc02de8bf8aa8dc0813a6dc8a7046"}, - {file = "kiwisolver-1.4.5-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:cdc8a402aaee9a798b50d8b827d7ecf75edc5fb35ea0f91f213ff927c15f4ff0"}, - {file = "kiwisolver-1.4.5-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:6c3bd3cde54cafb87d74d8db50b909705c62b17c2099b8f2e25b461882e544ff"}, - {file = "kiwisolver-1.4.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:955e8513d07a283056b1396e9a57ceddbd272d9252c14f154d450d227606eb54"}, - {file = "kiwisolver-1.4.5-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:346f5343b9e3f00b8db8ba359350eb124b98c99efd0b408728ac6ebf38173958"}, - {file = "kiwisolver-1.4.5-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b9098e0049e88c6a24ff64545cdfc50807818ba6c1b739cae221bbbcbc58aad3"}, - {file = "kiwisolver-1.4.5-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:00bd361b903dc4bbf4eb165f24d1acbee754fce22ded24c3d56eec268658a5cf"}, - {file = "kiwisolver-1.4.5-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:7b8b454bac16428b22560d0a1cf0a09875339cab69df61d7805bf48919415901"}, - {file = "kiwisolver-1.4.5-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:f1d072c2eb0ad60d4c183f3fb44ac6f73fb7a8f16a2694a91f988275cbf352f9"}, - {file = "kiwisolver-1.4.5-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:31a82d498054cac9f6d0b53d02bb85811185bcb477d4b60144f915f3b3126342"}, - {file = "kiwisolver-1.4.5-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:6512cb89e334e4700febbffaaa52761b65b4f5a3cf33f960213d5656cea36a77"}, - {file = "kiwisolver-1.4.5-cp39-cp39-win32.whl", hash = "sha256:9db8ea4c388fdb0f780fe91346fd438657ea602d58348753d9fb265ce1bca67f"}, - {file = "kiwisolver-1.4.5-cp39-cp39-win_amd64.whl", hash = "sha256:59415f46a37f7f2efeec758353dd2eae1b07640d8ca0f0c42548ec4125492635"}, - {file = "kiwisolver-1.4.5-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:5c7b3b3a728dc6faf3fc372ef24f21d1e3cee2ac3e9596691d746e5a536de920"}, - {file = "kiwisolver-1.4.5-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:620ced262a86244e2be10a676b646f29c34537d0d9cc8eb26c08f53d98013390"}, - {file = "kiwisolver-1.4.5-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:378a214a1e3bbf5ac4a8708304318b4f890da88c9e6a07699c4ae7174c09a68d"}, - {file = "kiwisolver-1.4.5-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:aaf7be1207676ac608a50cd08f102f6742dbfc70e8d60c4db1c6897f62f71523"}, - {file = "kiwisolver-1.4.5-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:ba55dce0a9b8ff59495ddd050a0225d58bd0983d09f87cfe2b6aec4f2c1234e4"}, - {file = "kiwisolver-1.4.5-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:fd32ea360bcbb92d28933fc05ed09bffcb1704ba3fc7942e81db0fd4f81a7892"}, - {file = "kiwisolver-1.4.5-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:5e7139af55d1688f8b960ee9ad5adafc4ac17c1c473fe07133ac092310d76544"}, - {file = "kiwisolver-1.4.5-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:dced8146011d2bc2e883f9bd68618b8247387f4bbec46d7392b3c3b032640126"}, - {file = "kiwisolver-1.4.5-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c9bf3325c47b11b2e51bca0824ea217c7cd84491d8ac4eefd1e409705ef092bd"}, - {file = "kiwisolver-1.4.5-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:5794cf59533bc3f1b1c821f7206a3617999db9fbefc345360aafe2e067514929"}, - {file = "kiwisolver-1.4.5-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:e368f200bbc2e4f905b8e71eb38b3c04333bddaa6a2464a6355487b02bb7fb09"}, - {file = "kiwisolver-1.4.5-pp39-pypy39_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e5d706eba36b4c4d5bc6c6377bb6568098765e990cfc21ee16d13963fab7b3e7"}, - {file = "kiwisolver-1.4.5-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:85267bd1aa8880a9c88a8cb71e18d3d64d2751a790e6ca6c27b8ccc724bcd5ad"}, - {file = "kiwisolver-1.4.5-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:210ef2c3a1f03272649aff1ef992df2e724748918c4bc2d5a90352849eb40bea"}, - {file = "kiwisolver-1.4.5-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:11d011a7574eb3b82bcc9c1a1d35c1d7075677fdd15de527d91b46bd35e935ee"}, - {file = "kiwisolver-1.4.5.tar.gz", hash = "sha256:e57e563a57fb22a142da34f38acc2fc1a5c864bc29ca1517a88abc963e60d6ec"}, + {file = "kiwisolver-1.4.7-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:8a9c83f75223d5e48b0bc9cb1bf2776cf01563e00ade8775ffe13b0b6e1af3a6"}, + {file = "kiwisolver-1.4.7-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:58370b1ffbd35407444d57057b57da5d6549d2d854fa30249771775c63b5fe17"}, + {file = "kiwisolver-1.4.7-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:aa0abdf853e09aff551db11fce173e2177d00786c688203f52c87ad7fcd91ef9"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:8d53103597a252fb3ab8b5845af04c7a26d5e7ea8122303dd7a021176a87e8b9"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:88f17c5ffa8e9462fb79f62746428dd57b46eb931698e42e990ad63103f35e6c"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88a9ca9c710d598fd75ee5de59d5bda2684d9db36a9f50b6125eaea3969c2599"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f4d742cb7af1c28303a51b7a27aaee540e71bb8e24f68c736f6f2ffc82f2bf05"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e28c7fea2196bf4c2f8d46a0415c77a1c480cc0724722f23d7410ffe9842c407"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:e968b84db54f9d42046cf154e02911e39c0435c9801681e3fc9ce8a3c4130278"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:0c18ec74c0472de033e1bebb2911c3c310eef5649133dd0bedf2a169a1b269e5"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:8f0ea6da6d393d8b2e187e6a5e3fb81f5862010a40c3945e2c6d12ae45cfb2ad"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:f106407dda69ae456dd1227966bf445b157ccc80ba0dff3802bb63f30b74e895"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:84ec80df401cfee1457063732d90022f93951944b5b58975d34ab56bb150dfb3"}, + {file = "kiwisolver-1.4.7-cp310-cp310-win32.whl", hash = "sha256:71bb308552200fb2c195e35ef05de12f0c878c07fc91c270eb3d6e41698c3bcc"}, + {file = "kiwisolver-1.4.7-cp310-cp310-win_amd64.whl", hash = "sha256:44756f9fd339de0fb6ee4f8c1696cfd19b2422e0d70b4cefc1cc7f1f64045a8c"}, + {file = "kiwisolver-1.4.7-cp310-cp310-win_arm64.whl", hash = "sha256:78a42513018c41c2ffd262eb676442315cbfe3c44eed82385c2ed043bc63210a"}, + {file = "kiwisolver-1.4.7-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d2b0e12a42fb4e72d509fc994713d099cbb15ebf1103545e8a45f14da2dfca54"}, + {file = "kiwisolver-1.4.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2a8781ac3edc42ea4b90bc23e7d37b665d89423818e26eb6df90698aa2287c95"}, + {file = "kiwisolver-1.4.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:46707a10836894b559e04b0fd143e343945c97fd170d69a2d26d640b4e297935"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ef97b8df011141c9b0f6caf23b29379f87dd13183c978a30a3c546d2c47314cb"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3ab58c12a2cd0fc769089e6d38466c46d7f76aced0a1f54c77652446733d2d02"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:803b8e1459341c1bb56d1c5c010406d5edec8a0713a0945851290a7930679b51"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f9a9e8a507420fe35992ee9ecb302dab68550dedc0da9e2880dd88071c5fb052"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:18077b53dc3bb490e330669a99920c5e6a496889ae8c63b58fbc57c3d7f33a18"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6af936f79086a89b3680a280c47ea90b4df7047b5bdf3aa5c524bbedddb9e545"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:3abc5b19d24af4b77d1598a585b8a719beb8569a71568b66f4ebe1fb0449460b"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:933d4de052939d90afbe6e9d5273ae05fb836cc86c15b686edd4b3560cc0ee36"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:65e720d2ab2b53f1f72fb5da5fb477455905ce2c88aaa671ff0a447c2c80e8e3"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3bf1ed55088f214ba6427484c59553123fdd9b218a42bbc8c6496d6754b1e523"}, + {file = "kiwisolver-1.4.7-cp311-cp311-win32.whl", hash = "sha256:4c00336b9dd5ad96d0a558fd18a8b6f711b7449acce4c157e7343ba92dd0cf3d"}, + {file = "kiwisolver-1.4.7-cp311-cp311-win_amd64.whl", hash = "sha256:929e294c1ac1e9f615c62a4e4313ca1823ba37326c164ec720a803287c4c499b"}, + {file = "kiwisolver-1.4.7-cp311-cp311-win_arm64.whl", hash = "sha256:e33e8fbd440c917106b237ef1a2f1449dfbb9b6f6e1ce17c94cd6a1e0d438376"}, + {file = "kiwisolver-1.4.7-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:5360cc32706dab3931f738d3079652d20982511f7c0ac5711483e6eab08efff2"}, + {file = "kiwisolver-1.4.7-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:942216596dc64ddb25adb215c3c783215b23626f8d84e8eff8d6d45c3f29f75a"}, + {file = "kiwisolver-1.4.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:48b571ecd8bae15702e4f22d3ff6a0f13e54d3d00cd25216d5e7f658242065ee"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ad42ba922c67c5f219097b28fae965e10045ddf145d2928bfac2eb2e17673640"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:612a10bdae23404a72941a0fc8fa2660c6ea1217c4ce0dbcab8a8f6543ea9e7f"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9e838bba3a3bac0fe06d849d29772eb1afb9745a59710762e4ba3f4cb8424483"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:22f499f6157236c19f4bbbd472fa55b063db77a16cd74d49afe28992dff8c258"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:693902d433cf585133699972b6d7c42a8b9f8f826ebcaf0132ff55200afc599e"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:4e77f2126c3e0b0d055f44513ed349038ac180371ed9b52fe96a32aa071a5107"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:657a05857bda581c3656bfc3b20e353c232e9193eb167766ad2dc58b56504948"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:4bfa75a048c056a411f9705856abfc872558e33c055d80af6a380e3658766038"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:34ea1de54beef1c104422d210c47c7d2a4999bdecf42c7b5718fbe59a4cac383"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:90da3b5f694b85231cf93586dad5e90e2d71b9428f9aad96952c99055582f520"}, + {file = "kiwisolver-1.4.7-cp312-cp312-win32.whl", hash = "sha256:18e0cca3e008e17fe9b164b55735a325140a5a35faad8de92dd80265cd5eb80b"}, + {file = "kiwisolver-1.4.7-cp312-cp312-win_amd64.whl", hash = "sha256:58cb20602b18f86f83a5c87d3ee1c766a79c0d452f8def86d925e6c60fbf7bfb"}, + {file = "kiwisolver-1.4.7-cp312-cp312-win_arm64.whl", hash = "sha256:f5a8b53bdc0b3961f8b6125e198617c40aeed638b387913bf1ce78afb1b0be2a"}, + {file = "kiwisolver-1.4.7-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2e6039dcbe79a8e0f044f1c39db1986a1b8071051efba3ee4d74f5b365f5226e"}, + {file = "kiwisolver-1.4.7-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:a1ecf0ac1c518487d9d23b1cd7139a6a65bc460cd101ab01f1be82ecf09794b6"}, + {file = "kiwisolver-1.4.7-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:7ab9ccab2b5bd5702ab0803676a580fffa2aa178c2badc5557a84cc943fcf750"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f816dd2277f8d63d79f9c8473a79fe54047bc0467754962840782c575522224d"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf8bcc23ceb5a1b624572a1623b9f79d2c3b337c8c455405ef231933a10da379"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:dea0bf229319828467d7fca8c7c189780aa9ff679c94539eed7532ebe33ed37c"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c06a4c7cf15ec739ce0e5971b26c93638730090add60e183530d70848ebdd34"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:913983ad2deb14e66d83c28b632fd35ba2b825031f2fa4ca29675e665dfecbe1"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:5337ec7809bcd0f424c6b705ecf97941c46279cf5ed92311782c7c9c2026f07f"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:4c26ed10c4f6fa6ddb329a5120ba3b6db349ca192ae211e882970bfc9d91420b"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:c619b101e6de2222c1fcb0531e1b17bbffbe54294bfba43ea0d411d428618c27"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:073a36c8273647592ea332e816e75ef8da5c303236ec0167196793eb1e34657a"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:3ce6b2b0231bda412463e152fc18335ba32faf4e8c23a754ad50ffa70e4091ee"}, + {file = "kiwisolver-1.4.7-cp313-cp313-win32.whl", hash = "sha256:f4c9aee212bc89d4e13f58be11a56cc8036cabad119259d12ace14b34476fd07"}, + {file = "kiwisolver-1.4.7-cp313-cp313-win_amd64.whl", hash = "sha256:8a3ec5aa8e38fc4c8af308917ce12c536f1c88452ce554027e55b22cbbfbff76"}, + {file = "kiwisolver-1.4.7-cp313-cp313-win_arm64.whl", hash = "sha256:76c8094ac20ec259471ac53e774623eb62e6e1f56cd8690c67ce6ce4fcb05650"}, + {file = "kiwisolver-1.4.7-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:5d5abf8f8ec1f4e22882273c423e16cae834c36856cac348cfbfa68e01c40f3a"}, + {file = "kiwisolver-1.4.7-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:aeb3531b196ef6f11776c21674dba836aeea9d5bd1cf630f869e3d90b16cfade"}, + {file = "kiwisolver-1.4.7-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:b7d755065e4e866a8086c9bdada157133ff466476a2ad7861828e17b6026e22c"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:08471d4d86cbaec61f86b217dd938a83d85e03785f51121e791a6e6689a3be95"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7bbfcb7165ce3d54a3dfbe731e470f65739c4c1f85bb1018ee912bae139e263b"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5d34eb8494bea691a1a450141ebb5385e4b69d38bb8403b5146ad279f4b30fa3"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:9242795d174daa40105c1d86aba618e8eab7bf96ba8c3ee614da8302a9f95503"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:a0f64a48bb81af7450e641e3fe0b0394d7381e342805479178b3d335d60ca7cf"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:8e045731a5416357638d1700927529e2b8ab304811671f665b225f8bf8d8f933"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:4322872d5772cae7369f8351da1edf255a604ea7087fe295411397d0cfd9655e"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:e1631290ee9271dffe3062d2634c3ecac02c83890ada077d225e081aca8aab89"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:edcfc407e4eb17e037bca59be0e85a2031a2ac87e4fed26d3e9df88b4165f92d"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:4d05d81ecb47d11e7f8932bd8b61b720bf0b41199358f3f5e36d38e28f0532c5"}, + {file = "kiwisolver-1.4.7-cp38-cp38-win32.whl", hash = "sha256:b38ac83d5f04b15e515fd86f312479d950d05ce2368d5413d46c088dda7de90a"}, + {file = "kiwisolver-1.4.7-cp38-cp38-win_amd64.whl", hash = "sha256:d83db7cde68459fc803052a55ace60bea2bae361fc3b7a6d5da07e11954e4b09"}, + {file = "kiwisolver-1.4.7-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:3f9362ecfca44c863569d3d3c033dbe8ba452ff8eed6f6b5806382741a1334bd"}, + {file = "kiwisolver-1.4.7-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:e8df2eb9b2bac43ef8b082e06f750350fbbaf2887534a5be97f6cf07b19d9583"}, + {file = "kiwisolver-1.4.7-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:f32d6edbc638cde7652bd690c3e728b25332acbadd7cad670cc4a02558d9c417"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:e2e6c39bd7b9372b0be21456caab138e8e69cc0fc1190a9dfa92bd45a1e6e904"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:dda56c24d869b1193fcc763f1284b9126550eaf84b88bbc7256e15028f19188a"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:79849239c39b5e1fd906556c474d9b0439ea6792b637511f3fe3a41158d89ca8"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5e3bc157fed2a4c02ec468de4ecd12a6e22818d4f09cde2c31ee3226ffbefab2"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3da53da805b71e41053dc670f9a820d1157aae77b6b944e08024d17bcd51ef88"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:8705f17dfeb43139a692298cb6637ee2e59c0194538153e83e9ee0c75c2eddde"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:82a5c2f4b87c26bb1a0ef3d16b5c4753434633b83d365cc0ddf2770c93829e3c"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:ce8be0466f4c0d585cdb6c1e2ed07232221df101a4c6f28821d2aa754ca2d9e2"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:409afdfe1e2e90e6ee7fc896f3df9a7fec8e793e58bfa0d052c8a82f99c37abb"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:5b9c3f4ee0b9a439d2415012bd1b1cc2df59e4d6a9939f4d669241d30b414327"}, + {file = "kiwisolver-1.4.7-cp39-cp39-win32.whl", hash = "sha256:a79ae34384df2b615eefca647a2873842ac3b596418032bef9a7283675962644"}, + {file = "kiwisolver-1.4.7-cp39-cp39-win_amd64.whl", hash = "sha256:cf0438b42121a66a3a667de17e779330fc0f20b0d97d59d2f2121e182b0505e4"}, + {file = "kiwisolver-1.4.7-cp39-cp39-win_arm64.whl", hash = "sha256:764202cc7e70f767dab49e8df52c7455e8de0df5d858fa801a11aa0d882ccf3f"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:94252291e3fe68001b1dd747b4c0b3be12582839b95ad4d1b641924d68fd4643"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:5b7dfa3b546da08a9f622bb6becdb14b3e24aaa30adba66749d38f3cc7ea9706"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bd3de6481f4ed8b734da5df134cd5a6a64fe32124fe83dde1e5b5f29fe30b1e6"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a91b5f9f1205845d488c928e8570dcb62b893372f63b8b6e98b863ebd2368ff2"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40fa14dbd66b8b8f470d5fc79c089a66185619d31645f9b0773b88b19f7223c4"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:eb542fe7933aa09d8d8f9d9097ef37532a7df6497819d16efe4359890a2f417a"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:bfa1acfa0c54932d5607e19a2c24646fb4c1ae2694437789129cf099789a3b00"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-macosx_11_0_arm64.whl", hash = "sha256:eee3ea935c3d227d49b4eb85660ff631556841f6e567f0f7bda972df6c2c9935"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:f3160309af4396e0ed04db259c3ccbfdc3621b5559b5453075e5de555e1f3a1b"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:a17f6a29cf8935e587cc8a4dbfc8368c55edc645283db0ce9801016f83526c2d"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:10849fb2c1ecbfae45a693c070e0320a91b35dd4bcf58172c023b994283a124d"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:ac542bf38a8a4be2dc6b15248d36315ccc65f0743f7b1a76688ffb6b5129a5c2"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:8b01aac285f91ca889c800042c35ad3b239e704b150cfd3382adfc9dcc780e39"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:48be928f59a1f5c8207154f935334d374e79f2b5d212826307d072595ad76a2e"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f37cfe618a117e50d8c240555331160d73d0411422b59b5ee217843d7b693608"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:599b5c873c63a1f6ed7eead644a8a380cfbdf5db91dcb6f85707aaab213b1674"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:801fa7802e5cfabe3ab0c81a34c323a319b097dfb5004be950482d882f3d7225"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:0c6c43471bc764fad4bc99c5c2d6d16a676b1abf844ca7c8702bdae92df01ee0"}, + {file = "kiwisolver-1.4.7.tar.gz", hash = "sha256:9893ff81bd7107f7b685d3017cc6583daadb4fc26e4a888350df530e41980a60"}, ] [[package]] name = "llvmlite" -version = "0.42.0" +version = "0.43.0" description = "lightweight wrapper around basic LLVM functionality" optional = false python-versions = ">=3.9" files = [ - {file = "llvmlite-0.42.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:3366938e1bf63d26c34fbfb4c8e8d2ded57d11e0567d5bb243d89aab1eb56098"}, - {file = "llvmlite-0.42.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c35da49666a21185d21b551fc3caf46a935d54d66969d32d72af109b5e7d2b6f"}, - {file = "llvmlite-0.42.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:70f44ccc3c6220bd23e0ba698a63ec2a7d3205da0d848804807f37fc243e3f77"}, - {file = "llvmlite-0.42.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:763f8d8717a9073b9e0246998de89929071d15b47f254c10eef2310b9aac033d"}, - {file = "llvmlite-0.42.0-cp310-cp310-win_amd64.whl", hash = "sha256:8d90edf400b4ceb3a0e776b6c6e4656d05c7187c439587e06f86afceb66d2be5"}, - {file = "llvmlite-0.42.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ae511caed28beaf1252dbaf5f40e663f533b79ceb408c874c01754cafabb9cbf"}, - {file = "llvmlite-0.42.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:81e674c2fe85576e6c4474e8c7e7aba7901ac0196e864fe7985492b737dbab65"}, - {file = "llvmlite-0.42.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bb3975787f13eb97629052edb5017f6c170eebc1c14a0433e8089e5db43bcce6"}, - {file = "llvmlite-0.42.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c5bece0cdf77f22379f19b1959ccd7aee518afa4afbd3656c6365865f84903f9"}, - {file = "llvmlite-0.42.0-cp311-cp311-win_amd64.whl", hash = "sha256:7e0c4c11c8c2aa9b0701f91b799cb9134a6a6de51444eff5a9087fc7c1384275"}, - {file = "llvmlite-0.42.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:08fa9ab02b0d0179c688a4216b8939138266519aaa0aa94f1195a8542faedb56"}, - {file = "llvmlite-0.42.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b2fce7d355068494d1e42202c7aff25d50c462584233013eb4470c33b995e3ee"}, - {file = "llvmlite-0.42.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ebe66a86dc44634b59a3bc860c7b20d26d9aaffcd30364ebe8ba79161a9121f4"}, - {file = "llvmlite-0.42.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d47494552559e00d81bfb836cf1c4d5a5062e54102cc5767d5aa1e77ccd2505c"}, - {file = "llvmlite-0.42.0-cp312-cp312-win_amd64.whl", hash = "sha256:05cb7e9b6ce69165ce4d1b994fbdedca0c62492e537b0cc86141b6e2c78d5888"}, - {file = "llvmlite-0.42.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:bdd3888544538a94d7ec99e7c62a0cdd8833609c85f0c23fcb6c5c591aec60ad"}, - {file = "llvmlite-0.42.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:d0936c2067a67fb8816c908d5457d63eba3e2b17e515c5fe00e5ee2bace06040"}, - {file = "llvmlite-0.42.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a78ab89f1924fc11482209f6799a7a3fc74ddc80425a7a3e0e8174af0e9e2301"}, - {file = "llvmlite-0.42.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d7599b65c7af7abbc978dbf345712c60fd596aa5670496561cc10e8a71cebfb2"}, - {file = "llvmlite-0.42.0-cp39-cp39-win_amd64.whl", hash = "sha256:43d65cc4e206c2e902c1004dd5418417c4efa6c1d04df05c6c5675a27e8ca90e"}, - {file = "llvmlite-0.42.0.tar.gz", hash = "sha256:f92b09243c0cc3f457da8b983f67bd8e1295d0f5b3746c7a1861d7a99403854a"}, + {file = "llvmlite-0.43.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:a289af9a1687c6cf463478f0fa8e8aa3b6fb813317b0d70bf1ed0759eab6f761"}, + {file = "llvmlite-0.43.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:6d4fd101f571a31acb1559ae1af30f30b1dc4b3186669f92ad780e17c81e91bc"}, + {file = "llvmlite-0.43.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7d434ec7e2ce3cc8f452d1cd9a28591745de022f931d67be688a737320dfcead"}, + {file = "llvmlite-0.43.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6912a87782acdff6eb8bf01675ed01d60ca1f2551f8176a300a886f09e836a6a"}, + {file = "llvmlite-0.43.0-cp310-cp310-win_amd64.whl", hash = "sha256:14f0e4bf2fd2d9a75a3534111e8ebeb08eda2f33e9bdd6dfa13282afacdde0ed"}, + {file = "llvmlite-0.43.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3e8d0618cb9bfe40ac38a9633f2493d4d4e9fcc2f438d39a4e854f39cc0f5f98"}, + {file = "llvmlite-0.43.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:e0a9a1a39d4bf3517f2af9d23d479b4175ead205c592ceeb8b89af48a327ea57"}, + {file = "llvmlite-0.43.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c1da416ab53e4f7f3bc8d4eeba36d801cc1894b9fbfbf2022b29b6bad34a7df2"}, + {file = "llvmlite-0.43.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:977525a1e5f4059316b183fb4fd34fa858c9eade31f165427a3977c95e3ee749"}, + {file = "llvmlite-0.43.0-cp311-cp311-win_amd64.whl", hash = "sha256:d5bd550001d26450bd90777736c69d68c487d17bf371438f975229b2b8241a91"}, + {file = "llvmlite-0.43.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f99b600aa7f65235a5a05d0b9a9f31150c390f31261f2a0ba678e26823ec38f7"}, + {file = "llvmlite-0.43.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:35d80d61d0cda2d767f72de99450766250560399edc309da16937b93d3b676e7"}, + {file = "llvmlite-0.43.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:eccce86bba940bae0d8d48ed925f21dbb813519169246e2ab292b5092aba121f"}, + {file = "llvmlite-0.43.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:df6509e1507ca0760787a199d19439cc887bfd82226f5af746d6977bd9f66844"}, + {file = "llvmlite-0.43.0-cp312-cp312-win_amd64.whl", hash = "sha256:7a2872ee80dcf6b5dbdc838763d26554c2a18aa833d31a2635bff16aafefb9c9"}, + {file = "llvmlite-0.43.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:9cd2a7376f7b3367019b664c21f0c61766219faa3b03731113ead75107f3b66c"}, + {file = "llvmlite-0.43.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:18e9953c748b105668487b7c81a3e97b046d8abf95c4ddc0cd3c94f4e4651ae8"}, + {file = "llvmlite-0.43.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:74937acd22dc11b33946b67dca7680e6d103d6e90eeaaaf932603bec6fe7b03a"}, + {file = "llvmlite-0.43.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bc9efc739cc6ed760f795806f67889923f7274276f0eb45092a1473e40d9b867"}, + {file = "llvmlite-0.43.0-cp39-cp39-win_amd64.whl", hash = "sha256:47e147cdda9037f94b399bf03bfd8a6b6b1f2f90be94a454e3386f006455a9b4"}, + {file = "llvmlite-0.43.0.tar.gz", hash = "sha256:ae2b5b5c3ef67354824fb75517c8db5fbe93bc02cd9671f3c62271626bc041d5"}, ] [[package]] name = "marshmallow" -version = "3.21.0" +version = "3.22.0" description = "A lightweight library for converting complex datatypes to and from native Python datatypes." optional = false python-versions = ">=3.8" files = [ - {file = "marshmallow-3.21.0-py3-none-any.whl", hash = "sha256:e7997f83571c7fd476042c2c188e4ee8a78900ca5e74bd9c8097afa56624e9bd"}, - {file = "marshmallow-3.21.0.tar.gz", hash = "sha256:20f53be28c6e374a711a16165fb22a8dc6003e3f7cda1285e3ca777b9193885b"}, + {file = "marshmallow-3.22.0-py3-none-any.whl", hash = "sha256:71a2dce49ef901c3f97ed296ae5051135fd3febd2bf43afe0ae9a82143a494d9"}, + {file = "marshmallow-3.22.0.tar.gz", hash = "sha256:4972f529104a220bb8637d595aa4c9762afbe7f7a77d82dc58c1615d70c5823e"}, ] [package.dependencies] @@ -967,44 +1028,70 @@ packaging = ">=17.0" [package.extras] dev = ["marshmallow[tests]", "pre-commit (>=3.5,<4.0)", "tox"] -docs = ["alabaster (==0.7.16)", "autodocsumm (==0.2.12)", "sphinx (==7.2.6)", "sphinx-issues (==4.0.0)", "sphinx-version-warning (==1.1.2)"] +docs = ["alabaster (==1.0.0)", "autodocsumm (==0.2.13)", "sphinx (==8.0.2)", "sphinx-issues (==4.1.0)", "sphinx-version-warning (==1.1.2)"] tests = ["pytest", "pytz", "simplejson"] +[[package]] +name = "marshmallow-enum" +version = "1.5.1" +description = "Enum field for Marshmallow" +optional = false +python-versions = "*" +files = [ + {file = "marshmallow-enum-1.5.1.tar.gz", hash = "sha256:38e697e11f45a8e64b4a1e664000897c659b60aa57bfa18d44e226a9920b6e58"}, + {file = "marshmallow_enum-1.5.1-py2.py3-none-any.whl", hash = "sha256:57161ab3dbfde4f57adeb12090f39592e992b9c86d206d02f6bd03ebec60f072"}, +] + +[package.dependencies] +marshmallow = ">=2.0.0" + [[package]] name = "matplotlib" -version = "3.8.3" +version = "3.9.2" description = "Python plotting package" optional = false python-versions = ">=3.9" files = [ - {file = "matplotlib-3.8.3-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:cf60138ccc8004f117ab2a2bad513cc4d122e55864b4fe7adf4db20ca68a078f"}, - {file = "matplotlib-3.8.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:5f557156f7116be3340cdeef7f128fa99b0d5d287d5f41a16e169819dcf22357"}, - {file = "matplotlib-3.8.3-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f386cf162b059809ecfac3bcc491a9ea17da69fa35c8ded8ad154cd4b933d5ec"}, - {file = "matplotlib-3.8.3-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b3c5f96f57b0369c288bf6f9b5274ba45787f7e0589a34d24bdbaf6d3344632f"}, - {file = "matplotlib-3.8.3-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:83e0f72e2c116ca7e571c57aa29b0fe697d4c6425c4e87c6e994159e0c008635"}, - {file = "matplotlib-3.8.3-cp310-cp310-win_amd64.whl", hash = "sha256:1c5c8290074ba31a41db1dc332dc2b62def469ff33766cbe325d32a3ee291aea"}, - {file = "matplotlib-3.8.3-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:5184e07c7e1d6d1481862ee361905b7059f7fe065fc837f7c3dc11eeb3f2f900"}, - {file = "matplotlib-3.8.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d7e7e0993d0758933b1a241a432b42c2db22dfa37d4108342ab4afb9557cbe3e"}, - {file = "matplotlib-3.8.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:04b36ad07eac9740fc76c2aa16edf94e50b297d6eb4c081e3add863de4bb19a7"}, - {file = "matplotlib-3.8.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7c42dae72a62f14982f1474f7e5c9959fc4bc70c9de11cc5244c6e766200ba65"}, - {file = "matplotlib-3.8.3-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:bf5932eee0d428192c40b7eac1399d608f5d995f975cdb9d1e6b48539a5ad8d0"}, - {file = "matplotlib-3.8.3-cp311-cp311-win_amd64.whl", hash = "sha256:40321634e3a05ed02abf7c7b47a50be50b53ef3eaa3a573847431a545585b407"}, - {file = "matplotlib-3.8.3-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:09074f8057917d17ab52c242fdf4916f30e99959c1908958b1fc6032e2d0f6d4"}, - {file = "matplotlib-3.8.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5745f6d0fb5acfabbb2790318db03809a253096e98c91b9a31969df28ee604aa"}, - {file = "matplotlib-3.8.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b97653d869a71721b639714b42d87cda4cfee0ee74b47c569e4874c7590c55c5"}, - {file = "matplotlib-3.8.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:242489efdb75b690c9c2e70bb5c6550727058c8a614e4c7716f363c27e10bba1"}, - {file = "matplotlib-3.8.3-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:83c0653c64b73926730bd9ea14aa0f50f202ba187c307a881673bad4985967b7"}, - {file = "matplotlib-3.8.3-cp312-cp312-win_amd64.whl", hash = "sha256:ef6c1025a570354297d6c15f7d0f296d95f88bd3850066b7f1e7b4f2f4c13a39"}, - {file = "matplotlib-3.8.3-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:c4af3f7317f8a1009bbb2d0bf23dfaba859eb7dd4ccbd604eba146dccaaaf0a4"}, - {file = "matplotlib-3.8.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:4c6e00a65d017d26009bac6808f637b75ceade3e1ff91a138576f6b3065eeeba"}, - {file = "matplotlib-3.8.3-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e7b49ab49a3bea17802df6872f8d44f664ba8f9be0632a60c99b20b6db2165b7"}, - {file = "matplotlib-3.8.3-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6728dde0a3997396b053602dbd907a9bd64ec7d5cf99e728b404083698d3ca01"}, - {file = "matplotlib-3.8.3-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:813925d08fb86aba139f2d31864928d67511f64e5945ca909ad5bc09a96189bb"}, - {file = "matplotlib-3.8.3-cp39-cp39-win_amd64.whl", hash = "sha256:cd3a0c2be76f4e7be03d34a14d49ded6acf22ef61f88da600a18a5cd8b3c5f3c"}, - {file = "matplotlib-3.8.3-pp39-pypy39_pp73-macosx_10_12_x86_64.whl", hash = "sha256:fa93695d5c08544f4a0dfd0965f378e7afc410d8672816aff1e81be1f45dbf2e"}, - {file = "matplotlib-3.8.3-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e9764df0e8778f06414b9d281a75235c1e85071f64bb5d71564b97c1306a2afc"}, - {file = "matplotlib-3.8.3-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:5e431a09e6fab4012b01fc155db0ce6dccacdbabe8198197f523a4ef4805eb26"}, - {file = "matplotlib-3.8.3.tar.gz", hash = "sha256:7b416239e9ae38be54b028abbf9048aff5054a9aba5416bef0bd17f9162ce161"}, + {file = "matplotlib-3.9.2-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:9d78bbc0cbc891ad55b4f39a48c22182e9bdaea7fc0e5dbd364f49f729ca1bbb"}, + {file = "matplotlib-3.9.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c375cc72229614632c87355366bdf2570c2dac01ac66b8ad048d2dabadf2d0d4"}, + {file = "matplotlib-3.9.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1d94ff717eb2bd0b58fe66380bd8b14ac35f48a98e7c6765117fe67fb7684e64"}, + {file = "matplotlib-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ab68d50c06938ef28681073327795c5db99bb4666214d2d5f880ed11aeaded66"}, + {file = "matplotlib-3.9.2-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:65aacf95b62272d568044531e41de26285d54aec8cb859031f511f84bd8b495a"}, + {file = "matplotlib-3.9.2-cp310-cp310-win_amd64.whl", hash = "sha256:3fd595f34aa8a55b7fc8bf9ebea8aa665a84c82d275190a61118d33fbc82ccae"}, + {file = "matplotlib-3.9.2-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:d8dd059447824eec055e829258ab092b56bb0579fc3164fa09c64f3acd478772"}, + {file = "matplotlib-3.9.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c797dac8bb9c7a3fd3382b16fe8f215b4cf0f22adccea36f1545a6d7be310b41"}, + {file = "matplotlib-3.9.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d719465db13267bcef19ea8954a971db03b9f48b4647e3860e4bc8e6ed86610f"}, + {file = "matplotlib-3.9.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8912ef7c2362f7193b5819d17dae8629b34a95c58603d781329712ada83f9447"}, + {file = "matplotlib-3.9.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:7741f26a58a240f43bee74965c4882b6c93df3e7eb3de160126d8c8f53a6ae6e"}, + {file = "matplotlib-3.9.2-cp311-cp311-win_amd64.whl", hash = "sha256:ae82a14dab96fbfad7965403c643cafe6515e386de723e498cf3eeb1e0b70cc7"}, + {file = "matplotlib-3.9.2-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:ac43031375a65c3196bee99f6001e7fa5bdfb00ddf43379d3c0609bdca042df9"}, + {file = "matplotlib-3.9.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:be0fc24a5e4531ae4d8e858a1a548c1fe33b176bb13eff7f9d0d38ce5112a27d"}, + {file = "matplotlib-3.9.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bf81de2926c2db243c9b2cbc3917619a0fc85796c6ba4e58f541df814bbf83c7"}, + {file = "matplotlib-3.9.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f6ee45bc4245533111ced13f1f2cace1e7f89d1c793390392a80c139d6cf0e6c"}, + {file = "matplotlib-3.9.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:306c8dfc73239f0e72ac50e5a9cf19cc4e8e331dd0c54f5e69ca8758550f1e1e"}, + {file = "matplotlib-3.9.2-cp312-cp312-win_amd64.whl", hash = "sha256:5413401594cfaff0052f9d8b1aafc6d305b4bd7c4331dccd18f561ff7e1d3bd3"}, + {file = "matplotlib-3.9.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:18128cc08f0d3cfff10b76baa2f296fc28c4607368a8402de61bb3f2eb33c7d9"}, + {file = "matplotlib-3.9.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:4876d7d40219e8ae8bb70f9263bcbe5714415acfdf781086601211335e24f8aa"}, + {file = "matplotlib-3.9.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6d9f07a80deab4bb0b82858a9e9ad53d1382fd122be8cde11080f4e7dfedb38b"}, + {file = "matplotlib-3.9.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f7c0410f181a531ec4e93bbc27692f2c71a15c2da16766f5ba9761e7ae518413"}, + {file = "matplotlib-3.9.2-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:909645cce2dc28b735674ce0931a4ac94e12f5b13f6bb0b5a5e65e7cea2c192b"}, + {file = "matplotlib-3.9.2-cp313-cp313-win_amd64.whl", hash = "sha256:f32c7410c7f246838a77d6d1eff0c0f87f3cb0e7c4247aebea71a6d5a68cab49"}, + {file = "matplotlib-3.9.2-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:37e51dd1c2db16ede9cfd7b5cabdfc818b2c6397c83f8b10e0e797501c963a03"}, + {file = "matplotlib-3.9.2-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:b82c5045cebcecd8496a4d694d43f9cc84aeeb49fe2133e036b207abe73f4d30"}, + {file = "matplotlib-3.9.2-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f053c40f94bc51bc03832a41b4f153d83f2062d88c72b5e79997072594e97e51"}, + {file = "matplotlib-3.9.2-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dbe196377a8248972f5cede786d4c5508ed5f5ca4a1e09b44bda889958b33f8c"}, + {file = "matplotlib-3.9.2-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:5816b1e1fe8c192cbc013f8f3e3368ac56fbecf02fb41b8f8559303f24c5015e"}, + {file = "matplotlib-3.9.2-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:cef2a73d06601437be399908cf13aee74e86932a5ccc6ccdf173408ebc5f6bb2"}, + {file = "matplotlib-3.9.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e0830e188029c14e891fadd99702fd90d317df294c3298aad682739c5533721a"}, + {file = "matplotlib-3.9.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:03ba9c1299c920964e8d3857ba27173b4dbb51ca4bab47ffc2c2ba0eb5e2cbc5"}, + {file = "matplotlib-3.9.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1cd93b91ab47a3616b4d3c42b52f8363b88ca021e340804c6ab2536344fad9ca"}, + {file = "matplotlib-3.9.2-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:6d1ce5ed2aefcdce11904fc5bbea7d9c21fff3d5f543841edf3dea84451a09ea"}, + {file = "matplotlib-3.9.2-cp39-cp39-win_amd64.whl", hash = "sha256:b2696efdc08648536efd4e1601b5fd491fd47f4db97a5fbfd175549a7365c1b2"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:d52a3b618cb1cbb769ce2ee1dcdb333c3ab6e823944e9a2d36e37253815f9556"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:039082812cacd6c6bec8e17a9c1e6baca230d4116d522e81e1f63a74d01d2e21"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6758baae2ed64f2331d4fd19be38b7b4eae3ecec210049a26b6a4f3ae1c85dcc"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:050598c2b29e0b9832cde72bcf97627bf00262adbc4a54e2b856426bb2ef0697"}, + {file = "matplotlib-3.9.2.tar.gz", hash = "sha256:96ab43906269ca64a6366934106fa01534454a69e471b7bf3d79083981aaab92"}, ] [package.dependencies] @@ -1013,21 +1100,24 @@ cycler = ">=0.10" fonttools = ">=4.22.0" importlib-resources = {version = ">=3.2.0", markers = "python_version < \"3.10\""} kiwisolver = ">=1.3.1" -numpy = ">=1.21,<2" +numpy = ">=1.23" packaging = ">=20.0" pillow = ">=8" pyparsing = ">=2.3.1" python-dateutil = ">=2.7" +[package.extras] +dev = ["meson-python (>=0.13.1)", "numpy (>=1.25)", "pybind11 (>=2.6)", "setuptools (>=64)", "setuptools_scm (>=7)"] + [[package]] name = "matplotlib-inline" -version = "0.1.6" +version = "0.1.7" description = "Inline Matplotlib backend for Jupyter" optional = false -python-versions = ">=3.5" +python-versions = ">=3.8" files = [ - {file = "matplotlib-inline-0.1.6.tar.gz", hash = "sha256:f887e5f10ba98e8d2b150ddcf4702c1e5f8b3a20005eb0f74bfdbd360ee6f304"}, - {file = "matplotlib_inline-0.1.6-py3-none-any.whl", hash = "sha256:f1f41aab5328aa5aaea9b16d083b128102f8712542f819fe7e6a420ff581b311"}, + {file = "matplotlib_inline-0.1.7-py3-none-any.whl", hash = "sha256:df192d39a4ff8f21b1895d72e6a13f5fcc5099f00fa84384e0ea28c2cc0653ca"}, + {file = "matplotlib_inline-0.1.7.tar.gz", hash = "sha256:8423b23ec666be3d16e16b60bdd8ac4e86e840ebd1dd11a30b9f117f2fa0ab90"}, ] [package.dependencies] @@ -1068,92 +1158,113 @@ files = [ [[package]] name = "numba" -version = "0.59.0" +version = "0.60.0" description = "compiling Python code using LLVM" optional = false python-versions = ">=3.9" files = [ - {file = "numba-0.59.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:8d061d800473fb8fef76a455221f4ad649a53f5e0f96e3f6c8b8553ee6fa98fa"}, - {file = "numba-0.59.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c086a434e7d3891ce5dfd3d1e7ee8102ac1e733962098578b507864120559ceb"}, - {file = "numba-0.59.0-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:9e20736bf62e61f8353fb71b0d3a1efba636c7a303d511600fc57648b55823ed"}, - {file = "numba-0.59.0-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e86e6786aec31d2002122199486e10bbc0dc40f78d76364cded375912b13614c"}, - {file = "numba-0.59.0-cp310-cp310-win_amd64.whl", hash = "sha256:0307ee91b24500bb7e64d8a109848baf3a3905df48ce142b8ac60aaa406a0400"}, - {file = "numba-0.59.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:d540f69a8245fb714419c2209e9af6104e568eb97623adc8943642e61f5d6d8e"}, - {file = "numba-0.59.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1192d6b2906bf3ff72b1d97458724d98860ab86a91abdd4cfd9328432b661e31"}, - {file = "numba-0.59.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:90efb436d3413809fcd15298c6d395cb7d98184350472588356ccf19db9e37c8"}, - {file = "numba-0.59.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:cd3dac45e25d927dcb65d44fb3a973994f5add2b15add13337844afe669dd1ba"}, - {file = "numba-0.59.0-cp311-cp311-win_amd64.whl", hash = "sha256:753dc601a159861808cc3207bad5c17724d3b69552fd22768fddbf302a817a4c"}, - {file = "numba-0.59.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:ce62bc0e6dd5264e7ff7f34f41786889fa81a6b860662f824aa7532537a7bee0"}, - {file = "numba-0.59.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8cbef55b73741b5eea2dbaf1b0590b14977ca95a13a07d200b794f8f6833a01c"}, - {file = "numba-0.59.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:70d26ba589f764be45ea8c272caa467dbe882b9676f6749fe6f42678091f5f21"}, - {file = "numba-0.59.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e125f7d69968118c28ec0eed9fbedd75440e64214b8d2eac033c22c04db48492"}, - {file = "numba-0.59.0-cp312-cp312-win_amd64.whl", hash = "sha256:4981659220b61a03c1e557654027d271f56f3087448967a55c79a0e5f926de62"}, - {file = "numba-0.59.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:fe4d7562d1eed754a7511ed7ba962067f198f86909741c5c6e18c4f1819b1f47"}, - {file = "numba-0.59.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:6feb1504bb432280f900deaf4b1dadcee68812209500ed3f81c375cbceab24dc"}, - {file = "numba-0.59.0-cp39-cp39-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:944faad25ee23ea9dda582bfb0189fb9f4fc232359a80ab2a028b94c14ce2b1d"}, - {file = "numba-0.59.0-cp39-cp39-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:5516a469514bfae52a9d7989db4940653a5cbfac106f44cb9c50133b7ad6224b"}, - {file = "numba-0.59.0-cp39-cp39-win_amd64.whl", hash = "sha256:32bd0a41525ec0b1b853da244808f4e5333867df3c43c30c33f89cf20b9c2b63"}, - {file = "numba-0.59.0.tar.gz", hash = "sha256:12b9b064a3e4ad00e2371fc5212ef0396c80f41caec9b5ec391c8b04b6eaf2a8"}, + {file = "numba-0.60.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:5d761de835cd38fb400d2c26bb103a2726f548dc30368853121d66201672e651"}, + {file = "numba-0.60.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:159e618ef213fba758837f9837fb402bbe65326e60ba0633dbe6c7f274d42c1b"}, + {file = "numba-0.60.0-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:1527dc578b95c7c4ff248792ec33d097ba6bef9eda466c948b68dfc995c25781"}, + {file = "numba-0.60.0-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:fe0b28abb8d70f8160798f4de9d486143200f34458d34c4a214114e445d7124e"}, + {file = "numba-0.60.0-cp310-cp310-win_amd64.whl", hash = "sha256:19407ced081d7e2e4b8d8c36aa57b7452e0283871c296e12d798852bc7d7f198"}, + {file = "numba-0.60.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a17b70fc9e380ee29c42717e8cc0bfaa5556c416d94f9aa96ba13acb41bdece8"}, + {file = "numba-0.60.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:3fb02b344a2a80efa6f677aa5c40cd5dd452e1b35f8d1c2af0dfd9ada9978e4b"}, + {file = "numba-0.60.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:5f4fde652ea604ea3c86508a3fb31556a6157b2c76c8b51b1d45eb40c8598703"}, + {file = "numba-0.60.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4142d7ac0210cc86432b818338a2bc368dc773a2f5cf1e32ff7c5b378bd63ee8"}, + {file = "numba-0.60.0-cp311-cp311-win_amd64.whl", hash = "sha256:cac02c041e9b5bc8cf8f2034ff6f0dbafccd1ae9590dc146b3a02a45e53af4e2"}, + {file = "numba-0.60.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:d7da4098db31182fc5ffe4bc42c6f24cd7d1cb8a14b59fd755bfee32e34b8404"}, + {file = "numba-0.60.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:38d6ea4c1f56417076ecf8fc327c831ae793282e0ff51080c5094cb726507b1c"}, + {file = "numba-0.60.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:62908d29fb6a3229c242e981ca27e32a6e606cc253fc9e8faeb0e48760de241e"}, + {file = "numba-0.60.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:0ebaa91538e996f708f1ab30ef4d3ddc344b64b5227b67a57aa74f401bb68b9d"}, + {file = "numba-0.60.0-cp312-cp312-win_amd64.whl", hash = "sha256:f75262e8fe7fa96db1dca93d53a194a38c46da28b112b8a4aca168f0df860347"}, + {file = "numba-0.60.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:01ef4cd7d83abe087d644eaa3d95831b777aa21d441a23703d649e06b8e06b74"}, + {file = "numba-0.60.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:819a3dfd4630d95fd574036f99e47212a1af41cbcb019bf8afac63ff56834449"}, + {file = "numba-0.60.0-cp39-cp39-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0b983bd6ad82fe868493012487f34eae8bf7dd94654951404114f23c3466d34b"}, + {file = "numba-0.60.0-cp39-cp39-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:c151748cd269ddeab66334bd754817ffc0cabd9433acb0f551697e5151917d25"}, + {file = "numba-0.60.0-cp39-cp39-win_amd64.whl", hash = "sha256:3031547a015710140e8c87226b4cfe927cac199835e5bf7d4fe5cb64e814e3ab"}, + {file = "numba-0.60.0.tar.gz", hash = "sha256:5df6158e5584eece5fc83294b949fd30b9f1125df7708862205217e068aabf16"}, ] [package.dependencies] -llvmlite = "==0.42.*" -numpy = ">=1.22,<1.27" +llvmlite = "==0.43.*" +numpy = ">=1.22,<2.1" [[package]] name = "numpy" -version = "1.25.0" +version = "2.0.2" description = "Fundamental package for array computing in Python" optional = false python-versions = ">=3.9" files = [ - {file = "numpy-1.25.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:8aa130c3042052d656751df5e81f6d61edff3e289b5994edcf77f54118a8d9f4"}, - {file = "numpy-1.25.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:9e3f2b96e3b63c978bc29daaa3700c028fe3f049ea3031b58aa33fe2a5809d24"}, - {file = "numpy-1.25.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d6b267f349a99d3908b56645eebf340cb58f01bd1e773b4eea1a905b3f0e4208"}, - {file = "numpy-1.25.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4aedd08f15d3045a4e9c648f1e04daca2ab1044256959f1f95aafeeb3d794c16"}, - {file = "numpy-1.25.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:6d183b5c58513f74225c376643234c369468e02947b47942eacbb23c1671f25d"}, - {file = "numpy-1.25.0-cp310-cp310-win32.whl", hash = "sha256:d76a84998c51b8b68b40448ddd02bd1081bb33abcdc28beee6cd284fe11036c6"}, - {file = "numpy-1.25.0-cp310-cp310-win_amd64.whl", hash = "sha256:c0dc071017bc00abb7d7201bac06fa80333c6314477b3d10b52b58fa6a6e38f6"}, - {file = "numpy-1.25.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4c69fe5f05eea336b7a740e114dec995e2f927003c30702d896892403df6dbf0"}, - {file = "numpy-1.25.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9c7211d7920b97aeca7b3773a6783492b5b93baba39e7c36054f6e749fc7490c"}, - {file = "numpy-1.25.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ecc68f11404930e9c7ecfc937aa423e1e50158317bf67ca91736a9864eae0232"}, - {file = "numpy-1.25.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e559c6afbca484072a98a51b6fa466aae785cfe89b69e8b856c3191bc8872a82"}, - {file = "numpy-1.25.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:6c284907e37f5e04d2412950960894b143a648dea3f79290757eb878b91acbd1"}, - {file = "numpy-1.25.0-cp311-cp311-win32.whl", hash = "sha256:95367ccd88c07af21b379be1725b5322362bb83679d36691f124a16357390153"}, - {file = "numpy-1.25.0-cp311-cp311-win_amd64.whl", hash = "sha256:b76aa836a952059d70a2788a2d98cb2a533ccd46222558b6970348939e55fc24"}, - {file = "numpy-1.25.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:b792164e539d99d93e4e5e09ae10f8cbe5466de7d759fc155e075237e0c274e4"}, - {file = "numpy-1.25.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:7cd981ccc0afe49b9883f14761bb57c964df71124dcd155b0cba2b591f0d64b9"}, - {file = "numpy-1.25.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5aa48bebfb41f93043a796128854b84407d4df730d3fb6e5dc36402f5cd594c0"}, - {file = "numpy-1.25.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5177310ac2e63d6603f659fadc1e7bab33dd5a8db4e0596df34214eeab0fee3b"}, - {file = "numpy-1.25.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:0ac6edfb35d2a99aaf102b509c8e9319c499ebd4978df4971b94419a116d0790"}, - {file = "numpy-1.25.0-cp39-cp39-win32.whl", hash = "sha256:7412125b4f18aeddca2ecd7219ea2d2708f697943e6f624be41aa5f8a9852cc4"}, - {file = "numpy-1.25.0-cp39-cp39-win_amd64.whl", hash = "sha256:26815c6c8498dc49d81faa76d61078c4f9f0859ce7817919021b9eba72b425e3"}, - {file = "numpy-1.25.0-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:5b1b90860bf7d8a8c313b372d4f27343a54f415b20fb69dd601b7efe1029c91e"}, - {file = "numpy-1.25.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:85cdae87d8c136fd4da4dad1e48064d700f63e923d5af6c8c782ac0df8044542"}, - {file = "numpy-1.25.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:cc3fda2b36482891db1060f00f881c77f9423eead4c3579629940a3e12095fe8"}, - {file = "numpy-1.25.0.tar.gz", hash = "sha256:f1accae9a28dc3cda46a91de86acf69de0d1b5f4edd44a9b0c3ceb8036dfff19"}, + {file = "numpy-2.0.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:51129a29dbe56f9ca83438b706e2e69a39892b5eda6cedcb6b0c9fdc9b0d3ece"}, + {file = "numpy-2.0.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:f15975dfec0cf2239224d80e32c3170b1d168335eaedee69da84fbe9f1f9cd04"}, + {file = "numpy-2.0.2-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:8c5713284ce4e282544c68d1c3b2c7161d38c256d2eefc93c1d683cf47683e66"}, + {file = "numpy-2.0.2-cp310-cp310-macosx_14_0_x86_64.whl", hash = "sha256:becfae3ddd30736fe1889a37f1f580e245ba79a5855bff5f2a29cb3ccc22dd7b"}, + {file = "numpy-2.0.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2da5960c3cf0df7eafefd806d4e612c5e19358de82cb3c343631188991566ccd"}, + {file = "numpy-2.0.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:496f71341824ed9f3d2fd36cf3ac57ae2e0165c143b55c3a035ee219413f3318"}, + {file = "numpy-2.0.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:a61ec659f68ae254e4d237816e33171497e978140353c0c2038d46e63282d0c8"}, + {file = "numpy-2.0.2-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:d731a1c6116ba289c1e9ee714b08a8ff882944d4ad631fd411106a30f083c326"}, + {file = "numpy-2.0.2-cp310-cp310-win32.whl", hash = "sha256:984d96121c9f9616cd33fbd0618b7f08e0cfc9600a7ee1d6fd9b239186d19d97"}, + {file = "numpy-2.0.2-cp310-cp310-win_amd64.whl", hash = "sha256:c7b0be4ef08607dd04da4092faee0b86607f111d5ae68036f16cc787e250a131"}, + {file = "numpy-2.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:49ca4decb342d66018b01932139c0961a8f9ddc7589611158cb3c27cbcf76448"}, + {file = "numpy-2.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:11a76c372d1d37437857280aa142086476136a8c0f373b2e648ab2c8f18fb195"}, + {file = "numpy-2.0.2-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:807ec44583fd708a21d4a11d94aedf2f4f3c3719035c76a2bbe1fe8e217bdc57"}, + {file = "numpy-2.0.2-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:8cafab480740e22f8d833acefed5cc87ce276f4ece12fdaa2e8903db2f82897a"}, + {file = "numpy-2.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a15f476a45e6e5a3a79d8a14e62161d27ad897381fecfa4a09ed5322f2085669"}, + {file = "numpy-2.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:13e689d772146140a252c3a28501da66dfecd77490b498b168b501835041f951"}, + {file = "numpy-2.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:9ea91dfb7c3d1c56a0e55657c0afb38cf1eeae4544c208dc465c3c9f3a7c09f9"}, + {file = "numpy-2.0.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c1c9307701fec8f3f7a1e6711f9089c06e6284b3afbbcd259f7791282d660a15"}, + {file = "numpy-2.0.2-cp311-cp311-win32.whl", hash = "sha256:a392a68bd329eafac5817e5aefeb39038c48b671afd242710b451e76090e81f4"}, + {file = "numpy-2.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:286cd40ce2b7d652a6f22efdfc6d1edf879440e53e76a75955bc0c826c7e64dc"}, + {file = "numpy-2.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:df55d490dea7934f330006d0f81e8551ba6010a5bf035a249ef61a94f21c500b"}, + {file = "numpy-2.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8df823f570d9adf0978347d1f926b2a867d5608f434a7cff7f7908c6570dcf5e"}, + {file = "numpy-2.0.2-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:9a92ae5c14811e390f3767053ff54eaee3bf84576d99a2456391401323f4ec2c"}, + {file = "numpy-2.0.2-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:a842d573724391493a97a62ebbb8e731f8a5dcc5d285dfc99141ca15a3302d0c"}, + {file = "numpy-2.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c05e238064fc0610c840d1cf6a13bf63d7e391717d247f1bf0318172e759e692"}, + {file = "numpy-2.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0123ffdaa88fa4ab64835dcbde75dcdf89c453c922f18dced6e27c90d1d0ec5a"}, + {file = "numpy-2.0.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:96a55f64139912d61de9137f11bf39a55ec8faec288c75a54f93dfd39f7eb40c"}, + {file = "numpy-2.0.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:ec9852fb39354b5a45a80bdab5ac02dd02b15f44b3804e9f00c556bf24b4bded"}, + {file = "numpy-2.0.2-cp312-cp312-win32.whl", hash = "sha256:671bec6496f83202ed2d3c8fdc486a8fc86942f2e69ff0e986140339a63bcbe5"}, + {file = "numpy-2.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:cfd41e13fdc257aa5778496b8caa5e856dc4896d4ccf01841daee1d96465467a"}, + {file = "numpy-2.0.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:9059e10581ce4093f735ed23f3b9d283b9d517ff46009ddd485f1747eb22653c"}, + {file = "numpy-2.0.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:423e89b23490805d2a5a96fe40ec507407b8ee786d66f7328be214f9679df6dd"}, + {file = "numpy-2.0.2-cp39-cp39-macosx_14_0_arm64.whl", hash = "sha256:2b2955fa6f11907cf7a70dab0d0755159bca87755e831e47932367fc8f2f2d0b"}, + {file = "numpy-2.0.2-cp39-cp39-macosx_14_0_x86_64.whl", hash = "sha256:97032a27bd9d8988b9a97a8c4d2c9f2c15a81f61e2f21404d7e8ef00cb5be729"}, + {file = "numpy-2.0.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1e795a8be3ddbac43274f18588329c72939870a16cae810c2b73461c40718ab1"}, + {file = "numpy-2.0.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f26b258c385842546006213344c50655ff1555a9338e2e5e02a0756dc3e803dd"}, + {file = "numpy-2.0.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:5fec9451a7789926bcf7c2b8d187292c9f93ea30284802a0ab3f5be8ab36865d"}, + {file = "numpy-2.0.2-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:9189427407d88ff25ecf8f12469d4d39d35bee1db5d39fc5c168c6f088a6956d"}, + {file = "numpy-2.0.2-cp39-cp39-win32.whl", hash = "sha256:905d16e0c60200656500c95b6b8dca5d109e23cb24abc701d41c02d74c6b3afa"}, + {file = "numpy-2.0.2-cp39-cp39-win_amd64.whl", hash = "sha256:a3f4ab0caa7f053f6797fcd4e1e25caee367db3112ef2b6ef82d749530768c73"}, + {file = "numpy-2.0.2-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:7f0a0c6f12e07fa94133c8a67404322845220c06a9e80e85999afe727f7438b8"}, + {file = "numpy-2.0.2-pp39-pypy39_pp73-macosx_14_0_x86_64.whl", hash = "sha256:312950fdd060354350ed123c0e25a71327d3711584beaef30cdaa93320c392d4"}, + {file = "numpy-2.0.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:26df23238872200f63518dd2aa984cfca675d82469535dc7162dc2ee52d9dd5c"}, + {file = "numpy-2.0.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:a46288ec55ebbd58947d31d72be2c63cbf839f0a63b49cb755022310792a3385"}, + {file = "numpy-2.0.2.tar.gz", hash = "sha256:883c987dee1880e2a864ab0dc9892292582510604156762362d9326444636e78"}, ] [[package]] name = "opencv-python" -version = "4.9.0.80" +version = "4.10.0.84" description = "Wrapper package for OpenCV python bindings." optional = false python-versions = ">=3.6" files = [ - {file = "opencv-python-4.9.0.80.tar.gz", hash = "sha256:1a9f0e6267de3a1a1db0c54213d022c7c8b5b9ca4b580e80bdc58516c922c9e1"}, - {file = "opencv_python-4.9.0.80-cp37-abi3-macosx_10_16_x86_64.whl", hash = "sha256:7e5f7aa4486651a6ebfa8ed4b594b65bd2d2f41beeb4241a3e4b1b85acbbbadb"}, - {file = "opencv_python-4.9.0.80-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:71dfb9555ccccdd77305fc3dcca5897fbf0cf28b297c51ee55e079c065d812a3"}, - {file = "opencv_python-4.9.0.80-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7b34a52e9da36dda8c151c6394aed602e4b17fa041df0b9f5b93ae10b0fcca2a"}, - {file = "opencv_python-4.9.0.80-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e4088cab82b66a3b37ffc452976b14a3c599269c247895ae9ceb4066d8188a57"}, - {file = "opencv_python-4.9.0.80-cp37-abi3-win32.whl", hash = "sha256:dcf000c36dd1651118a2462257e3a9e76db789a78432e1f303c7bac54f63ef6c"}, - {file = "opencv_python-4.9.0.80-cp37-abi3-win_amd64.whl", hash = "sha256:3f16f08e02b2a2da44259c7cc712e779eff1dd8b55fdb0323e8cab09548086c0"}, + {file = "opencv-python-4.10.0.84.tar.gz", hash = "sha256:72d234e4582e9658ffea8e9cae5b63d488ad06994ef12d81dc303b17472f3526"}, + {file = "opencv_python-4.10.0.84-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:fc182f8f4cda51b45f01c64e4cbedfc2f00aff799debebc305d8d0210c43f251"}, + {file = "opencv_python-4.10.0.84-cp37-abi3-macosx_12_0_x86_64.whl", hash = "sha256:71e575744f1d23f79741450254660442785f45a0797212852ee5199ef12eed98"}, + {file = "opencv_python-4.10.0.84-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:09a332b50488e2dda866a6c5573ee192fe3583239fb26ff2f7f9ceb0bc119ea6"}, + {file = "opencv_python-4.10.0.84-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9ace140fc6d647fbe1c692bcb2abce768973491222c067c131d80957c595b71f"}, + {file = "opencv_python-4.10.0.84-cp37-abi3-win32.whl", hash = "sha256:2db02bb7e50b703f0a2d50c50ced72e95c574e1e5a0bb35a8a86d0b35c98c236"}, + {file = "opencv_python-4.10.0.84-cp37-abi3-win_amd64.whl", hash = "sha256:32dbbd94c26f611dc5cc6979e6b7aa1f55a64d6b463cc1dcd3c95505a63e48fe"}, ] [package.dependencies] numpy = [ {version = ">=1.21.0", markers = "python_version == \"3.9\" and platform_system == \"Darwin\" and platform_machine == \"arm64\""}, - {version = ">=1.23.5", markers = "python_version >= \"3.11\""}, + {version = ">=1.26.0", markers = "python_version >= \"3.12\""}, + {version = ">=1.23.5", markers = "python_version >= \"3.11\" and python_version < \"3.12\""}, {version = ">=1.21.4", markers = "python_version >= \"3.10\" and platform_system == \"Darwin\" and python_version < \"3.11\""}, {version = ">=1.21.2", markers = "platform_system != \"Darwin\" and python_version >= \"3.10\" and python_version < \"3.11\""}, {version = ">=1.19.3", markers = "platform_system == \"Linux\" and platform_machine == \"aarch64\" and python_version >= \"3.8\" and python_version < \"3.10\" or python_version > \"3.9\" and python_version < \"3.10\" or python_version >= \"3.9\" and platform_system != \"Darwin\" and python_version < \"3.10\" or python_version >= \"3.9\" and platform_machine != \"arm64\" and python_version < \"3.10\""}, @@ -1161,29 +1272,29 @@ numpy = [ [[package]] name = "packaging" -version = "23.2" +version = "24.1" description = "Core utilities for Python packages" optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "packaging-23.2-py3-none-any.whl", hash = "sha256:8c491190033a9af7e1d931d0b5dacc2ef47509b34dd0de67ed209b5203fc88c7"}, - {file = "packaging-23.2.tar.gz", hash = "sha256:048fb0e9405036518eaaf48a55953c750c11e1a1b68e0dd1a9d62ed0c092cfc5"}, + {file = "packaging-24.1-py3-none-any.whl", hash = "sha256:5b8f2217dbdbd2f7f384c41c628544e6d52f2d0f53c6d0c3ea61aa5d1d7ff124"}, + {file = "packaging-24.1.tar.gz", hash = "sha256:026ed72c8ed3fcce5bf8950572258698927fd1dbda10a5e981cdf0ac37f4f002"}, ] [[package]] name = "parso" -version = "0.8.3" +version = "0.8.4" description = "A Python Parser" optional = false python-versions = ">=3.6" files = [ - {file = "parso-0.8.3-py2.py3-none-any.whl", hash = "sha256:c001d4636cd3aecdaf33cbb40aebb59b094be2a74c556778ef5576c175e19e75"}, - {file = "parso-0.8.3.tar.gz", hash = "sha256:8c07be290bb59f03588915921e29e8a50002acaf2cdc5fa0e0114f91709fafa0"}, + {file = "parso-0.8.4-py2.py3-none-any.whl", hash = "sha256:a418670a20291dacd2dddc80c377c5c3791378ee1e8d12bffc35420643d43f18"}, + {file = "parso-0.8.4.tar.gz", hash = "sha256:eb3a7b58240fb99099a345571deecc0f9540ea5f4dd2fe14c2a99d6b281ab92d"}, ] [package.extras] -qa = ["flake8 (==3.8.3)", "mypy (==0.782)"] -testing = ["docopt", "pytest (<6.0.0)"] +qa = ["flake8 (==5.0.4)", "mypy (==0.971)", "types-setuptools (==67.2.0.1)"] +testing = ["docopt", "pytest"] [[package]] name = "pathspec" @@ -1212,83 +1323,95 @@ ptyprocess = ">=0.5" [[package]] name = "pillow" -version = "10.2.0" +version = "10.4.0" description = "Python Imaging Library (Fork)" optional = false python-versions = ">=3.8" files = [ - {file = "pillow-10.2.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:7823bdd049099efa16e4246bdf15e5a13dbb18a51b68fa06d6c1d4d8b99a796e"}, - {file = "pillow-10.2.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:83b2021f2ade7d1ed556bc50a399127d7fb245e725aa0113ebd05cfe88aaf588"}, - {file = "pillow-10.2.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6fad5ff2f13d69b7e74ce5b4ecd12cc0ec530fcee76356cac6742785ff71c452"}, - {file = "pillow-10.2.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:da2b52b37dad6d9ec64e653637a096905b258d2fc2b984c41ae7d08b938a67e4"}, - {file = "pillow-10.2.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:47c0995fc4e7f79b5cfcab1fc437ff2890b770440f7696a3ba065ee0fd496563"}, - {file = "pillow-10.2.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:322bdf3c9b556e9ffb18f93462e5f749d3444ce081290352c6070d014c93feb2"}, - {file = "pillow-10.2.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:51f1a1bffc50e2e9492e87d8e09a17c5eea8409cda8d3f277eb6edc82813c17c"}, - {file = "pillow-10.2.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:69ffdd6120a4737710a9eee73e1d2e37db89b620f702754b8f6e62594471dee0"}, - {file = "pillow-10.2.0-cp310-cp310-win32.whl", hash = "sha256:c6dafac9e0f2b3c78df97e79af707cdc5ef8e88208d686a4847bab8266870023"}, - {file = "pillow-10.2.0-cp310-cp310-win_amd64.whl", hash = "sha256:aebb6044806f2e16ecc07b2a2637ee1ef67a11840a66752751714a0d924adf72"}, - {file = "pillow-10.2.0-cp310-cp310-win_arm64.whl", hash = "sha256:7049e301399273a0136ff39b84c3678e314f2158f50f517bc50285fb5ec847ad"}, - {file = "pillow-10.2.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:35bb52c37f256f662abdfa49d2dfa6ce5d93281d323a9af377a120e89a9eafb5"}, - {file = "pillow-10.2.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9c23f307202661071d94b5e384e1e1dc7dfb972a28a2310e4ee16103e66ddb67"}, - {file = "pillow-10.2.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:773efe0603db30c281521a7c0214cad7836c03b8ccff897beae9b47c0b657d61"}, - {file = "pillow-10.2.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:11fa2e5984b949b0dd6d7a94d967743d87c577ff0b83392f17cb3990d0d2fd6e"}, - {file = "pillow-10.2.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:716d30ed977be8b37d3ef185fecb9e5a1d62d110dfbdcd1e2a122ab46fddb03f"}, - {file = "pillow-10.2.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:a086c2af425c5f62a65e12fbf385f7c9fcb8f107d0849dba5839461a129cf311"}, - {file = "pillow-10.2.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:c8de2789052ed501dd829e9cae8d3dcce7acb4777ea4a479c14521c942d395b1"}, - {file = "pillow-10.2.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:609448742444d9290fd687940ac0b57fb35e6fd92bdb65386e08e99af60bf757"}, - {file = "pillow-10.2.0-cp311-cp311-win32.whl", hash = "sha256:823ef7a27cf86df6597fa0671066c1b596f69eba53efa3d1e1cb8b30f3533068"}, - {file = "pillow-10.2.0-cp311-cp311-win_amd64.whl", hash = "sha256:1da3b2703afd040cf65ec97efea81cfba59cdbed9c11d8efc5ab09df9509fc56"}, - {file = "pillow-10.2.0-cp311-cp311-win_arm64.whl", hash = "sha256:edca80cbfb2b68d7b56930b84a0e45ae1694aeba0541f798e908a49d66b837f1"}, - {file = "pillow-10.2.0-cp312-cp312-macosx_10_10_x86_64.whl", hash = "sha256:1b5e1b74d1bd1b78bc3477528919414874748dd363e6272efd5abf7654e68bef"}, - {file = "pillow-10.2.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0eae2073305f451d8ecacb5474997c08569fb4eb4ac231ffa4ad7d342fdc25ac"}, - {file = "pillow-10.2.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b7c2286c23cd350b80d2fc9d424fc797575fb16f854b831d16fd47ceec078f2c"}, - {file = "pillow-10.2.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1e23412b5c41e58cec602f1135c57dfcf15482013ce6e5f093a86db69646a5aa"}, - {file = "pillow-10.2.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:52a50aa3fb3acb9cf7213573ef55d31d6eca37f5709c69e6858fe3bc04a5c2a2"}, - {file = "pillow-10.2.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:127cee571038f252a552760076407f9cff79761c3d436a12af6000cd182a9d04"}, - {file = "pillow-10.2.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:8d12251f02d69d8310b046e82572ed486685c38f02176bd08baf216746eb947f"}, - {file = "pillow-10.2.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:54f1852cd531aa981bc0965b7d609f5f6cc8ce8c41b1139f6ed6b3c54ab82bfb"}, - {file = "pillow-10.2.0-cp312-cp312-win32.whl", hash = "sha256:257d8788df5ca62c980314053197f4d46eefedf4e6175bc9412f14412ec4ea2f"}, - {file = "pillow-10.2.0-cp312-cp312-win_amd64.whl", hash = "sha256:154e939c5f0053a383de4fd3d3da48d9427a7e985f58af8e94d0b3c9fcfcf4f9"}, - {file = "pillow-10.2.0-cp312-cp312-win_arm64.whl", hash = "sha256:f379abd2f1e3dddb2b61bc67977a6b5a0a3f7485538bcc6f39ec76163891ee48"}, - {file = "pillow-10.2.0-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:8373c6c251f7ef8bda6675dd6d2b3a0fcc31edf1201266b5cf608b62a37407f9"}, - {file = "pillow-10.2.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:870ea1ada0899fd0b79643990809323b389d4d1d46c192f97342eeb6ee0b8483"}, - {file = "pillow-10.2.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b4b6b1e20608493548b1f32bce8cca185bf0480983890403d3b8753e44077129"}, - {file = "pillow-10.2.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3031709084b6e7852d00479fd1d310b07d0ba82765f973b543c8af5061cf990e"}, - {file = "pillow-10.2.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:3ff074fc97dd4e80543a3e91f69d58889baf2002b6be64347ea8cf5533188213"}, - {file = "pillow-10.2.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:cb4c38abeef13c61d6916f264d4845fab99d7b711be96c326b84df9e3e0ff62d"}, - {file = "pillow-10.2.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:b1b3020d90c2d8e1dae29cf3ce54f8094f7938460fb5ce8bc5c01450b01fbaf6"}, - {file = "pillow-10.2.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:170aeb00224ab3dc54230c797f8404507240dd868cf52066f66a41b33169bdbe"}, - {file = "pillow-10.2.0-cp38-cp38-win32.whl", hash = "sha256:c4225f5220f46b2fde568c74fca27ae9771536c2e29d7c04f4fb62c83275ac4e"}, - {file = "pillow-10.2.0-cp38-cp38-win_amd64.whl", hash = "sha256:0689b5a8c5288bc0504d9fcee48f61a6a586b9b98514d7d29b840143d6734f39"}, - {file = "pillow-10.2.0-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:b792a349405fbc0163190fde0dc7b3fef3c9268292586cf5645598b48e63dc67"}, - {file = "pillow-10.2.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:c570f24be1e468e3f0ce7ef56a89a60f0e05b30a3669a459e419c6eac2c35364"}, - {file = "pillow-10.2.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8ecd059fdaf60c1963c58ceb8997b32e9dc1b911f5da5307aab614f1ce5c2fb"}, - {file = "pillow-10.2.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c365fd1703040de1ec284b176d6af5abe21b427cb3a5ff68e0759e1e313a5e7e"}, - {file = "pillow-10.2.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:70c61d4c475835a19b3a5aa42492409878bbca7438554a1f89d20d58a7c75c01"}, - {file = "pillow-10.2.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:b6f491cdf80ae540738859d9766783e3b3c8e5bd37f5dfa0b76abdecc5081f13"}, - {file = "pillow-10.2.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:9d189550615b4948f45252d7f005e53c2040cea1af5b60d6f79491a6e147eef7"}, - {file = "pillow-10.2.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:49d9ba1ed0ef3e061088cd1e7538a0759aab559e2e0a80a36f9fd9d8c0c21591"}, - {file = "pillow-10.2.0-cp39-cp39-win32.whl", hash = "sha256:babf5acfede515f176833ed6028754cbcd0d206f7f614ea3447d67c33be12516"}, - {file = "pillow-10.2.0-cp39-cp39-win_amd64.whl", hash = "sha256:0304004f8067386b477d20a518b50f3fa658a28d44e4116970abfcd94fac34a8"}, - {file = "pillow-10.2.0-cp39-cp39-win_arm64.whl", hash = "sha256:0fb3e7fc88a14eacd303e90481ad983fd5b69c761e9e6ef94c983f91025da869"}, - {file = "pillow-10.2.0-pp310-pypy310_pp73-macosx_10_10_x86_64.whl", hash = "sha256:322209c642aabdd6207517e9739c704dc9f9db943015535783239022002f054a"}, - {file = "pillow-10.2.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3eedd52442c0a5ff4f887fab0c1c0bb164d8635b32c894bc1faf4c618dd89df2"}, - {file = "pillow-10.2.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cb28c753fd5eb3dd859b4ee95de66cc62af91bcff5db5f2571d32a520baf1f04"}, - {file = "pillow-10.2.0-pp310-pypy310_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:33870dc4653c5017bf4c8873e5488d8f8d5f8935e2f1fb9a2208c47cdd66efd2"}, - {file = "pillow-10.2.0-pp310-pypy310_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:3c31822339516fb3c82d03f30e22b1d038da87ef27b6a78c9549888f8ceda39a"}, - {file = "pillow-10.2.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:a2b56ba36e05f973d450582fb015594aaa78834fefe8dfb8fcd79b93e64ba4c6"}, - {file = "pillow-10.2.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:d8e6aeb9201e655354b3ad049cb77d19813ad4ece0df1249d3c793de3774f8c7"}, - {file = "pillow-10.2.0-pp39-pypy39_pp73-macosx_10_10_x86_64.whl", hash = "sha256:2247178effb34a77c11c0e8ac355c7a741ceca0a732b27bf11e747bbc950722f"}, - {file = "pillow-10.2.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:15587643b9e5eb26c48e49a7b33659790d28f190fc514a322d55da2fb5c2950e"}, - {file = "pillow-10.2.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:753cd8f2086b2b80180d9b3010dd4ed147efc167c90d3bf593fe2af21265e5a5"}, - {file = "pillow-10.2.0-pp39-pypy39_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:7c8f97e8e7a9009bcacbe3766a36175056c12f9a44e6e6f2d5caad06dcfbf03b"}, - {file = "pillow-10.2.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:d1b35bcd6c5543b9cb547dee3150c93008f8dd0f1fef78fc0cd2b141c5baf58a"}, - {file = "pillow-10.2.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:fe4c15f6c9285dc54ce6553a3ce908ed37c8f3825b5a51a15c91442bb955b868"}, - {file = "pillow-10.2.0.tar.gz", hash = "sha256:e87f0b2c78157e12d7686b27d63c070fd65d994e8ddae6f328e0dcf4a0cd007e"}, + {file = "pillow-10.4.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:4d9667937cfa347525b319ae34375c37b9ee6b525440f3ef48542fcf66f2731e"}, + {file = "pillow-10.4.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:543f3dc61c18dafb755773efc89aae60d06b6596a63914107f75459cf984164d"}, + {file = "pillow-10.4.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7928ecbf1ece13956b95d9cbcfc77137652b02763ba384d9ab508099a2eca856"}, + {file = "pillow-10.4.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e4d49b85c4348ea0b31ea63bc75a9f3857869174e2bf17e7aba02945cd218e6f"}, + {file = "pillow-10.4.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:6c762a5b0997f5659a5ef2266abc1d8851ad7749ad9a6a5506eb23d314e4f46b"}, + {file = "pillow-10.4.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:a985e028fc183bf12a77a8bbf36318db4238a3ded7fa9df1b9a133f1cb79f8fc"}, + {file = "pillow-10.4.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:812f7342b0eee081eaec84d91423d1b4650bb9828eb53d8511bcef8ce5aecf1e"}, + {file = "pillow-10.4.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:ac1452d2fbe4978c2eec89fb5a23b8387aba707ac72810d9490118817d9c0b46"}, + {file = "pillow-10.4.0-cp310-cp310-win32.whl", hash = "sha256:bcd5e41a859bf2e84fdc42f4edb7d9aba0a13d29a2abadccafad99de3feff984"}, + {file = "pillow-10.4.0-cp310-cp310-win_amd64.whl", hash = "sha256:ecd85a8d3e79cd7158dec1c9e5808e821feea088e2f69a974db5edf84dc53141"}, + {file = "pillow-10.4.0-cp310-cp310-win_arm64.whl", hash = "sha256:ff337c552345e95702c5fde3158acb0625111017d0e5f24bf3acdb9cc16b90d1"}, + {file = "pillow-10.4.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:0a9ec697746f268507404647e531e92889890a087e03681a3606d9b920fbee3c"}, + {file = "pillow-10.4.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:dfe91cb65544a1321e631e696759491ae04a2ea11d36715eca01ce07284738be"}, + {file = "pillow-10.4.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5dc6761a6efc781e6a1544206f22c80c3af4c8cf461206d46a1e6006e4429ff3"}, + {file = "pillow-10.4.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5e84b6cc6a4a3d76c153a6b19270b3526a5a8ed6b09501d3af891daa2a9de7d6"}, + {file = "pillow-10.4.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:bbc527b519bd3aa9d7f429d152fea69f9ad37c95f0b02aebddff592688998abe"}, + {file = "pillow-10.4.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:76a911dfe51a36041f2e756b00f96ed84677cdeb75d25c767f296c1c1eda1319"}, + {file = "pillow-10.4.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:59291fb29317122398786c2d44427bbd1a6d7ff54017075b22be9d21aa59bd8d"}, + {file = "pillow-10.4.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:416d3a5d0e8cfe4f27f574362435bc9bae57f679a7158e0096ad2beb427b8696"}, + {file = "pillow-10.4.0-cp311-cp311-win32.whl", hash = "sha256:7086cc1d5eebb91ad24ded9f58bec6c688e9f0ed7eb3dbbf1e4800280a896496"}, + {file = "pillow-10.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:cbed61494057c0f83b83eb3a310f0bf774b09513307c434d4366ed64f4128a91"}, + {file = "pillow-10.4.0-cp311-cp311-win_arm64.whl", hash = "sha256:f5f0c3e969c8f12dd2bb7e0b15d5c468b51e5017e01e2e867335c81903046a22"}, + {file = "pillow-10.4.0-cp312-cp312-macosx_10_10_x86_64.whl", hash = "sha256:673655af3eadf4df6b5457033f086e90299fdd7a47983a13827acf7459c15d94"}, + {file = "pillow-10.4.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:866b6942a92f56300012f5fbac71f2d610312ee65e22f1aa2609e491284e5597"}, + {file = "pillow-10.4.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:29dbdc4207642ea6aad70fbde1a9338753d33fb23ed6956e706936706f52dd80"}, + {file = "pillow-10.4.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bf2342ac639c4cf38799a44950bbc2dfcb685f052b9e262f446482afaf4bffca"}, + {file = "pillow-10.4.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:f5b92f4d70791b4a67157321c4e8225d60b119c5cc9aee8ecf153aace4aad4ef"}, + {file = "pillow-10.4.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:86dcb5a1eb778d8b25659d5e4341269e8590ad6b4e8b44d9f4b07f8d136c414a"}, + {file = "pillow-10.4.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:780c072c2e11c9b2c7ca37f9a2ee8ba66f44367ac3e5c7832afcfe5104fd6d1b"}, + {file = "pillow-10.4.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:37fb69d905be665f68f28a8bba3c6d3223c8efe1edf14cc4cfa06c241f8c81d9"}, + {file = "pillow-10.4.0-cp312-cp312-win32.whl", hash = "sha256:7dfecdbad5c301d7b5bde160150b4db4c659cee2b69589705b6f8a0c509d9f42"}, + {file = "pillow-10.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:1d846aea995ad352d4bdcc847535bd56e0fd88d36829d2c90be880ef1ee4668a"}, + {file = "pillow-10.4.0-cp312-cp312-win_arm64.whl", hash = "sha256:e553cad5179a66ba15bb18b353a19020e73a7921296a7979c4a2b7f6a5cd57f9"}, + {file = "pillow-10.4.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:8bc1a764ed8c957a2e9cacf97c8b2b053b70307cf2996aafd70e91a082e70df3"}, + {file = "pillow-10.4.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:6209bb41dc692ddfee4942517c19ee81b86c864b626dbfca272ec0f7cff5d9fb"}, + {file = "pillow-10.4.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bee197b30783295d2eb680b311af15a20a8b24024a19c3a26431ff83eb8d1f70"}, + {file = "pillow-10.4.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1ef61f5dd14c300786318482456481463b9d6b91ebe5ef12f405afbba77ed0be"}, + {file = "pillow-10.4.0-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:297e388da6e248c98bc4a02e018966af0c5f92dfacf5a5ca22fa01cb3179bca0"}, + {file = "pillow-10.4.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:e4db64794ccdf6cb83a59d73405f63adbe2a1887012e308828596100a0b2f6cc"}, + {file = "pillow-10.4.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:bd2880a07482090a3bcb01f4265f1936a903d70bc740bfcb1fd4e8a2ffe5cf5a"}, + {file = "pillow-10.4.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:4b35b21b819ac1dbd1233317adeecd63495f6babf21b7b2512d244ff6c6ce309"}, + {file = "pillow-10.4.0-cp313-cp313-win32.whl", hash = "sha256:551d3fd6e9dc15e4c1eb6fc4ba2b39c0c7933fa113b220057a34f4bb3268a060"}, + {file = "pillow-10.4.0-cp313-cp313-win_amd64.whl", hash = "sha256:030abdbe43ee02e0de642aee345efa443740aa4d828bfe8e2eb11922ea6a21ea"}, + {file = "pillow-10.4.0-cp313-cp313-win_arm64.whl", hash = "sha256:5b001114dd152cfd6b23befeb28d7aee43553e2402c9f159807bf55f33af8a8d"}, + {file = "pillow-10.4.0-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:8d4d5063501b6dd4024b8ac2f04962d661222d120381272deea52e3fc52d3736"}, + {file = "pillow-10.4.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:7c1ee6f42250df403c5f103cbd2768a28fe1a0ea1f0f03fe151c8741e1469c8b"}, + {file = "pillow-10.4.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b15e02e9bb4c21e39876698abf233c8c579127986f8207200bc8a8f6bb27acf2"}, + {file = "pillow-10.4.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7a8d4bade9952ea9a77d0c3e49cbd8b2890a399422258a77f357b9cc9be8d680"}, + {file = "pillow-10.4.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:43efea75eb06b95d1631cb784aa40156177bf9dd5b4b03ff38979e048258bc6b"}, + {file = "pillow-10.4.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:950be4d8ba92aca4b2bb0741285a46bfae3ca699ef913ec8416c1b78eadd64cd"}, + {file = "pillow-10.4.0-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:d7480af14364494365e89d6fddc510a13e5a2c3584cb19ef65415ca57252fb84"}, + {file = "pillow-10.4.0-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:73664fe514b34c8f02452ffb73b7a92c6774e39a647087f83d67f010eb9a0cf0"}, + {file = "pillow-10.4.0-cp38-cp38-win32.whl", hash = "sha256:e88d5e6ad0d026fba7bdab8c3f225a69f063f116462c49892b0149e21b6c0a0e"}, + {file = "pillow-10.4.0-cp38-cp38-win_amd64.whl", hash = "sha256:5161eef006d335e46895297f642341111945e2c1c899eb406882a6c61a4357ab"}, + {file = "pillow-10.4.0-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:0ae24a547e8b711ccaaf99c9ae3cd975470e1a30caa80a6aaee9a2f19c05701d"}, + {file = "pillow-10.4.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:298478fe4f77a4408895605f3482b6cc6222c018b2ce565c2b6b9c354ac3229b"}, + {file = "pillow-10.4.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:134ace6dc392116566980ee7436477d844520a26a4b1bd4053f6f47d096997fd"}, + {file = "pillow-10.4.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:930044bb7679ab003b14023138b50181899da3f25de50e9dbee23b61b4de2126"}, + {file = "pillow-10.4.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:c76e5786951e72ed3686e122d14c5d7012f16c8303a674d18cdcd6d89557fc5b"}, + {file = "pillow-10.4.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:b2724fdb354a868ddf9a880cb84d102da914e99119211ef7ecbdc613b8c96b3c"}, + {file = "pillow-10.4.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:dbc6ae66518ab3c5847659e9988c3b60dc94ffb48ef9168656e0019a93dbf8a1"}, + {file = "pillow-10.4.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:06b2f7898047ae93fad74467ec3d28fe84f7831370e3c258afa533f81ef7f3df"}, + {file = "pillow-10.4.0-cp39-cp39-win32.whl", hash = "sha256:7970285ab628a3779aecc35823296a7869f889b8329c16ad5a71e4901a3dc4ef"}, + {file = "pillow-10.4.0-cp39-cp39-win_amd64.whl", hash = "sha256:961a7293b2457b405967af9c77dcaa43cc1a8cd50d23c532e62d48ab6cdd56f5"}, + {file = "pillow-10.4.0-cp39-cp39-win_arm64.whl", hash = "sha256:32cda9e3d601a52baccb2856b8ea1fc213c90b340c542dcef77140dfa3278a9e"}, + {file = "pillow-10.4.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:5b4815f2e65b30f5fbae9dfffa8636d992d49705723fe86a3661806e069352d4"}, + {file = "pillow-10.4.0-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:8f0aef4ef59694b12cadee839e2ba6afeab89c0f39a3adc02ed51d109117b8da"}, + {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9f4727572e2918acaa9077c919cbbeb73bd2b3ebcfe033b72f858fc9fbef0026"}, + {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ff25afb18123cea58a591ea0244b92eb1e61a1fd497bf6d6384f09bc3262ec3e"}, + {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:dc3e2db6ba09ffd7d02ae9141cfa0ae23393ee7687248d46a7507b75d610f4f5"}, + {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:02a2be69f9c9b8c1e97cf2713e789d4e398c751ecfd9967c18d0ce304efbf885"}, + {file = "pillow-10.4.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:0755ffd4a0c6f267cccbae2e9903d95477ca2f77c4fcf3a3a09570001856c8a5"}, + {file = "pillow-10.4.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:a02364621fe369e06200d4a16558e056fe2805d3468350df3aef21e00d26214b"}, + {file = "pillow-10.4.0-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:1b5dea9831a90e9d0721ec417a80d4cbd7022093ac38a568db2dd78363b00908"}, + {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9b885f89040bb8c4a1573566bbb2f44f5c505ef6e74cec7ab9068c900047f04b"}, + {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:87dd88ded2e6d74d31e1e0a99a726a6765cda32d00ba72dc37f0651f306daaa8"}, + {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:2db98790afc70118bd0255c2eeb465e9767ecf1f3c25f9a1abb8ffc8cfd1fe0a"}, + {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:f7baece4ce06bade126fb84b8af1c33439a76d8a6fd818970215e0560ca28c27"}, + {file = "pillow-10.4.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:cfdd747216947628af7b259d274771d84db2268ca062dd5faf373639d00113a3"}, + {file = "pillow-10.4.0.tar.gz", hash = "sha256:166c1cd4d24309b30d61f79f4a9114b7b2313d7450912277855ff5dfd7cd4a06"}, ] [package.extras] -docs = ["furo", "olefile", "sphinx (>=2.4)", "sphinx-copybutton", "sphinx-inline-tabs", "sphinx-removed-in", "sphinxext-opengraph"] +docs = ["furo", "olefile", "sphinx (>=7.3)", "sphinx-copybutton", "sphinx-inline-tabs", "sphinxext-opengraph"] fpx = ["olefile"] mic = ["olefile"] tests = ["check-manifest", "coverage", "defusedxml", "markdown2", "olefile", "packaging", "pyroma", "pytest", "pytest-cov", "pytest-timeout"] @@ -1297,28 +1420,29 @@ xmp = ["defusedxml"] [[package]] name = "platformdirs" -version = "4.2.0" -description = "A small Python package for determining appropriate platform-specific dirs, e.g. a \"user data dir\"." +version = "4.3.6" +description = "A small Python package for determining appropriate platform-specific dirs, e.g. a `user data dir`." optional = false python-versions = ">=3.8" files = [ - {file = "platformdirs-4.2.0-py3-none-any.whl", hash = "sha256:0614df2a2f37e1a662acbd8e2b25b92ccf8632929bc6d43467e17fe89c75e068"}, - {file = "platformdirs-4.2.0.tar.gz", hash = "sha256:ef0cc731df711022c174543cb70a9b5bd22e5a9337c8624ef2c2ceb8ddad8768"}, + {file = "platformdirs-4.3.6-py3-none-any.whl", hash = "sha256:73e575e1408ab8103900836b97580d5307456908a03e92031bab39e4554cc3fb"}, + {file = "platformdirs-4.3.6.tar.gz", hash = "sha256:357fb2acbc885b0419afd3ce3ed34564c13c9b95c89360cd9563f73aa5e2b907"}, ] [package.extras] -docs = ["furo (>=2023.9.10)", "proselint (>=0.13)", "sphinx (>=7.2.6)", "sphinx-autodoc-typehints (>=1.25.2)"] -test = ["appdirs (==1.4.4)", "covdefaults (>=2.3)", "pytest (>=7.4.3)", "pytest-cov (>=4.1)", "pytest-mock (>=3.12)"] +docs = ["furo (>=2024.8.6)", "proselint (>=0.14)", "sphinx (>=8.0.2)", "sphinx-autodoc-typehints (>=2.4)"] +test = ["appdirs (==1.4.4)", "covdefaults (>=2.3)", "pytest (>=8.3.2)", "pytest-cov (>=5)", "pytest-mock (>=3.14)"] +type = ["mypy (>=1.11.2)"] [[package]] name = "pluggy" -version = "1.4.0" +version = "1.5.0" description = "plugin and hook calling mechanisms for python" optional = false python-versions = ">=3.8" files = [ - {file = "pluggy-1.4.0-py3-none-any.whl", hash = "sha256:7db9f7b503d67d1c5b95f59773ebb58a8c1c288129a88665838012cfb07b8981"}, - {file = "pluggy-1.4.0.tar.gz", hash = "sha256:8c85c2876142a764e5b7548e7d9a0e0ddb46f5185161049a79b7e974454223be"}, + {file = "pluggy-1.5.0-py3-none-any.whl", hash = "sha256:44e1ad92c8ca002de6377e165f3e0f1be63266ab4d554740532335b9d75ea669"}, + {file = "pluggy-1.5.0.tar.gz", hash = "sha256:2cffa88e94fdc978c4c574f15f9e59b7f4201d439195c3715ca9e2486f1d0cf1"}, ] [package.extras] @@ -1327,13 +1451,13 @@ testing = ["pytest", "pytest-benchmark"] [[package]] name = "prompt-toolkit" -version = "3.0.43" +version = "3.0.47" description = "Library for building powerful interactive command lines in Python" optional = false python-versions = ">=3.7.0" files = [ - {file = "prompt_toolkit-3.0.43-py3-none-any.whl", hash = "sha256:a11a29cb3bf0a28a387fe5122cdb649816a957cd9261dcedf8c9f1fef33eacf6"}, - {file = "prompt_toolkit-3.0.43.tar.gz", hash = "sha256:3527b7af26106cbc65a040bcc84839a3566ec1b051bb0bfe953631e704b0ff7d"}, + {file = "prompt_toolkit-3.0.47-py3-none-any.whl", hash = "sha256:0d7bfa67001d5e39d02c224b663abc33687405033a8c422d0d675a5a13361d10"}, + {file = "prompt_toolkit-3.0.47.tar.gz", hash = "sha256:1e1b29cb58080b1e69f207c893a1a7bf16d127a5c30c9d17a25a5d77792e5360"}, ] [package.dependencies] @@ -1341,27 +1465,28 @@ wcwidth = "*" [[package]] name = "psutil" -version = "5.9.8" +version = "6.0.0" description = "Cross-platform lib for process and system monitoring in Python." optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*, !=3.5.*" -files = [ - {file = "psutil-5.9.8-cp27-cp27m-macosx_10_9_x86_64.whl", hash = "sha256:26bd09967ae00920df88e0352a91cff1a78f8d69b3ecabbfe733610c0af486c8"}, - {file = "psutil-5.9.8-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:05806de88103b25903dff19bb6692bd2e714ccf9e668d050d144012055cbca73"}, - {file = "psutil-5.9.8-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:611052c4bc70432ec770d5d54f64206aa7203a101ec273a0cd82418c86503bb7"}, - {file = "psutil-5.9.8-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:50187900d73c1381ba1454cf40308c2bf6f34268518b3f36a9b663ca87e65e36"}, - {file = "psutil-5.9.8-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:02615ed8c5ea222323408ceba16c60e99c3f91639b07da6373fb7e6539abc56d"}, - {file = "psutil-5.9.8-cp27-none-win32.whl", hash = "sha256:36f435891adb138ed3c9e58c6af3e2e6ca9ac2f365efe1f9cfef2794e6c93b4e"}, - {file = "psutil-5.9.8-cp27-none-win_amd64.whl", hash = "sha256:bd1184ceb3f87651a67b2708d4c3338e9b10c5df903f2e3776b62303b26cb631"}, - {file = "psutil-5.9.8-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:aee678c8720623dc456fa20659af736241f575d79429a0e5e9cf88ae0605cc81"}, - {file = "psutil-5.9.8-cp36-abi3-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8cb6403ce6d8e047495a701dc7c5bd788add903f8986d523e3e20b98b733e421"}, - {file = "psutil-5.9.8-cp36-abi3-manylinux_2_12_x86_64.manylinux2010_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d06016f7f8625a1825ba3732081d77c94589dca78b7a3fc072194851e88461a4"}, - {file = "psutil-5.9.8-cp36-cp36m-win32.whl", hash = "sha256:7d79560ad97af658a0f6adfef8b834b53f64746d45b403f225b85c5c2c140eee"}, - {file = "psutil-5.9.8-cp36-cp36m-win_amd64.whl", hash = "sha256:27cc40c3493bb10de1be4b3f07cae4c010ce715290a5be22b98493509c6299e2"}, - {file = "psutil-5.9.8-cp37-abi3-win32.whl", hash = "sha256:bc56c2a1b0d15aa3eaa5a60c9f3f8e3e565303b465dbf57a1b730e7a2b9844e0"}, - {file = "psutil-5.9.8-cp37-abi3-win_amd64.whl", hash = "sha256:8db4c1b57507eef143a15a6884ca10f7c73876cdf5d51e713151c1236a0e68cf"}, - {file = "psutil-5.9.8-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:d16bbddf0693323b8c6123dd804100241da461e41d6e332fb0ba6058f630f8c8"}, - {file = "psutil-5.9.8.tar.gz", hash = "sha256:6be126e3225486dff286a8fb9a06246a5253f4c7c53b475ea5f5ac934e64194c"}, +python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,>=2.7" +files = [ + {file = "psutil-6.0.0-cp27-cp27m-macosx_10_9_x86_64.whl", hash = "sha256:a021da3e881cd935e64a3d0a20983bda0bb4cf80e4f74fa9bfcb1bc5785360c6"}, + {file = "psutil-6.0.0-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:1287c2b95f1c0a364d23bc6f2ea2365a8d4d9b726a3be7294296ff7ba97c17f0"}, + {file = "psutil-6.0.0-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:a9a3dbfb4de4f18174528d87cc352d1f788b7496991cca33c6996f40c9e3c92c"}, + {file = "psutil-6.0.0-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:6ec7588fb3ddaec7344a825afe298db83fe01bfaaab39155fa84cf1c0d6b13c3"}, + {file = "psutil-6.0.0-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:1e7c870afcb7d91fdea2b37c24aeb08f98b6d67257a5cb0a8bc3ac68d0f1a68c"}, + {file = "psutil-6.0.0-cp27-none-win32.whl", hash = "sha256:02b69001f44cc73c1c5279d02b30a817e339ceb258ad75997325e0e6169d8b35"}, + {file = "psutil-6.0.0-cp27-none-win_amd64.whl", hash = "sha256:21f1fb635deccd510f69f485b87433460a603919b45e2a324ad65b0cc74f8fb1"}, + {file = "psutil-6.0.0-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:c588a7e9b1173b6e866756dde596fd4cad94f9399daf99ad8c3258b3cb2b47a0"}, + {file = "psutil-6.0.0-cp36-abi3-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6ed2440ada7ef7d0d608f20ad89a04ec47d2d3ab7190896cd62ca5fc4fe08bf0"}, + {file = "psutil-6.0.0-cp36-abi3-manylinux_2_12_x86_64.manylinux2010_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5fd9a97c8e94059b0ef54a7d4baf13b405011176c3b6ff257c247cae0d560ecd"}, + {file = "psutil-6.0.0-cp36-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e2e8d0054fc88153ca0544f5c4d554d42e33df2e009c4ff42284ac9ebdef4132"}, + {file = "psutil-6.0.0-cp36-cp36m-win32.whl", hash = "sha256:fc8c9510cde0146432bbdb433322861ee8c3efbf8589865c8bf8d21cb30c4d14"}, + {file = "psutil-6.0.0-cp36-cp36m-win_amd64.whl", hash = "sha256:34859b8d8f423b86e4385ff3665d3f4d94be3cdf48221fbe476e883514fdb71c"}, + {file = "psutil-6.0.0-cp37-abi3-win32.whl", hash = "sha256:a495580d6bae27291324fe60cea0b5a7c23fa36a7cd35035a16d93bdcf076b9d"}, + {file = "psutil-6.0.0-cp37-abi3-win_amd64.whl", hash = "sha256:33ea5e1c975250a720b3a6609c490db40dae5d83a4eb315170c4fe0d8b1f34b3"}, + {file = "psutil-6.0.0-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:ffe7fc9b6b36beadc8c322f84e1caff51e8703b88eee1da46d1e3a6ae11b4fd0"}, + {file = "psutil-6.0.0.tar.gz", hash = "sha256:8faae4f310b6d969fa26ca0545338b21f73c6b15db7c4a8d934a5482faa818f2"}, ] [package.extras] @@ -1380,13 +1505,13 @@ files = [ [[package]] name = "pure-eval" -version = "0.2.2" +version = "0.2.3" description = "Safely evaluate AST nodes without side effects" optional = false python-versions = "*" files = [ - {file = "pure_eval-0.2.2-py3-none-any.whl", hash = "sha256:01eaab343580944bc56080ebe0a674b39ec44a945e6d09ba7db3cb8cec289350"}, - {file = "pure_eval-0.2.2.tar.gz", hash = "sha256:2b45320af6dfaa1750f543d714b6d1c520a1688dec6fd24d339063ce0aaa9ac3"}, + {file = "pure_eval-0.2.3-py3-none-any.whl", hash = "sha256:1db8e35b67b3d218d818ae653e27f06c3aa420901fa7b081ca98cbedc874e0d0"}, + {file = "pure_eval-0.2.3.tar.gz", hash = "sha256:5f4e983f40564c576c7c8635ae88db5956bb2229d7e9237d03b3c0b0190eaf42"}, ] [package.extras] @@ -1394,24 +1519,24 @@ tests = ["pytest"] [[package]] name = "pycodestyle" -version = "2.11.1" +version = "2.12.1" description = "Python style guide checker" optional = false python-versions = ">=3.8" files = [ - {file = "pycodestyle-2.11.1-py2.py3-none-any.whl", hash = "sha256:44fe31000b2d866f2e41841b18528a505fbd7fef9017b04eff4e2648a0fadc67"}, - {file = "pycodestyle-2.11.1.tar.gz", hash = "sha256:41ba0e7afc9752dfb53ced5489e89f8186be00e599e712660695b7a75ff2663f"}, + {file = "pycodestyle-2.12.1-py2.py3-none-any.whl", hash = "sha256:46f0fb92069a7c28ab7bb558f05bfc0110dac69a0cd23c61ea0040283a9d78b3"}, + {file = "pycodestyle-2.12.1.tar.gz", hash = "sha256:6838eae08bbce4f6accd5d5572075c63626a15ee3e6f842df996bf62f6d73521"}, ] [[package]] name = "pycparser" -version = "2.21" +version = "2.22" description = "C parser in Python" optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" +python-versions = ">=3.8" files = [ - {file = "pycparser-2.21-py2.py3-none-any.whl", hash = "sha256:8ee45429555515e1f6b185e78100aea234072576aa43ab53aefcae078162fca9"}, - {file = "pycparser-2.21.tar.gz", hash = "sha256:e644fdec12f7872f86c58ff790da456218b10f863970249516d60a5eaca77206"}, + {file = "pycparser-2.22-py3-none-any.whl", hash = "sha256:c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc"}, + {file = "pycparser-2.22.tar.gz", hash = "sha256:491c8be9c040f5390f5bf44a5b07752bd07f56edf992381b05c701439eec10f6"}, ] [[package]] @@ -1427,94 +1552,93 @@ files = [ [[package]] name = "pygame" -version = "2.5.2" +version = "2.6.0" description = "Python Game Development" optional = false python-versions = ">=3.6" files = [ - {file = "pygame-2.5.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:a0769eb628c818761755eb0a0ca8216b95270ea8cbcbc82227e39ac9644643da"}, - {file = "pygame-2.5.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ed9a3d98adafa0805ccbaaff5d2996a2b5795381285d8437a4a5d248dbd12b4a"}, - {file = "pygame-2.5.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f30d1618672a55e8c6669281ba264464b3ab563158e40d89e8c8b3faa0febebd"}, - {file = "pygame-2.5.2-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:39690e9be9baf58b7359d1f3b2336e1fd6f92fedbbce42987be5df27f8d30718"}, - {file = "pygame-2.5.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:03879ec299c9f4ba23901b2649a96b2143f0a5d787f0b6c39469989e2320caf1"}, - {file = "pygame-2.5.2-cp310-cp310-win32.whl", hash = "sha256:74e1d6284100e294f445832e6f6343be4fe4748decc4f8a51131ae197dae8584"}, - {file = "pygame-2.5.2-cp310-cp310-win_amd64.whl", hash = "sha256:485239c7d32265fd35b76ae8f64f34b0637ae11e69d76de15710c4b9edcc7c8d"}, - {file = "pygame-2.5.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:34646ca20e163dc6f6cf8170f1e12a2e41726780112594ac061fa448cf7ccd75"}, - {file = "pygame-2.5.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:3b8a6e351665ed26ea791f0e1fd649d3f483e8681892caef9d471f488f9ea5ee"}, - {file = "pygame-2.5.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dc346965847aef00013fa2364f41a64f068cd096dcc7778fc306ca3735f0eedf"}, - {file = "pygame-2.5.2-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:35632035fd81261f2d797fa810ea8c46111bd78ceb6089d52b61ed7dc3c5d05f"}, - {file = "pygame-2.5.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0e24d05184e4195fe5ebcdce8b18ecb086f00182b9ae460a86682d312ce8d31f"}, - {file = "pygame-2.5.2-cp311-cp311-win32.whl", hash = "sha256:f02c1c7505af18d426d355ac9872bd5c916b27f7b0fe224749930662bea47a50"}, - {file = "pygame-2.5.2-cp311-cp311-win_amd64.whl", hash = "sha256:6d58c8cf937815d3b7cdc0fa9590c5129cb2c9658b72d00e8a4568dea2ff1d42"}, - {file = "pygame-2.5.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:1a2a43802bb5e89ce2b3b775744e78db4f9a201bf8d059b946c61722840ceea8"}, - {file = "pygame-2.5.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:1c289f2613c44fe70a1e40769de4a49c5ab5a29b9376f1692bb1a15c9c1c9bfa"}, - {file = "pygame-2.5.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:074aa6c6e110c925f7f27f00c7733c6303407edc61d738882985091d1eb2ef17"}, - {file = "pygame-2.5.2-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fe0228501ec616779a0b9c4299e837877783e18df294dd690b9ab0eed3d8aaab"}, - {file = "pygame-2.5.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:31648d38ecdc2335ffc0e38fb18a84b3339730521505dac68514f83a1092e3f4"}, - {file = "pygame-2.5.2-cp312-cp312-win32.whl", hash = "sha256:224c308856334bc792f696e9278e50d099a87c116f7fc314cd6aa3ff99d21592"}, - {file = "pygame-2.5.2-cp312-cp312-win_amd64.whl", hash = "sha256:dd2d2650faf54f9a0f5bd0db8409f79609319725f8f08af6507a0609deadcad4"}, - {file = "pygame-2.5.2-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:9b30bc1220c457169571aac998e54b013aaeb732d2fd8744966cb1cfab1f61d1"}, - {file = "pygame-2.5.2-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:78fcd7643358b886a44127ff7dec9041c056c212b3a98977674f83f99e9b12d3"}, - {file = "pygame-2.5.2-cp36-cp36m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:35cf093a51cb294ede56c29d4acf41538c00f297fcf78a9b186fb7d23c0577b6"}, - {file = "pygame-2.5.2-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6fe323acbf53a0195c8c98b1b941eba7ac24e3e2b28ae48e8cda566f15fc4945"}, - {file = "pygame-2.5.2-cp36-cp36m-win32.whl", hash = "sha256:5697528266b4716d9cdd44a5a1d210f4d86ef801d0f64ca5da5d0816704009d9"}, - {file = "pygame-2.5.2-cp36-cp36m-win_amd64.whl", hash = "sha256:edda1f7cff4806a4fa39e0e8ccd75f38d1d340fa5fc52d8582ade87aca247d92"}, - {file = "pygame-2.5.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:9bd738fd4ecc224769d0b4a719f96900a86578e26e0105193658a32966df2aae"}, - {file = "pygame-2.5.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:30a8d7cf12363b4140bf2f93b5eec4028376ca1d0fe4b550588f836279485308"}, - {file = "pygame-2.5.2-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bc12e4dea3e88ea8a553de6d56a37b704dbe2aed95105889f6afeb4b96e62097"}, - {file = "pygame-2.5.2-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2b34c73cb328024f8db3cb6487a37e54000148988275d8d6e5adf99d9323c937"}, - {file = "pygame-2.5.2-cp37-cp37m-win32.whl", hash = "sha256:7d0a2794649defa57ef50b096a99f7113d3d0c2e32d1426cafa7d618eadce4c7"}, - {file = "pygame-2.5.2-cp37-cp37m-win_amd64.whl", hash = "sha256:41f8779f52e0f6e6e6ccb8f0b5536e432bf386ee29c721a1c22cada7767b0cef"}, - {file = "pygame-2.5.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:677e37bc0ea7afd89dde5a88ced4458aa8656159c70a576eea68b5622ee1997b"}, - {file = "pygame-2.5.2-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:47a8415d2bd60e6909823b5643a1d4ef5cc29417d817f2a214b255f6fa3a1e4c"}, - {file = "pygame-2.5.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4ff21201df6278b8ca2e948fb148ffe88f5481fd03760f381dd61e45954c7dff"}, - {file = "pygame-2.5.2-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d29a84b2e02814b9ba925357fd2e1df78efe5e1aa64dc3051eaed95d2b96eafd"}, - {file = "pygame-2.5.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d78485c4d21133d6b2fbb504cd544ca655e50b6eb551d2995b3aa6035928adda"}, - {file = "pygame-2.5.2-cp38-cp38-win32.whl", hash = "sha256:d851247239548aa357c4a6840fb67adc2d570ce7cb56988d036a723d26b48bff"}, - {file = "pygame-2.5.2-cp38-cp38-win_amd64.whl", hash = "sha256:88d1cdacc2d3471eceab98bf0c93c14d3a8461f93e58e3d926f20d4de3a75554"}, - {file = "pygame-2.5.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:4f1559e7efe4efb9dc19d2d811d702f325d9605f9f6f9ececa39ee6890c798f5"}, - {file = "pygame-2.5.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:cf2191b756ceb0e8458a761d0c665b0c70b538570449e0d39b75a5ba94ac5cf0"}, - {file = "pygame-2.5.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6cf2257447ce7f2d6de37e5fb019d2bbe32ed05a5721ace8bc78c2d9beaf3aee"}, - {file = "pygame-2.5.2-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d75cbbfaba2b81434d62631d0b08b85fab16cf4a36e40b80298d3868927e1299"}, - {file = "pygame-2.5.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:daca456d5b9f52e088e06a127dec182b3638a775684fb2260f25d664351cf1ae"}, - {file = "pygame-2.5.2-cp39-cp39-win32.whl", hash = "sha256:3b3e619e33d11c297d7a57a82db40681f9c2c3ae1d5bf06003520b4fe30c435d"}, - {file = "pygame-2.5.2-cp39-cp39-win_amd64.whl", hash = "sha256:1822d534bb7fe756804647b6da2c9ea5d7a62d8796b2e15d172d3be085de28c6"}, - {file = "pygame-2.5.2-pp36-pypy36_pp73-win32.whl", hash = "sha256:e708fc8f709a0fe1d1876489345f2e443d47f3976d33455e2e1e937f972f8677"}, - {file = "pygame-2.5.2-pp37-pypy37_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c13edebc43c240fb0532969e914f0ccefff5ae7e50b0b788d08ad2c15ef793e4"}, - {file = "pygame-2.5.2-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:263b4a7cbfc9fe2055abc21b0251cc17dea6dff750f0e1c598919ff350cdbffe"}, - {file = "pygame-2.5.2-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:e58e2b0c791041e4bccafa5bd7650623ba1592b8fe62ae0a276b7d0ecb314b6c"}, - {file = "pygame-2.5.2-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a0bd67426c02ffe6c9827fc4bcbda9442fbc451d29b17c83a3c088c56fef2c90"}, - {file = "pygame-2.5.2-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9dcff6cbba1584cf7732ce1dbdd044406cd4f6e296d13bcb7fba963fb4aeefc9"}, - {file = "pygame-2.5.2-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:ce4b6c0bfe44d00bb0998a6517bd0cf9455f642f30f91bc671ad41c05bf6f6ae"}, - {file = "pygame-2.5.2-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:68c4e8e60b725ffc7a6c6ecd9bb5fcc5ed2d6e0e2a2c4a29a8454856ef16ad63"}, - {file = "pygame-2.5.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1f3849f97372a3381c66955f99a0d58485ccd513c3d00c030b869094ce6997a6"}, - {file = "pygame-2.5.2.tar.gz", hash = "sha256:c1b89eb5d539e7ac5cf75513125fb5f2f0a2d918b1fd6e981f23bf0ac1b1c24a"}, + {file = "pygame-2.6.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:e5707aa9d029752495b3eddc1edff62e0e390a02f699b0f1ce77fe0b8c70ea4f"}, + {file = "pygame-2.6.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:d3ed0547368733b854c0d9981c982a3cdfabfa01b477d095c57bf47f2199da44"}, + {file = "pygame-2.6.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6050f3e95f1f16602153d616b52619c6a2041cee7040eb529f65689e9633fc3e"}, + {file = "pygame-2.6.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:89be55b7e9e22e0eea08af9d6cfb97aed5da780f0b3a035803437d481a16d972"}, + {file = "pygame-2.6.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7d65fb222eea1294cfc8206d9e5754d476a1673eb2783c03c4f70e0455320274"}, + {file = "pygame-2.6.0-cp310-cp310-win32.whl", hash = "sha256:71eebb9803cb350298de188fb7cdd3ebf13299f78d59a71c7e81efc649aae348"}, + {file = "pygame-2.6.0-cp310-cp310-win_amd64.whl", hash = "sha256:1551852a2cd5b4139a752888f6cbeeb4a96fc0fe6e6f3f8b9d9784eb8fceab13"}, + {file = "pygame-2.6.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:f6e5e6c010b1bf429388acf4d41d7ab2f7ad8fbf241d0db822102d35c9a2eb84"}, + {file = "pygame-2.6.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:99902f4a2f6a338057200d99b5120a600c27a9f629ca012a9b0087c045508d08"}, + {file = "pygame-2.6.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6a284664978a1989c1e31a0888b2f70cfbcbafdfa3bb310e750b0d3366416225"}, + {file = "pygame-2.6.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:829623cee298b3dbaa1dd9f52c3051ae82f04cad7708c8c67cb9a1a4b8fd3c0b"}, + {file = "pygame-2.6.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6acf7949ed764487d51123f4f3606e8f76b0df167fef12ef73ef423c35fdea39"}, + {file = "pygame-2.6.0-cp311-cp311-win32.whl", hash = "sha256:3f809560c99bd1fb4716610eca0cd36412528f03da1a63841a347b71d0c604ee"}, + {file = "pygame-2.6.0-cp311-cp311-win_amd64.whl", hash = "sha256:6897ab87f9193510a774a3483e00debfe166f340ca159f544ef99807e2a44ec4"}, + {file = "pygame-2.6.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:b834711ebc8b9d0c2a5f9bfae4403dd277b2c61bcb689e1aa630d01a1ebcf40a"}, + {file = "pygame-2.6.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b5ac288655e8a31a303cc286e79cc57979ed2ba19c3a14042d4b6391c1d3bed2"}, + {file = "pygame-2.6.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d666667b7826b0a7921b8ce0a282ba5281dfa106976c1a3b24e32a0af65ad3b1"}, + {file = "pygame-2.6.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fd8848a37a7cee37854c7efb8d451334477c9f8ce7ac339c079e724dc1334a76"}, + {file = "pygame-2.6.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:315e7b3c1c573984f549ac5da9778ac4709b3b4e3a4061050d94eab63fa4fe31"}, + {file = "pygame-2.6.0-cp312-cp312-win32.whl", hash = "sha256:e44bde0840cc21a91c9d368846ac538d106cf0668be1a6030f48df139609d1e8"}, + {file = "pygame-2.6.0-cp312-cp312-win_amd64.whl", hash = "sha256:1c429824b1f881a7a5ce3b5c2014d3d182aa45a22cea33c8347a3971a5446907"}, + {file = "pygame-2.6.0-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:b832200bd8b6fc485e087bf3ef7ec1a21437258536413a5386088f5dcd3a9870"}, + {file = "pygame-2.6.0-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:098029d01a46ea4e30620dfb7c28a577070b456c8fc96350dde05f85c0bf51b5"}, + {file = "pygame-2.6.0-cp36-cp36m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a858bbdeac5ec473ec9e726c55fb8fbdc2f4aad7c55110e899883738071c7c9b"}, + {file = "pygame-2.6.0-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6f908762941fd99e1f66d1211d26383184f6045c45673443138b214bf48a89aa"}, + {file = "pygame-2.6.0-cp36-cp36m-win32.whl", hash = "sha256:4a63daee99d050f47d6ec7fa7dbd1c6597b8f082cdd58b6918d382d2bc31262d"}, + {file = "pygame-2.6.0-cp36-cp36m-win_amd64.whl", hash = "sha256:ace471b3849d68968e5427fc01166ef5afaf552a5c442fc2c28d3b7226786f55"}, + {file = "pygame-2.6.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:fea019713d0c89dfd5909225aa933010100035d1cd30e6c936e8b6f00529fb80"}, + {file = "pygame-2.6.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:249dbf2d51d9f0266009a380ccf0532e1a57614a1528bb2f89a802b01d61f93e"}, + {file = "pygame-2.6.0-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8cb51533ee3204e8160600b0de34eaad70eb913a182c94a7777b6051e8fc52f1"}, + {file = "pygame-2.6.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4f637636a44712e94e5601ec69160a080214626471983dfb0b5b68aa0c61563d"}, + {file = "pygame-2.6.0-cp37-cp37m-win32.whl", hash = "sha256:e432156b6f346f4cc6cab03ce9657600093390f4c9b10bf458716b25beebfe33"}, + {file = "pygame-2.6.0-cp37-cp37m-win_amd64.whl", hash = "sha256:a0194652db7874bdde7dfc69d659ca954544c012e04ae527151325bfb970f423"}, + {file = "pygame-2.6.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:eae3ee62cc172e268121d5bd9dc406a67094d33517de3a91de3323d6ae23eb02"}, + {file = "pygame-2.6.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:f6a58b0a5a8740a3c2cf6fc5366888bd4514561253437f093c12a9ab4fb3ecae"}, + {file = "pygame-2.6.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c71da36997dc7b9b4ee973fa3a5d4a6cfb2149161b5b1c08b712d2f13a63ccfe"}, + {file = "pygame-2.6.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b86771801a7fc10d9a62218f27f1d5c13341c3a27394aa25578443a9cd199830"}, + {file = "pygame-2.6.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4928f3acf5a9ce5fbab384c21f1245304535ffd5fb167ae92a6b4d3cdb55a3b6"}, + {file = "pygame-2.6.0-cp38-cp38-win32.whl", hash = "sha256:4faab2df9926c4d31215986536b112f0d76f711cf02f395805f1ff5df8fd55fc"}, + {file = "pygame-2.6.0-cp38-cp38-win_amd64.whl", hash = "sha256:afbb8d97aed93dfb116fe105603dacb68f8dab05b978a40a9e4ab1b6c1f683fd"}, + {file = "pygame-2.6.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:d11f3646b53819892f4a731e80b8589a9140343d0d4b86b826802191b241228c"}, + {file = "pygame-2.6.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:5ef92ed93c354eabff4b85e457d4d6980115004ec7ff52a19fd38b929c3b80fb"}, + {file = "pygame-2.6.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9bc1795f2e36302882546faacd5a0191463c4f4ae2b90e7c334a7733aa4190d2"}, + {file = "pygame-2.6.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e92294fcc85c4955fe5bc6a0404e4cc870808005dc8f359e881544e3cc214108"}, + {file = "pygame-2.6.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c0cb7bdf3ee0233a3ac02ef777c01dfe315e6d4670f1312c83b91c1ef124359a"}, + {file = "pygame-2.6.0-cp39-cp39-win32.whl", hash = "sha256:ac906478ae489bb837bf6d2ae1eb9261d658aa2c34fa5b283027a04149bda81a"}, + {file = "pygame-2.6.0-cp39-cp39-win_amd64.whl", hash = "sha256:92cf12a9722f6f0bdc5520d8925a8f085cff9c054a2ea462fc409cba3781be27"}, + {file = "pygame-2.6.0-pp36-pypy36_pp73-win32.whl", hash = "sha256:a6636f452fdaddf604a060849feb84c056930b6a3c036214f607741f16aac942"}, + {file = "pygame-2.6.0-pp37-pypy37_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3dc242dc15d067d10f25c5b12a1da48ca9436d8e2d72353eaf757e83612fba2f"}, + {file = "pygame-2.6.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f82df23598a281c8c342d3c90be213c8fe762a26c15815511f60d0aac6e03a70"}, + {file = "pygame-2.6.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:2ed2539bb6bd211fc570b1169dc4a64a74ec5cd95741e62a0ab46bd18fe08e0d"}, + {file = "pygame-2.6.0-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:904aaf29710c6b03a7e1a65b198f5467ed6525e8e60bdcc5e90ff8584c1d54ea"}, + {file = "pygame-2.6.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fcd28f96f0fffd28e71a98773843074597e10d7f55a098e2e5bcb2bef1bdcbf5"}, + {file = "pygame-2.6.0-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:4fad1ab33443ecd4f958dbbb67fc09fcdc7a37e26c34054e3296fb7e26ad641e"}, + {file = "pygame-2.6.0-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e909186d4d512add39b662904f0f79b73028fbfc4fbfdaf6f9412aed4e500e9c"}, + {file = "pygame-2.6.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:79abcbf6d12fce51a955a0652ccd50b6d0a355baa27799535eaf21efb43433dd"}, + {file = "pygame-2.6.0.tar.gz", hash = "sha256:722d33ae676aa8533c1f955eded966411298831346b8d51a77dad22e46ba3e35"}, ] [[package]] name = "pygments" -version = "2.17.2" +version = "2.18.0" description = "Pygments is a syntax highlighting package written in Python." optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "pygments-2.17.2-py3-none-any.whl", hash = "sha256:b27c2826c47d0f3219f29554824c30c5e8945175d888647acd804ddd04af846c"}, - {file = "pygments-2.17.2.tar.gz", hash = "sha256:da46cec9fd2de5be3a8a784f434e4c4ab670b4ff54d605c4c2717e9d49c4c367"}, + {file = "pygments-2.18.0-py3-none-any.whl", hash = "sha256:b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a"}, + {file = "pygments-2.18.0.tar.gz", hash = "sha256:786ff802f32e91311bff3889f6e9a86e81505fe99f2735bb6d60ae0c5004f199"}, ] [package.extras] -plugins = ["importlib-metadata"] windows-terminal = ["colorama (>=0.4.6)"] [[package]] name = "pyparsing" -version = "3.1.1" +version = "3.1.4" description = "pyparsing module - Classes and methods to define and execute parsing grammars" optional = false python-versions = ">=3.6.8" files = [ - {file = "pyparsing-3.1.1-py3-none-any.whl", hash = "sha256:32c7c0b711493c72ff18a981d24f28aaf9c1fb7ed5e9667c9e84e3db623bdbfb"}, - {file = "pyparsing-3.1.1.tar.gz", hash = "sha256:ede28a1a32462f5a9705e07aea48001a08f7cf81a021585011deba701581a0db"}, + {file = "pyparsing-3.1.4-py3-none-any.whl", hash = "sha256:a6a7ee4235a3f944aa1fa2249307708f893fe5717dc603503c6c7969c070fb7c"}, + {file = "pyparsing-3.1.4.tar.gz", hash = "sha256:f86ec8d1a83f11977c9a6ea7598e8c27fc5cddfa5b07ea2241edbbde1d7bc032"}, ] [package.extras] @@ -1581,164 +1705,182 @@ files = [ [[package]] name = "pyyaml" -version = "6.0.1" +version = "6.0.2" description = "YAML parser and emitter for Python" optional = false -python-versions = ">=3.6" +python-versions = ">=3.8" files = [ - {file = "PyYAML-6.0.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:d858aa552c999bc8a8d57426ed01e40bef403cd8ccdd0fc5f6f04a00414cac2a"}, - {file = "PyYAML-6.0.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:fd66fc5d0da6d9815ba2cebeb4205f95818ff4b79c3ebe268e75d961704af52f"}, - {file = "PyYAML-6.0.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:69b023b2b4daa7548bcfbd4aa3da05b3a74b772db9e23b982788168117739938"}, - {file = "PyYAML-6.0.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:81e0b275a9ecc9c0c0c07b4b90ba548307583c125f54d5b6946cfee6360c733d"}, - {file = "PyYAML-6.0.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ba336e390cd8e4d1739f42dfe9bb83a3cc2e80f567d8805e11b46f4a943f5515"}, - {file = "PyYAML-6.0.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:326c013efe8048858a6d312ddd31d56e468118ad4cdeda36c719bf5bb6192290"}, - {file = "PyYAML-6.0.1-cp310-cp310-win32.whl", hash = "sha256:bd4af7373a854424dabd882decdc5579653d7868b8fb26dc7d0e99f823aa5924"}, - {file = "PyYAML-6.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:fd1592b3fdf65fff2ad0004b5e363300ef59ced41c2e6b3a99d4089fa8c5435d"}, - {file = "PyYAML-6.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6965a7bc3cf88e5a1c3bd2e0b5c22f8d677dc88a455344035f03399034eb3007"}, - {file = "PyYAML-6.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f003ed9ad21d6a4713f0a9b5a7a0a79e08dd0f221aff4525a2be4c346ee60aab"}, - {file = "PyYAML-6.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:42f8152b8dbc4fe7d96729ec2b99c7097d656dc1213a3229ca5383f973a5ed6d"}, - {file = "PyYAML-6.0.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:062582fca9fabdd2c8b54a3ef1c978d786e0f6b3a1510e0ac93ef59e0ddae2bc"}, - {file = "PyYAML-6.0.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d2b04aac4d386b172d5b9692e2d2da8de7bfb6c387fa4f801fbf6fb2e6ba4673"}, - {file = "PyYAML-6.0.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e7d73685e87afe9f3b36c799222440d6cf362062f78be1013661b00c5c6f678b"}, - {file = "PyYAML-6.0.1-cp311-cp311-win32.whl", hash = "sha256:1635fd110e8d85d55237ab316b5b011de701ea0f29d07611174a1b42f1444741"}, - {file = "PyYAML-6.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:bf07ee2fef7014951eeb99f56f39c9bb4af143d8aa3c21b1677805985307da34"}, - {file = "PyYAML-6.0.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:855fb52b0dc35af121542a76b9a84f8d1cd886ea97c84703eaa6d88e37a2ad28"}, - {file = "PyYAML-6.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:40df9b996c2b73138957fe23a16a4f0ba614f4c0efce1e9406a184b6d07fa3a9"}, - {file = "PyYAML-6.0.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a08c6f0fe150303c1c6b71ebcd7213c2858041a7e01975da3a99aed1e7a378ef"}, - {file = "PyYAML-6.0.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6c22bec3fbe2524cde73d7ada88f6566758a8f7227bfbf93a408a9d86bcc12a0"}, - {file = "PyYAML-6.0.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8d4e9c88387b0f5c7d5f281e55304de64cf7f9c0021a3525bd3b1c542da3b0e4"}, - {file = "PyYAML-6.0.1-cp312-cp312-win32.whl", hash = "sha256:d483d2cdf104e7c9fa60c544d92981f12ad66a457afae824d146093b8c294c54"}, - {file = "PyYAML-6.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:0d3304d8c0adc42be59c5f8a4d9e3d7379e6955ad754aa9d6ab7a398b59dd1df"}, - {file = "PyYAML-6.0.1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:50550eb667afee136e9a77d6dc71ae76a44df8b3e51e41b77f6de2932bfe0f47"}, - {file = "PyYAML-6.0.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1fe35611261b29bd1de0070f0b2f47cb6ff71fa6595c077e42bd0c419fa27b98"}, - {file = "PyYAML-6.0.1-cp36-cp36m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:704219a11b772aea0d8ecd7058d0082713c3562b4e271b849ad7dc4a5c90c13c"}, - {file = "PyYAML-6.0.1-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:afd7e57eddb1a54f0f1a974bc4391af8bcce0b444685d936840f125cf046d5bd"}, - {file = "PyYAML-6.0.1-cp36-cp36m-win32.whl", hash = "sha256:fca0e3a251908a499833aa292323f32437106001d436eca0e6e7833256674585"}, - {file = "PyYAML-6.0.1-cp36-cp36m-win_amd64.whl", hash = "sha256:f22ac1c3cac4dbc50079e965eba2c1058622631e526bd9afd45fedd49ba781fa"}, - {file = "PyYAML-6.0.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:b1275ad35a5d18c62a7220633c913e1b42d44b46ee12554e5fd39c70a243d6a3"}, - {file = "PyYAML-6.0.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:18aeb1bf9a78867dc38b259769503436b7c72f7a1f1f4c93ff9a17de54319b27"}, - {file = "PyYAML-6.0.1-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:596106435fa6ad000c2991a98fa58eeb8656ef2325d7e158344fb33864ed87e3"}, - {file = "PyYAML-6.0.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:baa90d3f661d43131ca170712d903e6295d1f7a0f595074f151c0aed377c9b9c"}, - {file = "PyYAML-6.0.1-cp37-cp37m-win32.whl", hash = "sha256:9046c58c4395dff28dd494285c82ba00b546adfc7ef001486fbf0324bc174fba"}, - {file = "PyYAML-6.0.1-cp37-cp37m-win_amd64.whl", hash = "sha256:4fb147e7a67ef577a588a0e2c17b6db51dda102c71de36f8549b6816a96e1867"}, - {file = "PyYAML-6.0.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:1d4c7e777c441b20e32f52bd377e0c409713e8bb1386e1099c2415f26e479595"}, - {file = "PyYAML-6.0.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a0cd17c15d3bb3fa06978b4e8958dcdc6e0174ccea823003a106c7d4d7899ac5"}, - {file = "PyYAML-6.0.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:28c119d996beec18c05208a8bd78cbe4007878c6dd15091efb73a30e90539696"}, - {file = "PyYAML-6.0.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7e07cbde391ba96ab58e532ff4803f79c4129397514e1413a7dc761ccd755735"}, - {file = "PyYAML-6.0.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:49a183be227561de579b4a36efbb21b3eab9651dd81b1858589f796549873dd6"}, - {file = "PyYAML-6.0.1-cp38-cp38-win32.whl", hash = "sha256:184c5108a2aca3c5b3d3bf9395d50893a7ab82a38004c8f61c258d4428e80206"}, - {file = "PyYAML-6.0.1-cp38-cp38-win_amd64.whl", hash = "sha256:1e2722cc9fbb45d9b87631ac70924c11d3a401b2d7f410cc0e3bbf249f2dca62"}, - {file = "PyYAML-6.0.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:9eb6caa9a297fc2c2fb8862bc5370d0303ddba53ba97e71f08023b6cd73d16a8"}, - {file = "PyYAML-6.0.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:c8098ddcc2a85b61647b2590f825f3db38891662cfc2fc776415143f599bb859"}, - {file = "PyYAML-6.0.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5773183b6446b2c99bb77e77595dd486303b4faab2b086e7b17bc6bef28865f6"}, - {file = "PyYAML-6.0.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b786eecbdf8499b9ca1d697215862083bd6d2a99965554781d0d8d1ad31e13a0"}, - {file = "PyYAML-6.0.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bc1bf2925a1ecd43da378f4db9e4f799775d6367bdb94671027b73b393a7c42c"}, - {file = "PyYAML-6.0.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:04ac92ad1925b2cff1db0cfebffb6ffc43457495c9b3c39d3fcae417d7125dc5"}, - {file = "PyYAML-6.0.1-cp39-cp39-win32.whl", hash = "sha256:faca3bdcf85b2fc05d06ff3fbc1f83e1391b3e724afa3feba7d13eeab355484c"}, - {file = "PyYAML-6.0.1-cp39-cp39-win_amd64.whl", hash = "sha256:510c9deebc5c0225e8c96813043e62b680ba2f9c50a08d3724c7f28a747d1486"}, - {file = "PyYAML-6.0.1.tar.gz", hash = "sha256:bfdf460b1736c775f2ba9f6a92bca30bc2095067b8a9d77876d1fad6cc3b4a43"}, + {file = "PyYAML-6.0.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:0a9a2848a5b7feac301353437eb7d5957887edbf81d56e903999a75a3d743086"}, + {file = "PyYAML-6.0.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:29717114e51c84ddfba879543fb232a6ed60086602313ca38cce623c1d62cfbf"}, + {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8824b5a04a04a047e72eea5cec3bc266db09e35de6bdfe34c9436ac5ee27d237"}, + {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c36280e6fb8385e520936c3cb3b8042851904eba0e58d277dca80a5cfed590b"}, + {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec031d5d2feb36d1d1a24380e4db6d43695f3748343d99434e6f5f9156aaa2ed"}, + {file = "PyYAML-6.0.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:936d68689298c36b53b29f23c6dbb74de12b4ac12ca6cfe0e047bedceea56180"}, + {file = "PyYAML-6.0.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:23502f431948090f597378482b4812b0caae32c22213aecf3b55325e049a6c68"}, + {file = "PyYAML-6.0.2-cp310-cp310-win32.whl", hash = "sha256:2e99c6826ffa974fe6e27cdb5ed0021786b03fc98e5ee3c5bfe1fd5015f42b99"}, + {file = "PyYAML-6.0.2-cp310-cp310-win_amd64.whl", hash = "sha256:a4d3091415f010369ae4ed1fc6b79def9416358877534caf6a0fdd2146c87a3e"}, + {file = "PyYAML-6.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:cc1c1159b3d456576af7a3e4d1ba7e6924cb39de8f67111c735f6fc832082774"}, + {file = "PyYAML-6.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1e2120ef853f59c7419231f3bf4e7021f1b936f6ebd222406c3b60212205d2ee"}, + {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d225db5a45f21e78dd9358e58a98702a0302f2659a3c6cd320564b75b86f47c"}, + {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5ac9328ec4831237bec75defaf839f7d4564be1e6b25ac710bd1a96321cc8317"}, + {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3ad2a3decf9aaba3d29c8f537ac4b243e36bef957511b4766cb0057d32b0be85"}, + {file = "PyYAML-6.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ff3824dc5261f50c9b0dfb3be22b4567a6f938ccce4587b38952d85fd9e9afe4"}, + {file = "PyYAML-6.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:797b4f722ffa07cc8d62053e4cff1486fa6dc094105d13fea7b1de7d8bf71c9e"}, + {file = "PyYAML-6.0.2-cp311-cp311-win32.whl", hash = "sha256:11d8f3dd2b9c1207dcaf2ee0bbbfd5991f571186ec9cc78427ba5bd32afae4b5"}, + {file = "PyYAML-6.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:e10ce637b18caea04431ce14fabcf5c64a1c61ec9c56b071a4b7ca131ca52d44"}, + {file = "PyYAML-6.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c70c95198c015b85feafc136515252a261a84561b7b1d51e3384e0655ddf25ab"}, + {file = "PyYAML-6.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ce826d6ef20b1bc864f0a68340c8b3287705cae2f8b4b1d932177dcc76721725"}, + {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1f71ea527786de97d1a0cc0eacd1defc0985dcf6b3f17bb77dcfc8c34bec4dc5"}, + {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9b22676e8097e9e22e36d6b7bda33190d0d400f345f23d4065d48f4ca7ae0425"}, + {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:80bab7bfc629882493af4aa31a4cfa43a4c57c83813253626916b8c7ada83476"}, + {file = "PyYAML-6.0.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48"}, + {file = "PyYAML-6.0.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8b9c7197f7cb2738065c481a0461e50ad02f18c78cd75775628afb4d7137fb3b"}, + {file = "PyYAML-6.0.2-cp312-cp312-win32.whl", hash = "sha256:ef6107725bd54b262d6dedcc2af448a266975032bc85ef0172c5f059da6325b4"}, + {file = "PyYAML-6.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:7e7401d0de89a9a855c839bc697c079a4af81cf878373abd7dc625847d25cbd8"}, + {file = "PyYAML-6.0.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:efdca5630322a10774e8e98e1af481aad470dd62c3170801852d752aa7a783ba"}, + {file = "PyYAML-6.0.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:50187695423ffe49e2deacb8cd10510bc361faac997de9efef88badc3bb9e2d1"}, + {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0ffe8360bab4910ef1b9e87fb812d8bc0a308b0d0eef8c8f44e0254ab3b07133"}, + {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:17e311b6c678207928d649faa7cb0d7b4c26a0ba73d41e99c4fff6b6c3276484"}, + {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:70b189594dbe54f75ab3a1acec5f1e3faa7e8cf2f1e08d9b561cb41b845f69d5"}, + {file = "PyYAML-6.0.2-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:41e4e3953a79407c794916fa277a82531dd93aad34e29c2a514c2c0c5fe971cc"}, + {file = "PyYAML-6.0.2-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:68ccc6023a3400877818152ad9a1033e3db8625d899c72eacb5a668902e4d652"}, + {file = "PyYAML-6.0.2-cp313-cp313-win32.whl", hash = "sha256:bc2fa7c6b47d6bc618dd7fb02ef6fdedb1090ec036abab80d4681424b84c1183"}, + {file = "PyYAML-6.0.2-cp313-cp313-win_amd64.whl", hash = "sha256:8388ee1976c416731879ac16da0aff3f63b286ffdd57cdeb95f3f2e085687563"}, + {file = "PyYAML-6.0.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:24471b829b3bf607e04e88d79542a9d48bb037c2267d7927a874e6c205ca7e9a"}, + {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7fded462629cfa4b685c5416b949ebad6cec74af5e2d42905d41e257e0869f5"}, + {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d84a1718ee396f54f3a086ea0a66d8e552b2ab2017ef8b420e92edbc841c352d"}, + {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9056c1ecd25795207ad294bcf39f2db3d845767be0ea6e6a34d856f006006083"}, + {file = "PyYAML-6.0.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:82d09873e40955485746739bcb8b4586983670466c23382c19cffecbf1fd8706"}, + {file = "PyYAML-6.0.2-cp38-cp38-win32.whl", hash = "sha256:43fa96a3ca0d6b1812e01ced1044a003533c47f6ee8aca31724f78e93ccc089a"}, + {file = "PyYAML-6.0.2-cp38-cp38-win_amd64.whl", hash = "sha256:01179a4a8559ab5de078078f37e5c1a30d76bb88519906844fd7bdea1b7729ff"}, + {file = "PyYAML-6.0.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:688ba32a1cffef67fd2e9398a2efebaea461578b0923624778664cc1c914db5d"}, + {file = "PyYAML-6.0.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:a8786accb172bd8afb8be14490a16625cbc387036876ab6ba70912730faf8e1f"}, + {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8e03406cac8513435335dbab54c0d385e4a49e4945d2909a581c83647ca0290"}, + {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f753120cb8181e736c57ef7636e83f31b9c0d1722c516f7e86cf15b7aa57ff12"}, + {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3b1fdb9dc17f5a7677423d508ab4f243a726dea51fa5e70992e59a7411c89d19"}, + {file = "PyYAML-6.0.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:0b69e4ce7a131fe56b7e4d770c67429700908fc0752af059838b1cfb41960e4e"}, + {file = "PyYAML-6.0.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:a9f8c2e67970f13b16084e04f134610fd1d374bf477b17ec1599185cf611d725"}, + {file = "PyYAML-6.0.2-cp39-cp39-win32.whl", hash = "sha256:6395c297d42274772abc367baaa79683958044e5d3835486c16da75d2a694631"}, + {file = "PyYAML-6.0.2-cp39-cp39-win_amd64.whl", hash = "sha256:39693e1f8320ae4f43943590b49779ffb98acb81f788220ea932a6b6c51004d8"}, + {file = "pyyaml-6.0.2.tar.gz", hash = "sha256:d584d9ec91ad65861cc08d42e834324ef890a082e591037abe114850ff7bbc3e"}, ] [[package]] name = "pyzmq" -version = "25.1.2" +version = "26.2.0" description = "Python bindings for 0MQ" optional = false -python-versions = ">=3.6" +python-versions = ">=3.7" files = [ - {file = "pyzmq-25.1.2-cp310-cp310-macosx_10_15_universal2.whl", hash = "sha256:e624c789359f1a16f83f35e2c705d07663ff2b4d4479bad35621178d8f0f6ea4"}, - {file = "pyzmq-25.1.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:49151b0efece79f6a79d41a461d78535356136ee70084a1c22532fc6383f4ad0"}, - {file = "pyzmq-25.1.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d9a5f194cf730f2b24d6af1f833c14c10f41023da46a7f736f48b6d35061e76e"}, - {file = "pyzmq-25.1.2-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:faf79a302f834d9e8304fafdc11d0d042266667ac45209afa57e5efc998e3872"}, - {file = "pyzmq-25.1.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7f51a7b4ead28d3fca8dda53216314a553b0f7a91ee8fc46a72b402a78c3e43d"}, - {file = "pyzmq-25.1.2-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:0ddd6d71d4ef17ba5a87becf7ddf01b371eaba553c603477679ae817a8d84d75"}, - {file = "pyzmq-25.1.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:246747b88917e4867e2367b005fc8eefbb4a54b7db363d6c92f89d69abfff4b6"}, - {file = "pyzmq-25.1.2-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:00c48ae2fd81e2a50c3485de1b9d5c7c57cd85dc8ec55683eac16846e57ac979"}, - {file = "pyzmq-25.1.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:5a68d491fc20762b630e5db2191dd07ff89834086740f70e978bb2ef2668be08"}, - {file = "pyzmq-25.1.2-cp310-cp310-win32.whl", hash = "sha256:09dfe949e83087da88c4a76767df04b22304a682d6154de2c572625c62ad6886"}, - {file = "pyzmq-25.1.2-cp310-cp310-win_amd64.whl", hash = "sha256:fa99973d2ed20417744fca0073390ad65ce225b546febb0580358e36aa90dba6"}, - {file = "pyzmq-25.1.2-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:82544e0e2d0c1811482d37eef297020a040c32e0687c1f6fc23a75b75db8062c"}, - {file = "pyzmq-25.1.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:01171fc48542348cd1a360a4b6c3e7d8f46cdcf53a8d40f84db6707a6768acc1"}, - {file = "pyzmq-25.1.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bc69c96735ab501419c432110016329bf0dea8898ce16fab97c6d9106dc0b348"}, - {file = "pyzmq-25.1.2-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3e124e6b1dd3dfbeb695435dff0e383256655bb18082e094a8dd1f6293114642"}, - {file = "pyzmq-25.1.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7598d2ba821caa37a0f9d54c25164a4fa351ce019d64d0b44b45540950458840"}, - {file = "pyzmq-25.1.2-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:d1299d7e964c13607efd148ca1f07dcbf27c3ab9e125d1d0ae1d580a1682399d"}, - {file = "pyzmq-25.1.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:4e6f689880d5ad87918430957297c975203a082d9a036cc426648fcbedae769b"}, - {file = "pyzmq-25.1.2-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:cc69949484171cc961e6ecd4a8911b9ce7a0d1f738fcae717177c231bf77437b"}, - {file = "pyzmq-25.1.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:9880078f683466b7f567b8624bfc16cad65077be046b6e8abb53bed4eeb82dd3"}, - {file = "pyzmq-25.1.2-cp311-cp311-win32.whl", hash = "sha256:4e5837af3e5aaa99a091302df5ee001149baff06ad22b722d34e30df5f0d9097"}, - {file = "pyzmq-25.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:25c2dbb97d38b5ac9fd15586e048ec5eb1e38f3d47fe7d92167b0c77bb3584e9"}, - {file = "pyzmq-25.1.2-cp312-cp312-macosx_10_15_universal2.whl", hash = "sha256:11e70516688190e9c2db14fcf93c04192b02d457b582a1f6190b154691b4c93a"}, - {file = "pyzmq-25.1.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:313c3794d650d1fccaaab2df942af9f2c01d6217c846177cfcbc693c7410839e"}, - {file = "pyzmq-25.1.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1b3cbba2f47062b85fe0ef9de5b987612140a9ba3a9c6d2543c6dec9f7c2ab27"}, - {file = "pyzmq-25.1.2-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fc31baa0c32a2ca660784d5af3b9487e13b61b3032cb01a115fce6588e1bed30"}, - {file = "pyzmq-25.1.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:02c9087b109070c5ab0b383079fa1b5f797f8d43e9a66c07a4b8b8bdecfd88ee"}, - {file = "pyzmq-25.1.2-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:f8429b17cbb746c3e043cb986328da023657e79d5ed258b711c06a70c2ea7537"}, - {file = "pyzmq-25.1.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:5074adeacede5f810b7ef39607ee59d94e948b4fd954495bdb072f8c54558181"}, - {file = "pyzmq-25.1.2-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:7ae8f354b895cbd85212da245f1a5ad8159e7840e37d78b476bb4f4c3f32a9fe"}, - {file = "pyzmq-25.1.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:b264bf2cc96b5bc43ce0e852be995e400376bd87ceb363822e2cb1964fcdc737"}, - {file = "pyzmq-25.1.2-cp312-cp312-win32.whl", hash = "sha256:02bbc1a87b76e04fd780b45e7f695471ae6de747769e540da909173d50ff8e2d"}, - {file = "pyzmq-25.1.2-cp312-cp312-win_amd64.whl", hash = "sha256:ced111c2e81506abd1dc142e6cd7b68dd53747b3b7ae5edbea4578c5eeff96b7"}, - {file = "pyzmq-25.1.2-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:7b6d09a8962a91151f0976008eb7b29b433a560fde056ec7a3db9ec8f1075438"}, - {file = "pyzmq-25.1.2-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:967668420f36878a3c9ecb5ab33c9d0ff8d054f9c0233d995a6d25b0e95e1b6b"}, - {file = "pyzmq-25.1.2-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:5edac3f57c7ddaacdb4d40f6ef2f9e299471fc38d112f4bc6d60ab9365445fb0"}, - {file = "pyzmq-25.1.2-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:0dabfb10ef897f3b7e101cacba1437bd3a5032ee667b7ead32bbcdd1a8422fe7"}, - {file = "pyzmq-25.1.2-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:2c6441e0398c2baacfe5ba30c937d274cfc2dc5b55e82e3749e333aabffde561"}, - {file = "pyzmq-25.1.2-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:16b726c1f6c2e7625706549f9dbe9b06004dfbec30dbed4bf50cbdfc73e5b32a"}, - {file = "pyzmq-25.1.2-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:a86c2dd76ef71a773e70551a07318b8e52379f58dafa7ae1e0a4be78efd1ff16"}, - {file = "pyzmq-25.1.2-cp36-cp36m-win32.whl", hash = "sha256:359f7f74b5d3c65dae137f33eb2bcfa7ad9ebefd1cab85c935f063f1dbb245cc"}, - {file = "pyzmq-25.1.2-cp36-cp36m-win_amd64.whl", hash = "sha256:55875492f820d0eb3417b51d96fea549cde77893ae3790fd25491c5754ea2f68"}, - {file = "pyzmq-25.1.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:b8c8a419dfb02e91b453615c69568442e897aaf77561ee0064d789705ff37a92"}, - {file = "pyzmq-25.1.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8807c87fa893527ae8a524c15fc505d9950d5e856f03dae5921b5e9aa3b8783b"}, - {file = "pyzmq-25.1.2-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:5e319ed7d6b8f5fad9b76daa0a68497bc6f129858ad956331a5835785761e003"}, - {file = "pyzmq-25.1.2-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:3c53687dde4d9d473c587ae80cc328e5b102b517447456184b485587ebd18b62"}, - {file = "pyzmq-25.1.2-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:9add2e5b33d2cd765ad96d5eb734a5e795a0755f7fc49aa04f76d7ddda73fd70"}, - {file = "pyzmq-25.1.2-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:e690145a8c0c273c28d3b89d6fb32c45e0d9605b2293c10e650265bf5c11cfec"}, - {file = "pyzmq-25.1.2-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:00a06faa7165634f0cac1abb27e54d7a0b3b44eb9994530b8ec73cf52e15353b"}, - {file = "pyzmq-25.1.2-cp37-cp37m-win32.whl", hash = "sha256:0f97bc2f1f13cb16905a5f3e1fbdf100e712d841482b2237484360f8bc4cb3d7"}, - {file = "pyzmq-25.1.2-cp37-cp37m-win_amd64.whl", hash = "sha256:6cc0020b74b2e410287e5942e1e10886ff81ac77789eb20bec13f7ae681f0fdd"}, - {file = "pyzmq-25.1.2-cp38-cp38-macosx_10_15_universal2.whl", hash = "sha256:bef02cfcbded83473bdd86dd8d3729cd82b2e569b75844fb4ea08fee3c26ae41"}, - {file = "pyzmq-25.1.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:e10a4b5a4b1192d74853cc71a5e9fd022594573926c2a3a4802020360aa719d8"}, - {file = "pyzmq-25.1.2-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:8c5f80e578427d4695adac6fdf4370c14a2feafdc8cb35549c219b90652536ae"}, - {file = "pyzmq-25.1.2-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:5dde6751e857910c1339890f3524de74007958557593b9e7e8c5f01cd919f8a7"}, - {file = "pyzmq-25.1.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ea1608dd169da230a0ad602d5b1ebd39807ac96cae1845c3ceed39af08a5c6df"}, - {file = "pyzmq-25.1.2-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:0f513130c4c361201da9bc69df25a086487250e16b5571ead521b31ff6b02220"}, - {file = "pyzmq-25.1.2-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:019744b99da30330798bb37df33549d59d380c78e516e3bab9c9b84f87a9592f"}, - {file = "pyzmq-25.1.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:2e2713ef44be5d52dd8b8e2023d706bf66cb22072e97fc71b168e01d25192755"}, - {file = "pyzmq-25.1.2-cp38-cp38-win32.whl", hash = "sha256:07cd61a20a535524906595e09344505a9bd46f1da7a07e504b315d41cd42eb07"}, - {file = "pyzmq-25.1.2-cp38-cp38-win_amd64.whl", hash = "sha256:eb7e49a17fb8c77d3119d41a4523e432eb0c6932187c37deb6fbb00cc3028088"}, - {file = "pyzmq-25.1.2-cp39-cp39-macosx_10_15_universal2.whl", hash = "sha256:94504ff66f278ab4b7e03e4cba7e7e400cb73bfa9d3d71f58d8972a8dc67e7a6"}, - {file = "pyzmq-25.1.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:6dd0d50bbf9dca1d0bdea219ae6b40f713a3fb477c06ca3714f208fd69e16fd8"}, - {file = "pyzmq-25.1.2-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:004ff469d21e86f0ef0369717351073e0e577428e514c47c8480770d5e24a565"}, - {file = "pyzmq-25.1.2-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:c0b5ca88a8928147b7b1e2dfa09f3b6c256bc1135a1338536cbc9ea13d3b7add"}, - {file = "pyzmq-25.1.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c9a79f1d2495b167119d02be7448bfba57fad2a4207c4f68abc0bab4b92925b"}, - {file = "pyzmq-25.1.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:518efd91c3d8ac9f9b4f7dd0e2b7b8bf1a4fe82a308009016b07eaa48681af82"}, - {file = "pyzmq-25.1.2-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:1ec23bd7b3a893ae676d0e54ad47d18064e6c5ae1fadc2f195143fb27373f7f6"}, - {file = "pyzmq-25.1.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:db36c27baed588a5a8346b971477b718fdc66cf5b80cbfbd914b4d6d355e44e2"}, - {file = "pyzmq-25.1.2-cp39-cp39-win32.whl", hash = "sha256:39b1067f13aba39d794a24761e385e2eddc26295826530a8c7b6c6c341584289"}, - {file = "pyzmq-25.1.2-cp39-cp39-win_amd64.whl", hash = "sha256:8e9f3fabc445d0ce320ea2c59a75fe3ea591fdbdeebec5db6de530dd4b09412e"}, - {file = "pyzmq-25.1.2-pp310-pypy310_pp73-macosx_10_9_x86_64.whl", hash = "sha256:a8c1d566344aee826b74e472e16edae0a02e2a044f14f7c24e123002dcff1c05"}, - {file = "pyzmq-25.1.2-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:759cfd391a0996345ba94b6a5110fca9c557ad4166d86a6e81ea526c376a01e8"}, - {file = "pyzmq-25.1.2-pp310-pypy310_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7c61e346ac34b74028ede1c6b4bcecf649d69b707b3ff9dc0fab453821b04d1e"}, - {file = "pyzmq-25.1.2-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4cb8fc1f8d69b411b8ec0b5f1ffbcaf14c1db95b6bccea21d83610987435f1a4"}, - {file = "pyzmq-25.1.2-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:3c00c9b7d1ca8165c610437ca0c92e7b5607b2f9076f4eb4b095c85d6e680a1d"}, - {file = "pyzmq-25.1.2-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:df0c7a16ebb94452d2909b9a7b3337940e9a87a824c4fc1c7c36bb4404cb0cde"}, - {file = "pyzmq-25.1.2-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:45999e7f7ed5c390f2e87ece7f6c56bf979fb213550229e711e45ecc7d42ccb8"}, - {file = "pyzmq-25.1.2-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:ac170e9e048b40c605358667aca3d94e98f604a18c44bdb4c102e67070f3ac9b"}, - {file = "pyzmq-25.1.2-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d1b604734bec94f05f81b360a272fc824334267426ae9905ff32dc2be433ab96"}, - {file = "pyzmq-25.1.2-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:a793ac733e3d895d96f865f1806f160696422554e46d30105807fdc9841b9f7d"}, - {file = "pyzmq-25.1.2-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:0806175f2ae5ad4b835ecd87f5f85583316b69f17e97786f7443baaf54b9bb98"}, - {file = "pyzmq-25.1.2-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:ef12e259e7bc317c7597d4f6ef59b97b913e162d83b421dd0db3d6410f17a244"}, - {file = "pyzmq-25.1.2-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:ea253b368eb41116011add00f8d5726762320b1bda892f744c91997b65754d73"}, - {file = "pyzmq-25.1.2-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1b9b1f2ad6498445a941d9a4fee096d387fee436e45cc660e72e768d3d8ee611"}, - {file = "pyzmq-25.1.2-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:8b14c75979ce932c53b79976a395cb2a8cd3aaf14aef75e8c2cb55a330b9b49d"}, - {file = "pyzmq-25.1.2-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:889370d5174a741a62566c003ee8ddba4b04c3f09a97b8000092b7ca83ec9c49"}, - {file = "pyzmq-25.1.2-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9a18fff090441a40ffda8a7f4f18f03dc56ae73f148f1832e109f9bffa85df15"}, - {file = "pyzmq-25.1.2-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:99a6b36f95c98839ad98f8c553d8507644c880cf1e0a57fe5e3a3f3969040882"}, - {file = "pyzmq-25.1.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4345c9a27f4310afbb9c01750e9461ff33d6fb74cd2456b107525bbeebcb5be3"}, - {file = "pyzmq-25.1.2-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:3516e0b6224cf6e43e341d56da15fd33bdc37fa0c06af4f029f7d7dfceceabbc"}, - {file = "pyzmq-25.1.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:146b9b1f29ead41255387fb07be56dc29639262c0f7344f570eecdcd8d683314"}, - {file = "pyzmq-25.1.2.tar.gz", hash = "sha256:93f1aa311e8bb912e34f004cf186407a4e90eec4f0ecc0efd26056bf7eda0226"}, + {file = "pyzmq-26.2.0-cp310-cp310-macosx_10_15_universal2.whl", hash = "sha256:ddf33d97d2f52d89f6e6e7ae66ee35a4d9ca6f36eda89c24591b0c40205a3629"}, + {file = "pyzmq-26.2.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:dacd995031a01d16eec825bf30802fceb2c3791ef24bcce48fa98ce40918c27b"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:89289a5ee32ef6c439086184529ae060c741334b8970a6855ec0b6ad3ff28764"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5506f06d7dc6ecf1efacb4a013b1f05071bb24b76350832c96449f4a2d95091c"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8ea039387c10202ce304af74def5021e9adc6297067f3441d348d2b633e8166a"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:a2224fa4a4c2ee872886ed00a571f5e967c85e078e8e8c2530a2fb01b3309b88"}, + {file = "pyzmq-26.2.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:28ad5233e9c3b52d76196c696e362508959741e1a005fb8fa03b51aea156088f"}, + {file = "pyzmq-26.2.0-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:1c17211bc037c7d88e85ed8b7d8f7e52db6dc8eca5590d162717c654550f7282"}, + {file = "pyzmq-26.2.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:b8f86dd868d41bea9a5f873ee13bf5551c94cf6bc51baebc6f85075971fe6eea"}, + {file = "pyzmq-26.2.0-cp310-cp310-win32.whl", hash = "sha256:46a446c212e58456b23af260f3d9fb785054f3e3653dbf7279d8f2b5546b21c2"}, + {file = "pyzmq-26.2.0-cp310-cp310-win_amd64.whl", hash = "sha256:49d34ab71db5a9c292a7644ce74190b1dd5a3475612eefb1f8be1d6961441971"}, + {file = "pyzmq-26.2.0-cp310-cp310-win_arm64.whl", hash = "sha256:bfa832bfa540e5b5c27dcf5de5d82ebc431b82c453a43d141afb1e5d2de025fa"}, + {file = "pyzmq-26.2.0-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:8f7e66c7113c684c2b3f1c83cdd3376103ee0ce4c49ff80a648643e57fb22218"}, + {file = "pyzmq-26.2.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3a495b30fc91db2db25120df5847d9833af237546fd59170701acd816ccc01c4"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:77eb0968da535cba0470a5165468b2cac7772cfb569977cff92e240f57e31bef"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6ace4f71f1900a548f48407fc9be59c6ba9d9aaf658c2eea6cf2779e72f9f317"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:92a78853d7280bffb93df0a4a6a2498cba10ee793cc8076ef797ef2f74d107cf"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:689c5d781014956a4a6de61d74ba97b23547e431e9e7d64f27d4922ba96e9d6e"}, + {file = "pyzmq-26.2.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:0aca98bc423eb7d153214b2df397c6421ba6373d3397b26c057af3c904452e37"}, + {file = "pyzmq-26.2.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:1f3496d76b89d9429a656293744ceca4d2ac2a10ae59b84c1da9b5165f429ad3"}, + {file = "pyzmq-26.2.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:5c2b3bfd4b9689919db068ac6c9911f3fcb231c39f7dd30e3138be94896d18e6"}, + {file = "pyzmq-26.2.0-cp311-cp311-win32.whl", hash = "sha256:eac5174677da084abf378739dbf4ad245661635f1600edd1221f150b165343f4"}, + {file = "pyzmq-26.2.0-cp311-cp311-win_amd64.whl", hash = "sha256:5a509df7d0a83a4b178d0f937ef14286659225ef4e8812e05580776c70e155d5"}, + {file = "pyzmq-26.2.0-cp311-cp311-win_arm64.whl", hash = "sha256:c0e6091b157d48cbe37bd67233318dbb53e1e6327d6fc3bb284afd585d141003"}, + {file = "pyzmq-26.2.0-cp312-cp312-macosx_10_15_universal2.whl", hash = "sha256:ded0fc7d90fe93ae0b18059930086c51e640cdd3baebdc783a695c77f123dcd9"}, + {file = "pyzmq-26.2.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:17bf5a931c7f6618023cdacc7081f3f266aecb68ca692adac015c383a134ca52"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:55cf66647e49d4621a7e20c8d13511ef1fe1efbbccf670811864452487007e08"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4661c88db4a9e0f958c8abc2b97472e23061f0bc737f6f6179d7a27024e1faa5"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ea7f69de383cb47522c9c208aec6dd17697db7875a4674c4af3f8cfdac0bdeae"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:7f98f6dfa8b8ccaf39163ce872bddacca38f6a67289116c8937a02e30bbe9711"}, + {file = "pyzmq-26.2.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:e3e0210287329272539eea617830a6a28161fbbd8a3271bf4150ae3e58c5d0e6"}, + {file = "pyzmq-26.2.0-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:6b274e0762c33c7471f1a7471d1a2085b1a35eba5cdc48d2ae319f28b6fc4de3"}, + {file = "pyzmq-26.2.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:29c6a4635eef69d68a00321e12a7d2559fe2dfccfa8efae3ffb8e91cd0b36a8b"}, + {file = "pyzmq-26.2.0-cp312-cp312-win32.whl", hash = "sha256:989d842dc06dc59feea09e58c74ca3e1678c812a4a8a2a419046d711031f69c7"}, + {file = "pyzmq-26.2.0-cp312-cp312-win_amd64.whl", hash = "sha256:2a50625acdc7801bc6f74698c5c583a491c61d73c6b7ea4dee3901bb99adb27a"}, + {file = "pyzmq-26.2.0-cp312-cp312-win_arm64.whl", hash = "sha256:4d29ab8592b6ad12ebbf92ac2ed2bedcfd1cec192d8e559e2e099f648570e19b"}, + {file = "pyzmq-26.2.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:9dd8cd1aeb00775f527ec60022004d030ddc51d783d056e3e23e74e623e33726"}, + {file = "pyzmq-26.2.0-cp313-cp313-macosx_10_15_universal2.whl", hash = "sha256:28c812d9757fe8acecc910c9ac9dafd2ce968c00f9e619db09e9f8f54c3a68a3"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4d80b1dd99c1942f74ed608ddb38b181b87476c6a966a88a950c7dee118fdf50"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8c997098cc65e3208eca09303630e84d42718620e83b733d0fd69543a9cab9cb"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7ad1bc8d1b7a18497dda9600b12dc193c577beb391beae5cd2349184db40f187"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:bea2acdd8ea4275e1278350ced63da0b166421928276c7c8e3f9729d7402a57b"}, + {file = "pyzmq-26.2.0-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:23f4aad749d13698f3f7b64aad34f5fc02d6f20f05999eebc96b89b01262fb18"}, + {file = "pyzmq-26.2.0-cp313-cp313-musllinux_1_1_i686.whl", hash = "sha256:a4f96f0d88accc3dbe4a9025f785ba830f968e21e3e2c6321ccdfc9aef755115"}, + {file = "pyzmq-26.2.0-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:ced65e5a985398827cc9276b93ef6dfabe0273c23de8c7931339d7e141c2818e"}, + {file = "pyzmq-26.2.0-cp313-cp313-win32.whl", hash = "sha256:31507f7b47cc1ead1f6e86927f8ebb196a0bab043f6345ce070f412a59bf87b5"}, + {file = "pyzmq-26.2.0-cp313-cp313-win_amd64.whl", hash = "sha256:70fc7fcf0410d16ebdda9b26cbd8bf8d803d220a7f3522e060a69a9c87bf7bad"}, + {file = "pyzmq-26.2.0-cp313-cp313-win_arm64.whl", hash = "sha256:c3789bd5768ab5618ebf09cef6ec2b35fed88709b104351748a63045f0ff9797"}, + {file = "pyzmq-26.2.0-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:034da5fc55d9f8da09015d368f519478a52675e558c989bfcb5cf6d4e16a7d2a"}, + {file = "pyzmq-26.2.0-cp313-cp313t-macosx_10_15_universal2.whl", hash = "sha256:c92d73464b886931308ccc45b2744e5968cbaade0b1d6aeb40d8ab537765f5bc"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:794a4562dcb374f7dbbfb3f51d28fb40123b5a2abadee7b4091f93054909add5"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:aee22939bb6075e7afededabad1a56a905da0b3c4e3e0c45e75810ebe3a52672"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2ae90ff9dad33a1cfe947d2c40cb9cb5e600d759ac4f0fd22616ce6540f72797"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:43a47408ac52647dfabbc66a25b05b6a61700b5165807e3fbd40063fcaf46386"}, + {file = "pyzmq-26.2.0-cp313-cp313t-musllinux_1_1_aarch64.whl", hash = "sha256:25bf2374a2a8433633c65ccb9553350d5e17e60c8eb4de4d92cc6bd60f01d306"}, + {file = "pyzmq-26.2.0-cp313-cp313t-musllinux_1_1_i686.whl", hash = "sha256:007137c9ac9ad5ea21e6ad97d3489af654381324d5d3ba614c323f60dab8fae6"}, + {file = "pyzmq-26.2.0-cp313-cp313t-musllinux_1_1_x86_64.whl", hash = "sha256:470d4a4f6d48fb34e92d768b4e8a5cc3780db0d69107abf1cd7ff734b9766eb0"}, + {file = "pyzmq-26.2.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:3b55a4229ce5da9497dd0452b914556ae58e96a4381bb6f59f1305dfd7e53fc8"}, + {file = "pyzmq-26.2.0-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:9cb3a6460cdea8fe8194a76de8895707e61ded10ad0be97188cc8463ffa7e3a8"}, + {file = "pyzmq-26.2.0-cp37-cp37m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:8ab5cad923cc95c87bffee098a27856c859bd5d0af31bd346035aa816b081fe1"}, + {file = "pyzmq-26.2.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9ed69074a610fad1c2fda66180e7b2edd4d31c53f2d1872bc2d1211563904cd9"}, + {file = "pyzmq-26.2.0-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:cccba051221b916a4f5e538997c45d7d136a5646442b1231b916d0164067ea27"}, + {file = "pyzmq-26.2.0-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:0eaa83fc4c1e271c24eaf8fb083cbccef8fde77ec8cd45f3c35a9a123e6da097"}, + {file = "pyzmq-26.2.0-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:9edda2df81daa129b25a39b86cb57dfdfe16f7ec15b42b19bfac503360d27a93"}, + {file = "pyzmq-26.2.0-cp37-cp37m-win32.whl", hash = "sha256:ea0eb6af8a17fa272f7b98d7bebfab7836a0d62738e16ba380f440fceca2d951"}, + {file = "pyzmq-26.2.0-cp37-cp37m-win_amd64.whl", hash = "sha256:4ff9dc6bc1664bb9eec25cd17506ef6672d506115095411e237d571e92a58231"}, + {file = "pyzmq-26.2.0-cp38-cp38-macosx_10_15_universal2.whl", hash = "sha256:2eb7735ee73ca1b0d71e0e67c3739c689067f055c764f73aac4cc8ecf958ee3f"}, + {file = "pyzmq-26.2.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:1a534f43bc738181aa7cbbaf48e3eca62c76453a40a746ab95d4b27b1111a7d2"}, + {file = "pyzmq-26.2.0-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:aedd5dd8692635813368e558a05266b995d3d020b23e49581ddd5bbe197a8ab6"}, + {file = "pyzmq-26.2.0-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:8be4700cd8bb02cc454f630dcdf7cfa99de96788b80c51b60fe2fe1dac480289"}, + {file = "pyzmq-26.2.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1fcc03fa4997c447dce58264e93b5aa2d57714fbe0f06c07b7785ae131512732"}, + {file = "pyzmq-26.2.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:402b190912935d3db15b03e8f7485812db350d271b284ded2b80d2e5704be780"}, + {file = "pyzmq-26.2.0-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:8685fa9c25ff00f550c1fec650430c4b71e4e48e8d852f7ddcf2e48308038640"}, + {file = "pyzmq-26.2.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:76589c020680778f06b7e0b193f4b6dd66d470234a16e1df90329f5e14a171cd"}, + {file = "pyzmq-26.2.0-cp38-cp38-win32.whl", hash = "sha256:8423c1877d72c041f2c263b1ec6e34360448decfb323fa8b94e85883043ef988"}, + {file = "pyzmq-26.2.0-cp38-cp38-win_amd64.whl", hash = "sha256:76589f2cd6b77b5bdea4fca5992dc1c23389d68b18ccc26a53680ba2dc80ff2f"}, + {file = "pyzmq-26.2.0-cp39-cp39-macosx_10_15_universal2.whl", hash = "sha256:b1d464cb8d72bfc1a3adc53305a63a8e0cac6bc8c5a07e8ca190ab8d3faa43c2"}, + {file = "pyzmq-26.2.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:4da04c48873a6abdd71811c5e163bd656ee1b957971db7f35140a2d573f6949c"}, + {file = "pyzmq-26.2.0-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:d049df610ac811dcffdc147153b414147428567fbbc8be43bb8885f04db39d98"}, + {file = "pyzmq-26.2.0-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:05590cdbc6b902101d0e65d6a4780af14dc22914cc6ab995d99b85af45362cc9"}, + {file = "pyzmq-26.2.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c811cfcd6a9bf680236c40c6f617187515269ab2912f3d7e8c0174898e2519db"}, + {file = "pyzmq-26.2.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:6835dd60355593de10350394242b5757fbbd88b25287314316f266e24c61d073"}, + {file = "pyzmq-26.2.0-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:bc6bee759a6bddea5db78d7dcd609397449cb2d2d6587f48f3ca613b19410cfc"}, + {file = "pyzmq-26.2.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:c530e1eecd036ecc83c3407f77bb86feb79916d4a33d11394b8234f3bd35b940"}, + {file = "pyzmq-26.2.0-cp39-cp39-win32.whl", hash = "sha256:367b4f689786fca726ef7a6c5ba606958b145b9340a5e4808132cc65759abd44"}, + {file = "pyzmq-26.2.0-cp39-cp39-win_amd64.whl", hash = "sha256:e6fa2e3e683f34aea77de8112f6483803c96a44fd726d7358b9888ae5bb394ec"}, + {file = "pyzmq-26.2.0-cp39-cp39-win_arm64.whl", hash = "sha256:7445be39143a8aa4faec43b076e06944b8f9d0701b669df4af200531b21e40bb"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:706e794564bec25819d21a41c31d4df2d48e1cc4b061e8d345d7fb4dd3e94072"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8b435f2753621cd36e7c1762156815e21c985c72b19135dac43a7f4f31d28dd1"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:160c7e0a5eb178011e72892f99f918c04a131f36056d10d9c1afb223fc952c2d"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2c4a71d5d6e7b28a47a394c0471b7e77a0661e2d651e7ae91e0cab0a587859ca"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:90412f2db8c02a3864cbfc67db0e3dcdbda336acf1c469526d3e869394fe001c"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:2ea4ad4e6a12e454de05f2949d4beddb52460f3de7c8b9d5c46fbb7d7222e02c"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:fc4f7a173a5609631bb0c42c23d12c49df3966f89f496a51d3eb0ec81f4519d6"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:878206a45202247781472a2d99df12a176fef806ca175799e1c6ad263510d57c"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:17c412bad2eb9468e876f556eb4ee910e62d721d2c7a53c7fa31e643d35352e6"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:0d987a3ae5a71c6226b203cfd298720e0086c7fe7c74f35fa8edddfbd6597eed"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:39887ac397ff35b7b775db7201095fc6310a35fdbae85bac4523f7eb3b840e20"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:fdb5b3e311d4d4b0eb8b3e8b4d1b0a512713ad7e6a68791d0923d1aec433d919"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:226af7dcb51fdb0109f0016449b357e182ea0ceb6b47dfb5999d569e5db161d5"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0bed0e799e6120b9c32756203fb9dfe8ca2fb8467fed830c34c877e25638c3fc"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:29c7947c594e105cb9e6c466bace8532dc1ca02d498684128b339799f5248277"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:cdeabcff45d1c219636ee2e54d852262e5c2e085d6cb476d938aee8d921356b3"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:35cffef589bcdc587d06f9149f8d5e9e8859920a071df5a2671de2213bef592a"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:18c8dc3b7468d8b4bdf60ce9d7141897da103c7a4690157b32b60acb45e333e6"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7133d0a1677aec369d67dd78520d3fa96dd7f3dcec99d66c1762870e5ea1a50a"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:6a96179a24b14fa6428cbfc08641c779a53f8fcec43644030328f44034c7f1f4"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:4f78c88905461a9203eac9faac157a2a0dbba84a0fd09fd29315db27be40af9f"}, + {file = "pyzmq-26.2.0.tar.gz", hash = "sha256:070672c258581c8e4f640b5159297580a9974b026043bd4ab0470be9ed324f1f"}, ] [package.dependencies] @@ -1746,13 +1888,13 @@ cffi = {version = "*", markers = "implementation_name == \"pypy\""} [[package]] name = "requests" -version = "2.31.0" +version = "2.32.3" description = "Python HTTP for Humans." optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "requests-2.31.0-py3-none-any.whl", hash = "sha256:58cd2187c01e70e6e26505bca751777aa9f2ee0b7f4300988b709f44e013003f"}, - {file = "requests-2.31.0.tar.gz", hash = "sha256:942c5a758f98d790eaed1a29cb6eefc7ffb0d1cf7af05c3d2791656dbd6ad1e1"}, + {file = "requests-2.32.3-py3-none-any.whl", hash = "sha256:70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6"}, + {file = "requests-2.32.3.tar.gz", hash = "sha256:55365417734eb18255590a9ff9eb97e9e1da868d4ccd6402399eaf68af20a760"}, ] [package.dependencies] @@ -1767,98 +1909,99 @@ use-chardet-on-py3 = ["chardet (>=3.0.2,<6)"] [[package]] name = "scipy" -version = "1.12.0" +version = "1.13.1" description = "Fundamental algorithms for scientific computing in Python" optional = false python-versions = ">=3.9" files = [ - {file = "scipy-1.12.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:78e4402e140879387187f7f25d91cc592b3501a2e51dfb320f48dfb73565f10b"}, - {file = "scipy-1.12.0-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:f5f00ebaf8de24d14b8449981a2842d404152774c1a1d880c901bf454cb8e2a1"}, - {file = "scipy-1.12.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e53958531a7c695ff66c2e7bb7b79560ffdc562e2051644c5576c39ff8efb563"}, - {file = "scipy-1.12.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5e32847e08da8d895ce09d108a494d9eb78974cf6de23063f93306a3e419960c"}, - {file = "scipy-1.12.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:4c1020cad92772bf44b8e4cdabc1df5d87376cb219742549ef69fc9fd86282dd"}, - {file = "scipy-1.12.0-cp310-cp310-win_amd64.whl", hash = "sha256:75ea2a144096b5e39402e2ff53a36fecfd3b960d786b7efd3c180e29c39e53f2"}, - {file = "scipy-1.12.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:408c68423f9de16cb9e602528be4ce0d6312b05001f3de61fe9ec8b1263cad08"}, - {file = "scipy-1.12.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:5adfad5dbf0163397beb4aca679187d24aec085343755fcdbdeb32b3679f254c"}, - {file = "scipy-1.12.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c3003652496f6e7c387b1cf63f4bb720951cfa18907e998ea551e6de51a04467"}, - {file = "scipy-1.12.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8b8066bce124ee5531d12a74b617d9ac0ea59245246410e19bca549656d9a40a"}, - {file = "scipy-1.12.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:8bee4993817e204d761dba10dbab0774ba5a8612e57e81319ea04d84945375ba"}, - {file = "scipy-1.12.0-cp311-cp311-win_amd64.whl", hash = "sha256:a24024d45ce9a675c1fb8494e8e5244efea1c7a09c60beb1eeb80373d0fecc70"}, - {file = "scipy-1.12.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:e7e76cc48638228212c747ada851ef355c2bb5e7f939e10952bc504c11f4e372"}, - {file = "scipy-1.12.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:f7ce148dffcd64ade37b2df9315541f9adad6efcaa86866ee7dd5db0c8f041c3"}, - {file = "scipy-1.12.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9c39f92041f490422924dfdb782527a4abddf4707616e07b021de33467f917bc"}, - {file = "scipy-1.12.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a7ebda398f86e56178c2fa94cad15bf457a218a54a35c2a7b4490b9f9cb2676c"}, - {file = "scipy-1.12.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:95e5c750d55cf518c398a8240571b0e0782c2d5a703250872f36eaf737751338"}, - {file = "scipy-1.12.0-cp312-cp312-win_amd64.whl", hash = "sha256:e646d8571804a304e1da01040d21577685ce8e2db08ac58e543eaca063453e1c"}, - {file = "scipy-1.12.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:913d6e7956c3a671de3b05ccb66b11bc293f56bfdef040583a7221d9e22a2e35"}, - {file = "scipy-1.12.0-cp39-cp39-macosx_12_0_arm64.whl", hash = "sha256:bba1b0c7256ad75401c73e4b3cf09d1f176e9bd4248f0d3112170fb2ec4db067"}, - {file = "scipy-1.12.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:730badef9b827b368f351eacae2e82da414e13cf8bd5051b4bdfd720271a5371"}, - {file = "scipy-1.12.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6546dc2c11a9df6926afcbdd8a3edec28566e4e785b915e849348c6dd9f3f490"}, - {file = "scipy-1.12.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:196ebad3a4882081f62a5bf4aeb7326aa34b110e533aab23e4374fcccb0890dc"}, - {file = "scipy-1.12.0-cp39-cp39-win_amd64.whl", hash = "sha256:b360f1b6b2f742781299514e99ff560d1fe9bd1bff2712894b52abe528d1fd1e"}, - {file = "scipy-1.12.0.tar.gz", hash = "sha256:4bf5abab8a36d20193c698b0f1fc282c1d083c94723902c447e5d2f1780936a3"}, + {file = "scipy-1.13.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:20335853b85e9a49ff7572ab453794298bcf0354d8068c5f6775a0eabf350aca"}, + {file = "scipy-1.13.1-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:d605e9c23906d1994f55ace80e0125c587f96c020037ea6aa98d01b4bd2e222f"}, + {file = "scipy-1.13.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cfa31f1def5c819b19ecc3a8b52d28ffdcc7ed52bb20c9a7589669dd3c250989"}, + {file = "scipy-1.13.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f26264b282b9da0952a024ae34710c2aff7d27480ee91a2e82b7b7073c24722f"}, + {file = "scipy-1.13.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:eccfa1906eacc02de42d70ef4aecea45415f5be17e72b61bafcfd329bdc52e94"}, + {file = "scipy-1.13.1-cp310-cp310-win_amd64.whl", hash = "sha256:2831f0dc9c5ea9edd6e51e6e769b655f08ec6db6e2e10f86ef39bd32eb11da54"}, + {file = "scipy-1.13.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:27e52b09c0d3a1d5b63e1105f24177e544a222b43611aaf5bc44d4a0979e32f9"}, + {file = "scipy-1.13.1-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:54f430b00f0133e2224c3ba42b805bfd0086fe488835effa33fa291561932326"}, + {file = "scipy-1.13.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e89369d27f9e7b0884ae559a3a956e77c02114cc60a6058b4e5011572eea9299"}, + {file = "scipy-1.13.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a78b4b3345f1b6f68a763c6e25c0c9a23a9fd0f39f5f3d200efe8feda560a5fa"}, + {file = "scipy-1.13.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:45484bee6d65633752c490404513b9ef02475b4284c4cfab0ef946def50b3f59"}, + {file = "scipy-1.13.1-cp311-cp311-win_amd64.whl", hash = "sha256:5713f62f781eebd8d597eb3f88b8bf9274e79eeabf63afb4a737abc6c84ad37b"}, + {file = "scipy-1.13.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:5d72782f39716b2b3509cd7c33cdc08c96f2f4d2b06d51e52fb45a19ca0c86a1"}, + {file = "scipy-1.13.1-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:017367484ce5498445aade74b1d5ab377acdc65e27095155e448c88497755a5d"}, + {file = "scipy-1.13.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:949ae67db5fa78a86e8fa644b9a6b07252f449dcf74247108c50e1d20d2b4627"}, + {file = "scipy-1.13.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:de3ade0e53bc1f21358aa74ff4830235d716211d7d077e340c7349bc3542e884"}, + {file = "scipy-1.13.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:2ac65fb503dad64218c228e2dc2d0a0193f7904747db43014645ae139c8fad16"}, + {file = "scipy-1.13.1-cp312-cp312-win_amd64.whl", hash = "sha256:cdd7dacfb95fea358916410ec61bbc20440f7860333aee6d882bb8046264e949"}, + {file = "scipy-1.13.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:436bbb42a94a8aeef855d755ce5a465479c721e9d684de76bf61a62e7c2b81d5"}, + {file = "scipy-1.13.1-cp39-cp39-macosx_12_0_arm64.whl", hash = "sha256:8335549ebbca860c52bf3d02f80784e91a004b71b059e3eea9678ba994796a24"}, + {file = "scipy-1.13.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d533654b7d221a6a97304ab63c41c96473ff04459e404b83275b60aa8f4b7004"}, + {file = "scipy-1.13.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:637e98dcf185ba7f8e663e122ebf908c4702420477ae52a04f9908707456ba4d"}, + {file = "scipy-1.13.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:a014c2b3697bde71724244f63de2476925596c24285c7a637364761f8710891c"}, + {file = "scipy-1.13.1-cp39-cp39-win_amd64.whl", hash = "sha256:392e4ec766654852c25ebad4f64e4e584cf19820b980bc04960bca0b0cd6eaa2"}, + {file = "scipy-1.13.1.tar.gz", hash = "sha256:095a87a0312b08dfd6a6155cbbd310a8c51800fc931b8c0b84003014b874ed3c"}, ] [package.dependencies] -numpy = ">=1.22.4,<1.29.0" +numpy = ">=1.22.4,<2.3" [package.extras] -dev = ["click", "cython-lint (>=0.12.2)", "doit (>=0.36.0)", "mypy", "pycodestyle", "pydevtool", "rich-click", "ruff", "types-psutil", "typing_extensions"] -doc = ["jupytext", "matplotlib (>2)", "myst-nb", "numpydoc", "pooch", "pydata-sphinx-theme (==0.9.0)", "sphinx (!=4.1.0)", "sphinx-design (>=0.2.0)"] -test = ["asv", "gmpy2", "hypothesis", "mpmath", "pooch", "pytest", "pytest-cov", "pytest-timeout", "pytest-xdist", "scikit-umfpack", "threadpoolctl"] +dev = ["cython-lint (>=0.12.2)", "doit (>=0.36.0)", "mypy", "pycodestyle", "pydevtool", "rich-click", "ruff", "types-psutil", "typing_extensions"] +doc = ["jupyterlite-pyodide-kernel", "jupyterlite-sphinx (>=0.12.0)", "jupytext", "matplotlib (>=3.5)", "myst-nb", "numpydoc", "pooch", "pydata-sphinx-theme (>=0.15.2)", "sphinx (>=5.0.0)", "sphinx-design (>=0.4.0)"] +test = ["array-api-strict", "asv", "gmpy2", "hypothesis (>=6.30)", "mpmath", "pooch", "pytest", "pytest-cov", "pytest-timeout", "pytest-xdist", "scikit-umfpack", "threadpoolctl"] [[package]] name = "shapely" -version = "2.0.3" +version = "2.0.6" description = "Manipulation and analysis of geometric objects" optional = false python-versions = ">=3.7" files = [ - {file = "shapely-2.0.3-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:af7e9abe180b189431b0f490638281b43b84a33a960620e6b2e8d3e3458b61a1"}, - {file = "shapely-2.0.3-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:98040462b36ced9671e266b95c326b97f41290d9d17504a1ee4dc313a7667b9c"}, - {file = "shapely-2.0.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:71eb736ef2843f23473c6e37f6180f90f0a35d740ab284321548edf4e55d9a52"}, - {file = "shapely-2.0.3-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:881eb9dbbb4a6419667e91fcb20313bfc1e67f53dbb392c6840ff04793571ed1"}, - {file = "shapely-2.0.3-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f10d2ccf0554fc0e39fad5886c839e47e207f99fdf09547bc687a2330efda35b"}, - {file = "shapely-2.0.3-cp310-cp310-win32.whl", hash = "sha256:6dfdc077a6fcaf74d3eab23a1ace5abc50c8bce56ac7747d25eab582c5a2990e"}, - {file = "shapely-2.0.3-cp310-cp310-win_amd64.whl", hash = "sha256:64c5013dacd2d81b3bb12672098a0b2795c1bf8190cfc2980e380f5ef9d9e4d9"}, - {file = "shapely-2.0.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:56cee3e4e8159d6f2ce32e421445b8e23154fd02a0ac271d6a6c0b266a8e3cce"}, - {file = "shapely-2.0.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:619232c8276fded09527d2a9fd91a7885ff95c0ff9ecd5e3cb1e34fbb676e2ae"}, - {file = "shapely-2.0.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b2a7d256db6f5b4b407dc0c98dd1b2fcf1c9c5814af9416e5498d0a2e4307a4b"}, - {file = "shapely-2.0.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e45f0c8cd4583647db3216d965d49363e6548c300c23fd7e57ce17a03f824034"}, - {file = "shapely-2.0.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:13cb37d3826972a82748a450328fe02a931dcaed10e69a4d83cc20ba021bc85f"}, - {file = "shapely-2.0.3-cp311-cp311-win32.whl", hash = "sha256:9302d7011e3e376d25acd30d2d9e70d315d93f03cc748784af19b00988fc30b1"}, - {file = "shapely-2.0.3-cp311-cp311-win_amd64.whl", hash = "sha256:6b464f2666b13902835f201f50e835f2f153f37741db88f68c7f3b932d3505fa"}, - {file = "shapely-2.0.3-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:e86e7cb8e331a4850e0c2a8b2d66dc08d7a7b301b8d1d34a13060e3a5b4b3b55"}, - {file = "shapely-2.0.3-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c91981c99ade980fc49e41a544629751a0ccd769f39794ae913e53b07b2f78b9"}, - {file = "shapely-2.0.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:bd45d456983dc60a42c4db437496d3f08a4201fbf662b69779f535eb969660af"}, - {file = "shapely-2.0.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:882fb1ffc7577e88c1194f4f1757e277dc484ba096a3b94844319873d14b0f2d"}, - {file = "shapely-2.0.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b9f2d93bff2ea52fa93245798cddb479766a18510ea9b93a4fb9755c79474889"}, - {file = "shapely-2.0.3-cp312-cp312-win32.whl", hash = "sha256:99abad1fd1303b35d991703432c9481e3242b7b3a393c186cfb02373bf604004"}, - {file = "shapely-2.0.3-cp312-cp312-win_amd64.whl", hash = "sha256:6f555fe3304a1f40398977789bc4fe3c28a11173196df9ece1e15c5bc75a48db"}, - {file = "shapely-2.0.3-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:a983cc418c1fa160b7d797cfef0e0c9f8c6d5871e83eae2c5793fce6a837fad9"}, - {file = "shapely-2.0.3-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:18bddb8c327f392189a8d5d6b9a858945722d0bb95ccbd6a077b8e8fc4c7890d"}, - {file = "shapely-2.0.3-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:442f4dcf1eb58c5a4e3428d88e988ae153f97ab69a9f24e07bf4af8038536325"}, - {file = "shapely-2.0.3-cp37-cp37m-win32.whl", hash = "sha256:31a40b6e3ab00a4fd3a1d44efb2482278642572b8e0451abdc8e0634b787173e"}, - {file = "shapely-2.0.3-cp37-cp37m-win_amd64.whl", hash = "sha256:59b16976c2473fec85ce65cc9239bef97d4205ab3acead4e6cdcc72aee535679"}, - {file = "shapely-2.0.3-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:705efbce1950a31a55b1daa9c6ae1c34f1296de71ca8427974ec2f27d57554e3"}, - {file = "shapely-2.0.3-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:601c5c0058a6192df704cb889439f64994708563f57f99574798721e9777a44b"}, - {file = "shapely-2.0.3-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:f24ecbb90a45c962b3b60d8d9a387272ed50dc010bfe605f1d16dfc94772d8a1"}, - {file = "shapely-2.0.3-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8c2a2989222c6062f7a0656e16276c01bb308bc7e5d999e54bf4e294ce62e76"}, - {file = "shapely-2.0.3-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:42bceb9bceb3710a774ce04908fda0f28b291323da2688f928b3f213373b5aee"}, - {file = "shapely-2.0.3-cp38-cp38-win32.whl", hash = "sha256:54d925c9a311e4d109ec25f6a54a8bd92cc03481a34ae1a6a92c1fe6729b7e01"}, - {file = "shapely-2.0.3-cp38-cp38-win_amd64.whl", hash = "sha256:300d203b480a4589adefff4c4af0b13919cd6d760ba3cbb1e56275210f96f654"}, - {file = "shapely-2.0.3-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:083d026e97b6c1f4a9bd2a9171c7692461092ed5375218170d91705550eecfd5"}, - {file = "shapely-2.0.3-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:27b6e1910094d93e9627f2664121e0e35613262fc037051680a08270f6058daf"}, - {file = "shapely-2.0.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:71b2de56a9e8c0e5920ae5ddb23b923490557ac50cb0b7fa752761bf4851acde"}, - {file = "shapely-2.0.3-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4d279e56bbb68d218d63f3efc80c819cedcceef0e64efbf058a1df89dc57201b"}, - {file = "shapely-2.0.3-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:88566d01a30f0453f7d038db46bc83ce125e38e47c5f6bfd4c9c287010e9bf74"}, - {file = "shapely-2.0.3-cp39-cp39-win32.whl", hash = "sha256:58afbba12c42c6ed44c4270bc0e22f3dadff5656d711b0ad335c315e02d04707"}, - {file = "shapely-2.0.3-cp39-cp39-win_amd64.whl", hash = "sha256:5026b30433a70911979d390009261b8c4021ff87c7c3cbd825e62bb2ffa181bc"}, - {file = "shapely-2.0.3.tar.gz", hash = "sha256:4d65d0aa7910af71efa72fd6447e02a8e5dd44da81a983de9d736d6e6ccbe674"}, + {file = "shapely-2.0.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:29a34e068da2d321e926b5073539fd2a1d4429a2c656bd63f0bd4c8f5b236d0b"}, + {file = "shapely-2.0.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:e1c84c3f53144febf6af909d6b581bc05e8785d57e27f35ebaa5c1ab9baba13b"}, + {file = "shapely-2.0.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2ad2fae12dca8d2b727fa12b007e46fbc522148a584f5d6546c539f3464dccde"}, + {file = "shapely-2.0.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b3304883bd82d44be1b27a9d17f1167fda8c7f5a02a897958d86c59ec69b705e"}, + {file = "shapely-2.0.6-cp310-cp310-win32.whl", hash = "sha256:3ec3a0eab496b5e04633a39fa3d5eb5454628228201fb24903d38174ee34565e"}, + {file = "shapely-2.0.6-cp310-cp310-win_amd64.whl", hash = "sha256:28f87cdf5308a514763a5c38de295544cb27429cfa655d50ed8431a4796090c4"}, + {file = "shapely-2.0.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:5aeb0f51a9db176da9a30cb2f4329b6fbd1e26d359012bb0ac3d3c7781667a9e"}, + {file = "shapely-2.0.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9a7a78b0d51257a367ee115f4d41ca4d46edbd0dd280f697a8092dd3989867b2"}, + {file = "shapely-2.0.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f32c23d2f43d54029f986479f7c1f6e09c6b3a19353a3833c2ffb226fb63a855"}, + {file = "shapely-2.0.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b3dc9fb0eb56498912025f5eb352b5126f04801ed0e8bdbd867d21bdbfd7cbd0"}, + {file = "shapely-2.0.6-cp311-cp311-win32.whl", hash = "sha256:d93b7e0e71c9f095e09454bf18dad5ea716fb6ced5df3cb044564a00723f339d"}, + {file = "shapely-2.0.6-cp311-cp311-win_amd64.whl", hash = "sha256:c02eb6bf4cfb9fe6568502e85bb2647921ee49171bcd2d4116c7b3109724ef9b"}, + {file = "shapely-2.0.6-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:cec9193519940e9d1b86a3b4f5af9eb6910197d24af02f247afbfb47bcb3fab0"}, + {file = "shapely-2.0.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:83b94a44ab04a90e88be69e7ddcc6f332da7c0a0ebb1156e1c4f568bbec983c3"}, + {file = "shapely-2.0.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:537c4b2716d22c92036d00b34aac9d3775e3691f80c7aa517c2c290351f42cd8"}, + {file = "shapely-2.0.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:98fea108334be345c283ce74bf064fa00cfdd718048a8af7343c59eb40f59726"}, + {file = "shapely-2.0.6-cp312-cp312-win32.whl", hash = "sha256:42fd4cd4834747e4990227e4cbafb02242c0cffe9ce7ef9971f53ac52d80d55f"}, + {file = "shapely-2.0.6-cp312-cp312-win_amd64.whl", hash = "sha256:665990c84aece05efb68a21b3523a6b2057e84a1afbef426ad287f0796ef8a48"}, + {file = "shapely-2.0.6-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:42805ef90783ce689a4dde2b6b2f261e2c52609226a0438d882e3ced40bb3013"}, + {file = "shapely-2.0.6-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:6d2cb146191a47bd0cee8ff5f90b47547b82b6345c0d02dd8b25b88b68af62d7"}, + {file = "shapely-2.0.6-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e3fdef0a1794a8fe70dc1f514440aa34426cc0ae98d9a1027fb299d45741c381"}, + {file = "shapely-2.0.6-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2c665a0301c645615a107ff7f52adafa2153beab51daf34587170d85e8ba6805"}, + {file = "shapely-2.0.6-cp313-cp313-win32.whl", hash = "sha256:0334bd51828f68cd54b87d80b3e7cee93f249d82ae55a0faf3ea21c9be7b323a"}, + {file = "shapely-2.0.6-cp313-cp313-win_amd64.whl", hash = "sha256:d37d070da9e0e0f0a530a621e17c0b8c3c9d04105655132a87cfff8bd77cc4c2"}, + {file = "shapely-2.0.6-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:fa7468e4f5b92049c0f36d63c3e309f85f2775752e076378e36c6387245c5462"}, + {file = "shapely-2.0.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ed5867e598a9e8ac3291da6cc9baa62ca25706eea186117034e8ec0ea4355653"}, + {file = "shapely-2.0.6-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:81d9dfe155f371f78c8d895a7b7f323bb241fb148d848a2bf2244f79213123fe"}, + {file = "shapely-2.0.6-cp37-cp37m-win32.whl", hash = "sha256:fbb7bf02a7542dba55129062570211cfb0defa05386409b3e306c39612e7fbcc"}, + {file = "shapely-2.0.6-cp37-cp37m-win_amd64.whl", hash = "sha256:837d395fac58aa01aa544495b97940995211e3e25f9aaf87bc3ba5b3a8cd1ac7"}, + {file = "shapely-2.0.6-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:c6d88ade96bf02f6bfd667ddd3626913098e243e419a0325ebef2bbd481d1eb6"}, + {file = "shapely-2.0.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:8b3b818c4407eaa0b4cb376fd2305e20ff6df757bf1356651589eadc14aab41b"}, + {file = "shapely-2.0.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1bbc783529a21f2bd50c79cef90761f72d41c45622b3e57acf78d984c50a5d13"}, + {file = "shapely-2.0.6-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2423f6c0903ebe5df6d32e0066b3d94029aab18425ad4b07bf98c3972a6e25a1"}, + {file = "shapely-2.0.6-cp38-cp38-win32.whl", hash = "sha256:2de00c3bfa80d6750832bde1d9487e302a6dd21d90cb2f210515cefdb616e5f5"}, + {file = "shapely-2.0.6-cp38-cp38-win_amd64.whl", hash = "sha256:3a82d58a1134d5e975f19268710e53bddd9c473743356c90d97ce04b73e101ee"}, + {file = "shapely-2.0.6-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:392f66f458a0a2c706254f473290418236e52aa4c9b476a072539d63a2460595"}, + {file = "shapely-2.0.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:eba5bae271d523c938274c61658ebc34de6c4b33fdf43ef7e938b5776388c1be"}, + {file = "shapely-2.0.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7060566bc4888b0c8ed14b5d57df8a0ead5c28f9b69fb6bed4476df31c51b0af"}, + {file = "shapely-2.0.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b02154b3e9d076a29a8513dffcb80f047a5ea63c897c0cd3d3679f29363cf7e5"}, + {file = "shapely-2.0.6-cp39-cp39-win32.whl", hash = "sha256:44246d30124a4f1a638a7d5419149959532b99dfa25b54393512e6acc9c211ac"}, + {file = "shapely-2.0.6-cp39-cp39-win_amd64.whl", hash = "sha256:2b542d7f1dbb89192d3512c52b679c822ba916f93479fa5d4fc2fe4fa0b3c9e8"}, + {file = "shapely-2.0.6.tar.gz", hash = "sha256:997f6159b1484059ec239cacaa53467fd8b5564dabe186cd84ac2944663b0bf6"}, ] [package.dependencies] -numpy = ">=1.14,<2" +numpy = ">=1.14,<3" [package.extras] docs = ["matplotlib", "numpydoc (==1.1.*)", "sphinx", "sphinx-book-theme", "sphinx-remove-toctrees"] @@ -1907,48 +2050,48 @@ files = [ [[package]] name = "tornado" -version = "6.4" +version = "6.4.1" description = "Tornado is a Python web framework and asynchronous networking library, originally developed at FriendFeed." optional = false -python-versions = ">= 3.8" +python-versions = ">=3.8" files = [ - {file = "tornado-6.4-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:02ccefc7d8211e5a7f9e8bc3f9e5b0ad6262ba2fbb683a6443ecc804e5224ce0"}, - {file = "tornado-6.4-cp38-abi3-macosx_10_9_x86_64.whl", hash = "sha256:27787de946a9cffd63ce5814c33f734c627a87072ec7eed71f7fc4417bb16263"}, - {file = "tornado-6.4-cp38-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f7894c581ecdcf91666a0912f18ce5e757213999e183ebfc2c3fdbf4d5bd764e"}, - {file = "tornado-6.4-cp38-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e43bc2e5370a6a8e413e1e1cd0c91bedc5bd62a74a532371042a18ef19e10579"}, - {file = "tornado-6.4-cp38-abi3-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f0251554cdd50b4b44362f73ad5ba7126fc5b2c2895cc62b14a1c2d7ea32f212"}, - {file = "tornado-6.4-cp38-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:fd03192e287fbd0899dd8f81c6fb9cbbc69194d2074b38f384cb6fa72b80e9c2"}, - {file = "tornado-6.4-cp38-abi3-musllinux_1_1_i686.whl", hash = "sha256:88b84956273fbd73420e6d4b8d5ccbe913c65d31351b4c004ae362eba06e1f78"}, - {file = "tornado-6.4-cp38-abi3-musllinux_1_1_x86_64.whl", hash = "sha256:71ddfc23a0e03ef2df1c1397d859868d158c8276a0603b96cf86892bff58149f"}, - {file = "tornado-6.4-cp38-abi3-win32.whl", hash = "sha256:6f8a6c77900f5ae93d8b4ae1196472d0ccc2775cc1dfdc9e7727889145c45052"}, - {file = "tornado-6.4-cp38-abi3-win_amd64.whl", hash = "sha256:10aeaa8006333433da48dec9fe417877f8bcc21f48dda8d661ae79da357b2a63"}, - {file = "tornado-6.4.tar.gz", hash = "sha256:72291fa6e6bc84e626589f1c29d90a5a6d593ef5ae68052ee2ef000dfd273dee"}, + {file = "tornado-6.4.1-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:163b0aafc8e23d8cdc3c9dfb24c5368af84a81e3364745ccb4427669bf84aec8"}, + {file = "tornado-6.4.1-cp38-abi3-macosx_10_9_x86_64.whl", hash = "sha256:6d5ce3437e18a2b66fbadb183c1d3364fb03f2be71299e7d10dbeeb69f4b2a14"}, + {file = "tornado-6.4.1-cp38-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e2e20b9113cd7293f164dc46fffb13535266e713cdb87bd2d15ddb336e96cfc4"}, + {file = "tornado-6.4.1-cp38-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8ae50a504a740365267b2a8d1a90c9fbc86b780a39170feca9bcc1787ff80842"}, + {file = "tornado-6.4.1-cp38-abi3-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:613bf4ddf5c7a95509218b149b555621497a6cc0d46ac341b30bd9ec19eac7f3"}, + {file = "tornado-6.4.1-cp38-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:25486eb223babe3eed4b8aecbac33b37e3dd6d776bc730ca14e1bf93888b979f"}, + {file = "tornado-6.4.1-cp38-abi3-musllinux_1_2_i686.whl", hash = "sha256:454db8a7ecfcf2ff6042dde58404164d969b6f5d58b926da15e6b23817950fc4"}, + {file = "tornado-6.4.1-cp38-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:a02a08cc7a9314b006f653ce40483b9b3c12cda222d6a46d4ac63bb6c9057698"}, + {file = "tornado-6.4.1-cp38-abi3-win32.whl", hash = "sha256:d9a566c40b89757c9aa8e6f032bcdb8ca8795d7c1a9762910c722b1635c9de4d"}, + {file = "tornado-6.4.1-cp38-abi3-win_amd64.whl", hash = "sha256:b24b8982ed444378d7f21d563f4180a2de31ced9d8d84443907a0a64da2072e7"}, + {file = "tornado-6.4.1.tar.gz", hash = "sha256:92d3ab53183d8c50f8204a51e6f91d18a15d5ef261e84d452800d4ff6fc504e9"}, ] [[package]] name = "traitlets" -version = "5.14.1" +version = "5.14.3" description = "Traitlets Python configuration system" optional = false python-versions = ">=3.8" files = [ - {file = "traitlets-5.14.1-py3-none-any.whl", hash = "sha256:2e5a030e6eff91737c643231bfcf04a65b0132078dad75e4936700b213652e74"}, - {file = "traitlets-5.14.1.tar.gz", hash = "sha256:8585105b371a04b8316a43d5ce29c098575c2e477850b62b848b964f1444527e"}, + {file = "traitlets-5.14.3-py3-none-any.whl", hash = "sha256:b74e89e397b1ed28cc831db7aea759ba6640cb3de13090ca145426688ff1ac4f"}, + {file = "traitlets-5.14.3.tar.gz", hash = "sha256:9ed0579d3502c94b4b3732ac120375cda96f923114522847de4b3bb98b96b6b7"}, ] [package.extras] docs = ["myst-parser", "pydata-sphinx-theme", "sphinx"] -test = ["argcomplete (>=3.0.3)", "mypy (>=1.7.0)", "pre-commit", "pytest (>=7.0,<7.5)", "pytest-mock", "pytest-mypy-testing"] +test = ["argcomplete (>=3.0.3)", "mypy (>=1.7.0)", "pre-commit", "pytest (>=7.0,<8.2)", "pytest-mock", "pytest-mypy-testing"] [[package]] name = "typing-extensions" -version = "4.10.0" +version = "4.12.2" description = "Backported and Experimental Type Hints for Python 3.8+" optional = false python-versions = ">=3.8" files = [ - {file = "typing_extensions-4.10.0-py3-none-any.whl", hash = "sha256:69b1a937c3a517342112fb4c6df7e72fc39a38e7891a5730ed4985b5214b5475"}, - {file = "typing_extensions-4.10.0.tar.gz", hash = "sha256:b0abd7c89e8fb96f98db18d86106ff1d90ab692004eb746cf6eda2682f91b3cb"}, + {file = "typing_extensions-4.12.2-py3-none-any.whl", hash = "sha256:04e5ca0351e0f3f85c6853954072df659d0d13fac324d0072316b67d7794700d"}, + {file = "typing_extensions-4.12.2.tar.gz", hash = "sha256:1a7ead55c7e559dd4dee8856e3a88b41225abfe1ce8df57b7c13915fe121ffb8"}, ] [[package]] @@ -1968,13 +2111,13 @@ typing-extensions = ">=3.7.4" [[package]] name = "urllib3" -version = "2.2.1" +version = "2.2.3" description = "HTTP library with thread-safe connection pooling, file post, and more." optional = false python-versions = ">=3.8" files = [ - {file = "urllib3-2.2.1-py3-none-any.whl", hash = "sha256:450b20ec296a467077128bff42b73080516e71b56ff59a60a02bef2232c4fa9d"}, - {file = "urllib3-2.2.1.tar.gz", hash = "sha256:d0570876c61ab9e520d776c38acbbb5b05a776d3f9ff98a5c8fd5162a444cf19"}, + {file = "urllib3-2.2.3-py3-none-any.whl", hash = "sha256:ca899ca043dcb1bafa3e262d73aa25c465bfb49e0bd9dd5d59f1d0acba2f8fac"}, + {file = "urllib3-2.2.3.tar.gz", hash = "sha256:e7d814a81dad81e6caf2ec9fdedb284ecc9c73076b62654547cc64ccdcae26e9"}, ] [package.extras] @@ -2011,20 +2154,24 @@ pyyaml = "*" [[package]] name = "zipp" -version = "3.17.0" +version = "3.20.2" description = "Backport of pathlib-compatible object wrapper for zip files" optional = false python-versions = ">=3.8" files = [ - {file = "zipp-3.17.0-py3-none-any.whl", hash = "sha256:0e923e726174922dce09c53c59ad483ff7bbb8e572e00c7f7c46b88556409f31"}, - {file = "zipp-3.17.0.tar.gz", hash = "sha256:84e64a1c28cf7e91ed2078bb8cc8c259cb19b76942096c8d7b84947690cabaf0"}, + {file = "zipp-3.20.2-py3-none-any.whl", hash = "sha256:a817ac80d6cf4b23bf7f2828b7cabf326f15a001bea8b1f9b49631780ba28350"}, + {file = "zipp-3.20.2.tar.gz", hash = "sha256:bc9eb26f4506fda01b81bcde0ca78103b6e62f991b381fec825435c836edbc29"}, ] [package.extras] -docs = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (<7.2.5)", "sphinx (>=3.5)", "sphinx-lint"] -testing = ["big-O", "jaraco.functools", "jaraco.itertools", "more-itertools", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-ignore-flaky", "pytest-mypy (>=0.9.1)", "pytest-ruff"] +check = ["pytest-checkdocs (>=2.4)", "pytest-ruff (>=0.2.1)"] +cover = ["pytest-cov"] +doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] +enabler = ["pytest-enabler (>=2.2)"] +test = ["big-O", "importlib-resources", "jaraco.functools", "jaraco.itertools", "jaraco.test", "more-itertools", "pytest (>=6,!=8.1.*)", "pytest-ignore-flaky"] +type = ["pytest-mypy"] [metadata] lock-version = "2.0" -python-versions = ">=3.9,<3.12" -content-hash = "a6ab3acc3be9323829288c857b92ba3250cc36343f487ea2a0950ecb41a46bc1" +python-versions = ">=3.9" +content-hash = "efdbfe91976ae78442e45faa2c5eda3e54ccbf6d92323c504fcedf0ac3637dcc" From d3d181a51c922ffed538e196624d07e866e1e6c3 Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 21 Sep 2024 15:29:00 -0400 Subject: [PATCH 31/55] Refactored dynamics into a module --- f1tenth_gym/envs/dynamic_models/__init__.py | 55 +++++++ f1tenth_gym/envs/dynamic_models/kinematic.py | 94 ++++++++++++ f1tenth_gym/envs/dynamic_models/multi_body.py | 0 .../envs/dynamic_models/single_track.py | 144 ++++++++++++++++++ .../envs/dynamic_models/tire_models.py | 0 f1tenth_gym/envs/dynamic_models/utils.py | 136 +++++++++++++++++ pyproject.toml | 61 -------- 7 files changed, 429 insertions(+), 61 deletions(-) create mode 100644 f1tenth_gym/envs/dynamic_models/__init__.py create mode 100644 f1tenth_gym/envs/dynamic_models/kinematic.py create mode 100644 f1tenth_gym/envs/dynamic_models/multi_body.py create mode 100644 f1tenth_gym/envs/dynamic_models/single_track.py create mode 100644 f1tenth_gym/envs/dynamic_models/tire_models.py create mode 100644 f1tenth_gym/envs/dynamic_models/utils.py delete mode 100644 pyproject.toml diff --git a/f1tenth_gym/envs/dynamic_models/__init__.py b/f1tenth_gym/envs/dynamic_models/__init__.py new file mode 100644 index 00000000..10f0c507 --- /dev/null +++ b/f1tenth_gym/envs/dynamic_models/__init__.py @@ -0,0 +1,55 @@ +""" +This module contains the dynamic models available in the F1Tenth Gym. +Each submodule contains a single model, and the equations or their source is documented alongside it. Many of the models are from the CommonRoad repository, available here: https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/ +""" +import warnings +from enum import Enum +import numpy as np + +from .kinematic import vehicle_dynamics_ks +from .single_track import vehicle_dynamics_st +from .utils import pid_steer, pid_accl + +class DynamicModel(Enum): + KS = 1 # Kinematic Single Track + ST = 2 # Single Track + MB = 3 + + @staticmethod + def from_string(model: str): + if model == "ks": + warnings.warn( + "Chosen model is KS. This is different from previous versions of the gym." + ) + return DynamicModel.KS + elif model == "st": + return DynamicModel.ST + else: + raise ValueError(f"Unknown model type {model}") + + def get_initial_state(self, pose=None): + # initialize zero state + if self == DynamicModel.KS: + # state is [x, y, steer_angle, vel, yaw_angle] + state = np.zeros(5) + elif self == DynamicModel.ST: + # state is [x, y, steer_angle, vel, yaw_angle, yaw_rate, slip_angle] + state = np.zeros(7) + else: + raise ValueError(f"Unknown model type {self}") + + # set initial pose if provided + if pose is not None: + state[0:2] = pose[0:2] + state[4] = pose[2] + + return state + + @property + def f_dynamics(self): + if self == DynamicModel.KS: + return vehicle_dynamics_ks + elif self == DynamicModel.ST: + return vehicle_dynamics_st + else: + raise ValueError(f"Unknown model type {self}") diff --git a/f1tenth_gym/envs/dynamic_models/kinematic.py b/f1tenth_gym/envs/dynamic_models/kinematic.py new file mode 100644 index 00000000..84feb08f --- /dev/null +++ b/f1tenth_gym/envs/dynamic_models/kinematic.py @@ -0,0 +1,94 @@ +import numpy as np +from numba import njit + +from .utils import steering_constraint, accl_constraints + +@njit(cache=True) +def vehicle_dynamics_ks( + x, + u_init, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): + """ + Single Track Kinematic Vehicle Dynamics. + Follows https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/-/blob/master/vehicleModels_commonRoad.pdf, section 5 + + Args: + x (numpy.ndarray (5, )): vehicle state vector (x0, x1, x2, x3, x4) + x0: x position in global coordinates + x1: y position in global coordinates + x2: steering angle of front wheels + x3: velocity in x direction + x4: yaw angle + u (numpy.ndarray (2, )): control input vector (u1, u2) + u1: steering angle velocity of front wheels + u2: longitudinal acceleration + mu (float): friction coefficient + C_Sf (float): cornering stiffness of front wheels + C_Sr (float): cornering stiffness of rear wheels + lf (float): distance from center of gravity to front axle + lr (float): distance from center of gravity to rear axle + h (float): height of center of gravity + m (float): mass of vehicle + I (float): moment of inertia of vehicle, about Z axis + s_min (float): minimum steering angle + s_max (float): maximum steering angle + sv_min (float): minimum steering velocity + sv_max (float): maximum steering velocity + v_switch (float): velocity above which the acceleration is no longer able to create wheel slip + a_max (float): maximum allowed acceleration + v_min (float): minimum allowed velocity + v_max (float): maximum allowed velocity + + Returns: + f (numpy.ndarray): right hand side of differential equations + """ + # Controls + X = x[0] + Y = x[1] + DELTA = x[2] + V = x[3] + PSI = x[4] + # Raw Actions + RAW_STEER_VEL = u_init[0] + RAW_ACCL = u_init[1] + # wheelbase + lwb = lf + lr + + # constraints + u = np.array( + [ + steering_constraint(DELTA, RAW_STEER_VEL, s_min, s_max, sv_min, sv_max), + accl_constraints(V, RAW_ACCL, v_switch, a_max, v_min, v_max), + ] + ) + # Corrected Actions + STEER_VEL = u[0] + ACCL = u[1] + + # system dynamics + f = np.array( + [ + V * np.cos(PSI), # X_DOT + V * np.sin(PSI), # Y_DOT + STEER_VEL, # DELTA_DOT + ACCL, # V_DOT + (V / lwb) * np.tan(DELTA), # PSI_DOT + ] + ) + return f diff --git a/f1tenth_gym/envs/dynamic_models/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body.py new file mode 100644 index 00000000..e69de29b diff --git a/f1tenth_gym/envs/dynamic_models/single_track.py b/f1tenth_gym/envs/dynamic_models/single_track.py new file mode 100644 index 00000000..16b53b7a --- /dev/null +++ b/f1tenth_gym/envs/dynamic_models/single_track.py @@ -0,0 +1,144 @@ +import numpy as np +from numba import njit + +from .utils import steering_constraint, accl_constraints + +@njit(cache=True) +def vehicle_dynamics_st( + x, + u_init, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): + """ + Single Track Vehicle Dynamics. + From https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/-/blob/master/vehicleModels_commonRoad.pdf, section 7 + + Args: + x (numpy.ndarray (7, )): vehicle state vector (x0, x1, x2, x3, x4, x5, x6) + x0: x position in global coordinates + x1: y position in global coordinates + x2: steering angle of front wheels + x3: velocity in x direction + x4:yaw angle + x5: yaw rate + x6: slip angle at vehicle center + u (numpy.ndarray (2, )): control input vector (u1, u2) + u1: steering angle velocity of front wheels + u2: longitudinal acceleration + mu (float): friction coefficient + C_Sf (float): cornering stiffness of front wheels + C_Sr (float): cornering stiffness of rear wheels + lf (float): distance from center of gravity to front axle + lr (float): distance from center of gravity to rear axle + h (float): height of center of gravity + m (float): mass of vehicle + I (float): moment of inertia of vehicle, about Z axis + s_min (float): minimum steering angle + s_max (float): maximum steering angle + sv_min (float): minimum steering velocity + sv_max (float): maximum steering velocity + v_switch (float): velocity above which the acceleration is no longer able to create wheel spin + a_max (float): maximum allowed acceleration + v_min (float): minimum allowed velocity + v_max (float): maximum allowed velocity + + Returns: + f (numpy.ndarray): right hand side of differential equations + """ + # States + X = x[0] + Y = x[1] + DELTA = x[2] + V = x[3] + PSI = x[4] + PSI_DOT = x[5] + BETA = x[6] + # We have to wrap the slip angle to [-pi, pi] + # BETA = np.arctan2(np.sin(BETA), np.cos(BETA)) + + # gravity constant m/s^2 + g = 9.81 + + # constraints + u = np.array( + [ + steering_constraint(DELTA, u_init[0], s_min, s_max, sv_min, sv_max), + accl_constraints(V, u_init[1], v_switch, a_max, v_min, v_max), + ] + ) + # Controls + STEER_VEL = u[0] + ACCL = u[1] + + # switch to kinematic model for small velocities + if V < 0.1: + # wheelbase + lwb = lf + lr + BETA_HAT = np.arctan(np.tan(DELTA) * lr / lwb) + BETA_DOT = ( + (1 / (1 + (np.tan(DELTA) * (lr / lwb)) ** 2)) + * (lr / (lwb * np.cos(DELTA) ** 2)) + * STEER_VEL + ) + f = np.array( + [ + V * np.cos(PSI + BETA_HAT), # X_DOT + V * np.sin(PSI + BETA_HAT), # Y_DOT + STEER_VEL, # DELTA_DOT + ACCL, # V_DOT + V * np.cos(BETA_HAT) * np.tan(DELTA) / lwb, # PSI_DOT + (1 / lwb) + * ( + ACCL * np.cos(BETA) * np.tan(DELTA) + - V * np.sin(BETA) * np.tan(DELTA) * BETA_DOT + + ((V * np.cos(BETA) * STEER_VEL) / (np.cos(DELTA) ** 2)) + ), # PSI_DOT_DOT + BETA_DOT, # BETA_DOT + ] + ) + else: + # system dynamics + glr = (g * lr - ACCL * h) + glf = (g * lf + ACCL * h) + f = np.array( + [ + V * np.cos(PSI + BETA), # X_DOT + V * np.sin(PSI + BETA), # Y_DOT + STEER_VEL, # DELTA_DOT + ACCL, # V_DOT + PSI_DOT, # PSI_DOT + ((mu * m) / (I * (lf + lr))) * ( + lf * C_Sf * (g * lr - ACCL * h) * DELTA + + ( + lr * C_Sr * (g * lf + ACCL * h) - lf * C_Sf * (g * lr - ACCL * h) + ) * BETA + - ( + lf * lf * C_Sf * (g * lr - ACCL * h) + lr * lr * C_Sr * (g * lf + ACCL * h) + ) * (PSI_DOT / V) + ), # PSI_DOT_DOT + (mu / (V * (lr + lf))) * ( + C_Sf * (g * lr - ACCL * h) * DELTA \ + - (C_Sr * (g * lf + ACCL * h) + C_Sf * (g * lr - ACCL * h)) * BETA + + ( + C_Sr * (g * lf + ACCL * h) * lr - C_Sf * (g * lr - ACCL * h) * lf + ) * (PSI_DOT / V) + ) - PSI_DOT, # BETA_DOT + ] + ) + + return f diff --git a/f1tenth_gym/envs/dynamic_models/tire_models.py b/f1tenth_gym/envs/dynamic_models/tire_models.py new file mode 100644 index 00000000..e69de29b diff --git a/f1tenth_gym/envs/dynamic_models/utils.py b/f1tenth_gym/envs/dynamic_models/utils.py new file mode 100644 index 00000000..2044e3c5 --- /dev/null +++ b/f1tenth_gym/envs/dynamic_models/utils.py @@ -0,0 +1,136 @@ +import numpy as np +from numba import njit + +@njit(cache=True) +def upper_accel_limit(vel, a_max, v_switch): + """ + Upper acceleration limit, adjusts the acceleration based on constraints + + Args: + vel (float): current velocity of the vehicle + a_max (float): maximum allowed acceleration, symmetrical + v_switch (float): switching velocity (velocity at which the acceleration is no longer able to create wheel spin) + + Returns: + positive_accel_limit (float): adjusted acceleration + """ + if vel > v_switch: + pos_limit = a_max * (v_switch / vel) + else: + pos_limit = a_max + + return pos_limit + + +@njit(cache=True) +def accl_constraints(vel, a_long_d, v_switch, a_max, v_min, v_max): + """ + Acceleration constraints, adjusts the acceleration based on constraints + + Args: + vel (float): current velocity of the vehicle + a_long_d (float): unconstrained desired acceleration in the direction of travel. + v_switch (float): switching velocity (velocity at which the acceleration is no longer able to create wheel spin) + a_max (float): maximum allowed acceleration, symmetrical + v_min (float): minimum allowed velocity + v_max (float): maximum allowed velocity + + Returns: + accl (float): adjusted acceleration + """ + + uac = upper_accel_limit(vel, a_max, v_switch) + + if (vel <= v_min and a_long_d <= 0) or (vel >= v_max and a_long_d >= 0): + a_long = 0.0 + elif a_long_d <= -a_max: + a_long = -a_max + elif a_long_d >= uac: + a_long = uac + else: + a_long = a_long_d + + return a_long + + +@njit(cache=True) +def steering_constraint( + steering_angle, steering_velocity, s_min, s_max, sv_min, sv_max +): + """ + Steering constraints, adjusts the steering velocity based on constraints + + Args: + steering_angle (float): current steering_angle of the vehicle + steering_velocity (float): unconstraint desired steering_velocity + s_min (float): minimum steering angle + s_max (float): maximum steering angle + sv_min (float): minimum steering velocity + sv_max (float): maximum steering velocity + + Returns: + steering_velocity (float): adjusted steering velocity + """ + + # constraint steering velocity + if (steering_angle <= s_min and steering_velocity <= 0) or ( + steering_angle >= s_max and steering_velocity >= 0 + ): + steering_velocity = 0.0 + elif steering_velocity <= sv_min: + steering_velocity = sv_min + elif steering_velocity >= sv_max: + steering_velocity = sv_max + + return steering_velocity + + +@njit(cache=True) +def pid_steer(steer, current_steer, max_sv): + # steering + steer_diff = steer - current_steer + if np.fabs(steer_diff) > 1e-4: + sv = (steer_diff / np.fabs(steer_diff)) * max_sv + else: + sv = 0.0 + + return sv + + +@njit(cache=True) +def pid_accl(speed, current_speed, max_a, max_v, min_v): + """ + Basic controller for speed/steer -> accl./steer vel. + + Args: + speed (float): desired input speed + steer (float): desired input steering angle + + Returns: + accl (float): desired input acceleration + sv (float): desired input steering velocity + """ + # accl + vel_diff = speed - current_speed + # currently forward + if current_speed > 0.0: + if vel_diff > 0: + # accelerate + kp = 10.0 * max_a / max_v + accl = kp * vel_diff + else: + # braking + kp = 10.0 * max_a / (-min_v) + accl = kp * vel_diff + # currently backwards + else: + if vel_diff > 0: + # braking + kp = 2.0 * max_a / max_v + accl = kp * vel_diff + else: + # accelerating + kp = 2.0 * max_a / (-min_v) + accl = kp * vel_diff + + return accl diff --git a/pyproject.toml b/pyproject.toml deleted file mode 100644 index a558e896..00000000 --- a/pyproject.toml +++ /dev/null @@ -1,61 +0,0 @@ -[tool.pytest.ini_options] -minversion = 6.0 -addopts = "-ra" -testpaths =[ - "tests", - "integration", -] - - -[tool.poetry] -name = "f1tenth_gym" -version = "1.0.0dev" -description = "Gym environment for F1TENTH" -license = "MIT" -authors = [ - "Hongrui Zheng", - "Renukanandan Tumu", - "Luigi Berducci", - "Ahmad Amine", - "Joseph Auckley", - "Matthew O'Kelly", - "Aman Sinha" -] -maintainers = [ - "Hongrui Zheng", -] -readme = "README.md" -homepage = "https://f1tenth.org" -repository = "https://github.com/f1tenth/f1tenth_gym" -documentation = "https://f1tenth-gym.readthedocs.io/en/latest/" -packages = [ - {include = "f1tenth_gym"}, -] - -[tool.poetry.dependencies] -python = ">=3.9" -gymnasium = "^0.29.1" -numpy = ">=1.18" -pillow = ">=9.0.1" -scipy = ">=1.7.3" -numba = ">=0.55.2" -PyYAML = ">=5.3.1" -pygame = "^2.5.2" -opencv-python = "^4.9.0.80" -yamldataclassconfig = "^1.5.0" -requests = "^2.31.0" -shapely = "^2.0.2" - -[tool.poetry.group.dev.dependencies] -pytest = "^7.4.4" -black = "^23.12.1" -ipykernel = "^6.29.0" -isort = "^5.13.2" -autoflake = "^2.2.1" -matplotlib = "^3.8.2" -flake8 = "^7.0.0" - - -[build-system] -requires = ["poetry-core"] -build-backend = "poetry.core.masonry.api" From 38b6fe451fe7e52f4ab482c2245734d50f86c5ec Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 21 Sep 2024 15:51:35 -0400 Subject: [PATCH 32/55] Refactored dynamics into a module --- f1tenth_gym/envs/dynamic_models.py | 511 -------------------- f1tenth_gym/envs/dynamic_models/__init__.py | 7 +- tests/test_dynamics.py | 89 +++- 3 files changed, 93 insertions(+), 514 deletions(-) delete mode 100644 f1tenth_gym/envs/dynamic_models.py diff --git a/f1tenth_gym/envs/dynamic_models.py b/f1tenth_gym/envs/dynamic_models.py deleted file mode 100644 index 91cc91da..00000000 --- a/f1tenth_gym/envs/dynamic_models.py +++ /dev/null @@ -1,511 +0,0 @@ -""" -Prototype of vehicle dynamics functions and classes for simulating 2D Single -Track dynamic model -Following the implementation of commanroad's Single Track Dynamics model -Original implementation: https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/ -Author: Hongrui Zheng, Renukanandan Tumu -""" -import warnings -from enum import Enum - -import numpy as np -from numba import njit - - -class DynamicModel(Enum): - KS = 1 # Kinematic Single Track - ST = 2 # Single Track - - @staticmethod - def from_string(model: str): - if model == "ks": - warnings.warn( - "Chosen model is KS. This is different from previous versions of the gym." - ) - return DynamicModel.KS - elif model == "st": - return DynamicModel.ST - else: - raise ValueError(f"Unknown model type {model}") - - def get_initial_state(self, pose=None): - # initialize zero state - if self == DynamicModel.KS: - # state is [x, y, steer_angle, vel, yaw_angle] - state = np.zeros(5) - elif self == DynamicModel.ST: - # state is [x, y, steer_angle, vel, yaw_angle, yaw_rate, slip_angle] - state = np.zeros(7) - else: - raise ValueError(f"Unknown model type {self}") - - # set initial pose if provided - if pose is not None: - state[0:2] = pose[0:2] - state[4] = pose[2] - - return state - - @property - def f_dynamics(self): - if self == DynamicModel.KS: - return vehicle_dynamics_ks - elif self == DynamicModel.ST: - return vehicle_dynamics_st - else: - raise ValueError(f"Unknown model type {self}") - - -@njit(cache=True) -def upper_accel_limit(vel, a_max, v_switch): - """ - Upper acceleration limit, adjusts the acceleration based on constraints - - Args: - vel (float): current velocity of the vehicle - a_max (float): maximum allowed acceleration, symmetrical - v_switch (float): switching velocity (velocity at which the acceleration is no longer able to create wheel spin) - - Returns: - positive_accel_limit (float): adjusted acceleration - """ - if vel > v_switch: - pos_limit = a_max * (v_switch / vel) - else: - pos_limit = a_max - - return pos_limit - - -@njit(cache=True) -def accl_constraints(vel, a_long_d, v_switch, a_max, v_min, v_max): - """ - Acceleration constraints, adjusts the acceleration based on constraints - - Args: - vel (float): current velocity of the vehicle - a_long_d (float): unconstrained desired acceleration in the direction of travel. - v_switch (float): switching velocity (velocity at which the acceleration is no longer able to create wheel spin) - a_max (float): maximum allowed acceleration, symmetrical - v_min (float): minimum allowed velocity - v_max (float): maximum allowed velocity - - Returns: - accl (float): adjusted acceleration - """ - - uac = upper_accel_limit(vel, a_max, v_switch) - - if (vel <= v_min and a_long_d <= 0) or (vel >= v_max and a_long_d >= 0): - a_long = 0.0 - elif a_long_d <= -a_max: - a_long = -a_max - elif a_long_d >= uac: - a_long = uac - else: - a_long = a_long_d - - return a_long - - -@njit(cache=True) -def steering_constraint( - steering_angle, steering_velocity, s_min, s_max, sv_min, sv_max -): - """ - Steering constraints, adjusts the steering velocity based on constraints - - Args: - steering_angle (float): current steering_angle of the vehicle - steering_velocity (float): unconstraint desired steering_velocity - s_min (float): minimum steering angle - s_max (float): maximum steering angle - sv_min (float): minimum steering velocity - sv_max (float): maximum steering velocity - - Returns: - steering_velocity (float): adjusted steering velocity - """ - - # constraint steering velocity - if (steering_angle <= s_min and steering_velocity <= 0) or ( - steering_angle >= s_max and steering_velocity >= 0 - ): - steering_velocity = 0.0 - elif steering_velocity <= sv_min: - steering_velocity = sv_min - elif steering_velocity >= sv_max: - steering_velocity = sv_max - - return steering_velocity - - -@njit(cache=True) -def vehicle_dynamics_ks( - x, - u_init, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): - """ - Single Track Kinematic Vehicle Dynamics. - Follows https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/-/blob/master/vehicleModels_commonRoad.pdf, section 5 - - Args: - x (numpy.ndarray (5, )): vehicle state vector (x0, x1, x2, x3, x4) - x0: x position in global coordinates - x1: y position in global coordinates - x2: steering angle of front wheels - x3: velocity in x direction - x4: yaw angle - u (numpy.ndarray (2, )): control input vector (u1, u2) - u1: steering angle velocity of front wheels - u2: longitudinal acceleration - mu (float): friction coefficient - C_Sf (float): cornering stiffness of front wheels - C_Sr (float): cornering stiffness of rear wheels - lf (float): distance from center of gravity to front axle - lr (float): distance from center of gravity to rear axle - h (float): height of center of gravity - m (float): mass of vehicle - I (float): moment of inertia of vehicle, about Z axis - s_min (float): minimum steering angle - s_max (float): maximum steering angle - sv_min (float): minimum steering velocity - sv_max (float): maximum steering velocity - v_switch (float): velocity above which the acceleration is no longer able to create wheel slip - a_max (float): maximum allowed acceleration - v_min (float): minimum allowed velocity - v_max (float): maximum allowed velocity - - Returns: - f (numpy.ndarray): right hand side of differential equations - """ - # Controls - X = x[0] - Y = x[1] - DELTA = x[2] - V = x[3] - PSI = x[4] - # Raw Actions - RAW_STEER_VEL = u_init[0] - RAW_ACCL = u_init[1] - # wheelbase - lwb = lf + lr - - # constraints - u = np.array( - [ - steering_constraint(DELTA, RAW_STEER_VEL, s_min, s_max, sv_min, sv_max), - accl_constraints(V, RAW_ACCL, v_switch, a_max, v_min, v_max), - ] - ) - # Corrected Actions - STEER_VEL = u[0] - ACCL = u[1] - - # system dynamics - f = np.array( - [ - V * np.cos(PSI), # X_DOT - V * np.sin(PSI), # Y_DOT - STEER_VEL, # DELTA_DOT - ACCL, # V_DOT - (V / lwb) * np.tan(DELTA), # PSI_DOT - ] - ) - return f - - -@njit(cache=True) -def vehicle_dynamics_st( - x, - u_init, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): - """ - Single Track Vehicle Dynamics. - From https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/-/blob/master/vehicleModels_commonRoad.pdf, section 7 - - Args: - x (numpy.ndarray (7, )): vehicle state vector (x0, x1, x2, x3, x4, x5, x6) - x0: x position in global coordinates - x1: y position in global coordinates - x2: steering angle of front wheels - x3: velocity in x direction - x4:yaw angle - x5: yaw rate - x6: slip angle at vehicle center - u (numpy.ndarray (2, )): control input vector (u1, u2) - u1: steering angle velocity of front wheels - u2: longitudinal acceleration - mu (float): friction coefficient - C_Sf (float): cornering stiffness of front wheels - C_Sr (float): cornering stiffness of rear wheels - lf (float): distance from center of gravity to front axle - lr (float): distance from center of gravity to rear axle - h (float): height of center of gravity - m (float): mass of vehicle - I (float): moment of inertia of vehicle, about Z axis - s_min (float): minimum steering angle - s_max (float): maximum steering angle - sv_min (float): minimum steering velocity - sv_max (float): maximum steering velocity - v_switch (float): velocity above which the acceleration is no longer able to create wheel spin - a_max (float): maximum allowed acceleration - v_min (float): minimum allowed velocity - v_max (float): maximum allowed velocity - - Returns: - f (numpy.ndarray): right hand side of differential equations - """ - # States - X = x[0] - Y = x[1] - DELTA = x[2] - V = x[3] - PSI = x[4] - PSI_DOT = x[5] - BETA = x[6] - # We have to wrap the slip angle to [-pi, pi] - # BETA = np.arctan2(np.sin(BETA), np.cos(BETA)) - - # gravity constant m/s^2 - g = 9.81 - - # constraints - u = np.array( - [ - steering_constraint(DELTA, u_init[0], s_min, s_max, sv_min, sv_max), - accl_constraints(V, u_init[1], v_switch, a_max, v_min, v_max), - ] - ) - # Controls - STEER_VEL = u[0] - ACCL = u[1] - - # switch to kinematic model for small velocities - if V < 0.1: - # wheelbase - lwb = lf + lr - BETA_HAT = np.arctan(np.tan(DELTA) * lr / lwb) - BETA_DOT = ( - (1 / (1 + (np.tan(DELTA) * (lr / lwb)) ** 2)) - * (lr / (lwb * np.cos(DELTA) ** 2)) - * STEER_VEL - ) - f = np.array( - [ - V * np.cos(PSI + BETA_HAT), # X_DOT - V * np.sin(PSI + BETA_HAT), # Y_DOT - STEER_VEL, # DELTA_DOT - ACCL, # V_DOT - V * np.cos(BETA_HAT) * np.tan(DELTA) / lwb, # PSI_DOT - (1 / lwb) - * ( - ACCL * np.cos(BETA) * np.tan(DELTA) - - V * np.sin(BETA) * np.tan(DELTA) * BETA_DOT - + ((V * np.cos(BETA) * STEER_VEL) / (np.cos(DELTA) ** 2)) - ), # PSI_DOT_DOT - BETA_DOT, # BETA_DOT - ] - ) - else: - # system dynamics - glr = (g * lr - ACCL * h) - glf = (g * lf + ACCL * h) - f = np.array( - [ - V * np.cos(PSI + BETA), # X_DOT - V * np.sin(PSI + BETA), # Y_DOT - STEER_VEL, # DELTA_DOT - ACCL, # V_DOT - PSI_DOT, # PSI_DOT - ((mu * m) / (I * (lf + lr))) * ( - lf * C_Sf * (g * lr - ACCL * h) * DELTA - + ( - lr * C_Sr * (g * lf + ACCL * h) - lf * C_Sf * (g * lr - ACCL * h) - ) * BETA - - ( - lf * lf * C_Sf * (g * lr - ACCL * h) + lr * lr * C_Sr * (g * lf + ACCL * h) - ) * (PSI_DOT / V) - ), # PSI_DOT_DOT - (mu / (V * (lr + lf))) * ( - C_Sf * (g * lr - ACCL * h) * DELTA \ - - (C_Sr * (g * lf + ACCL * h) + C_Sf * (g * lr - ACCL * h)) * BETA - + ( - C_Sr * (g * lf + ACCL * h) * lr - C_Sf * (g * lr - ACCL * h) * lf - ) * (PSI_DOT / V) - ) - PSI_DOT, # BETA_DOT - ] - ) - - return f - - -@njit(cache=True) -def pid_steer(steer, current_steer, max_sv): - # steering - steer_diff = steer - current_steer - if np.fabs(steer_diff) > 1e-4: - sv = (steer_diff / np.fabs(steer_diff)) * max_sv - else: - sv = 0.0 - - return sv - - -@njit(cache=True) -def pid_accl(speed, current_speed, max_a, max_v, min_v): - """ - Basic controller for speed/steer -> accl./steer vel. - - Args: - speed (float): desired input speed - steer (float): desired input steering angle - - Returns: - accl (float): desired input acceleration - sv (float): desired input steering velocity - """ - # accl - vel_diff = speed - current_speed - # currently forward - if current_speed > 0.0: - if vel_diff > 0: - # accelerate - kp = 10.0 * max_a / max_v - accl = kp * vel_diff - else: - # braking - kp = 10.0 * max_a / (-min_v) - accl = kp * vel_diff - # currently backwards - else: - if vel_diff > 0: - # braking - kp = 2.0 * max_a / max_v - accl = kp * vel_diff - else: - # accelerating - kp = 2.0 * max_a / (-min_v) - accl = kp * vel_diff - - return accl - - -def func_KS( - x, - t, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): - f = vehicle_dynamics_ks( - x, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, - ) - return f - - -def func_ST( - x, - t, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): - f = vehicle_dynamics_st( - x, - u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, - ) - return f diff --git a/f1tenth_gym/envs/dynamic_models/__init__.py b/f1tenth_gym/envs/dynamic_models/__init__.py index 10f0c507..3f0bfaf6 100644 --- a/f1tenth_gym/envs/dynamic_models/__init__.py +++ b/f1tenth_gym/envs/dynamic_models/__init__.py @@ -13,7 +13,7 @@ class DynamicModel(Enum): KS = 1 # Kinematic Single Track ST = 2 # Single Track - MB = 3 + MB = 3 # Multi-body Model @staticmethod def from_string(model: str): @@ -24,6 +24,8 @@ def from_string(model: str): return DynamicModel.KS elif model == "st": return DynamicModel.ST + elif model == "mb": + return DynamicModel.MB else: raise ValueError(f"Unknown model type {model}") @@ -35,6 +37,9 @@ def get_initial_state(self, pose=None): elif self == DynamicModel.ST: # state is [x, y, steer_angle, vel, yaw_angle, yaw_rate, slip_angle] state = np.zeros(7) + elif self == DynamicModel.MB: + # state is a 29D vector + state = np.zeros(29) else: raise ValueError(f"Unknown model type {self}") diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index 598cb0e4..39fb6c1f 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -26,10 +26,95 @@ from f1tenth_gym.envs.dynamic_models import ( vehicle_dynamics_ks, vehicle_dynamics_st, - func_KS, - func_ST, ) +def func_KS( + x, + t, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): + f = vehicle_dynamics_ks( + x, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, + ) + return f + + +def func_ST( + x, + t, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, +): + f = vehicle_dynamics_st( + x, + u, + mu, + C_Sf, + C_Sr, + lf, + lr, + h, + m, + I, + s_min, + s_max, + sv_min, + sv_max, + v_switch, + a_max, + v_min, + v_max, + ) + return f + class DynamicsTest(unittest.TestCase): def setUp(self): From 13970c398c5536b452e989a7d52bb7e7bf98b752 Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 21 Sep 2024 16:06:49 -0400 Subject: [PATCH 33/55] Replaced pyproject.toml --- pyproject.toml | 60 ++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 60 insertions(+) create mode 100644 pyproject.toml diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 00000000..b0a72ef2 --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,60 @@ +[tool.pytest.ini_options] +minversion = 6.0 +addopts = "-ra" +testpaths =[ + "tests", + "integration", +] + +[tool.poetry] +name = "f1tenth_gym" +version = "1.0.0dev" +description = "Gym environment for F1TENTH" +license = "MIT" +authors = [ + "Hongrui Zheng", + "Renukanandan Tumu", + "Luigi Berducci", + "Ahmad Amine", + "Joseph Auckley", + "Matthew O'Kelly", + "Aman Sinha" +] +maintainers = [ + "Hongrui Zheng", +] +readme = "README.md" +homepage = "https://f1tenth.org" +repository = "https://github.com/f1tenth/f1tenth_gym" +documentation = "https://f1tenth-gym.readthedocs.io/en/latest/" +packages = [ + {include = "f1tenth_gym"}, +] + +[tool.poetry.dependencies] +python = ">=3.9" +gymnasium = "^0.29.1" +numpy = ">=1.18" +pillow = ">=9.0.1" +scipy = ">=1.7.3" +numba = ">=0.55.2" +PyYAML = ">=5.3.1" +pygame = "^2.5.2" +opencv-python = "^4.9.0.80" +yamldataclassconfig = "^1.5.0" +requests = "^2.31.0" +shapely = "^2.0.2" + +[tool.poetry.group.dev.dependencies] +pytest = "^7.4.4" +black = "^23.12.1" +ipykernel = "^6.29.0" +isort = "^5.13.2" +autoflake = "^2.2.1" +matplotlib = "^3.8.2" +flake8 = "^7.0.0" + + +[build-system] +requires = ["poetry-core"] +build-backend = "poetry.core.masonry.api" From 45a2816e8b2f2b36f9189b2bc9537966729ab112 Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 21 Sep 2024 17:48:51 -0400 Subject: [PATCH 34/55] Fixed errors so tests run. --- f1tenth_gym/envs/f110_env.py | 40 ++++--------- f1tenth_gym/envs/rendering/__init__.py | 6 +- poetry.lock | 80 +++++++++++++++++++++++++- 3 files changed, 94 insertions(+), 32 deletions(-) diff --git a/f1tenth_gym/envs/f110_env.py b/f1tenth_gym/envs/f110_env.py index ba301e76..f6b62916 100644 --- a/f1tenth_gym/envs/f110_env.py +++ b/f1tenth_gym/envs/f110_env.py @@ -27,25 +27,21 @@ # gym imports import gymnasium as gym -from .action import (CarAction, - from_single_to_multi_action_space) -from .integrator import IntegratorType -from .rendering import make_renderer +# others +import numpy as np -from .track import Track +from .action import CarAction, from_single_to_multi_action_space # base classes -from .base_classes import Simulator, DynamicModel +from .base_classes import DynamicModel, Simulator +from .integrator import IntegratorType from .observation import observation_factory +from .rendering import make_renderer from .reset import make_reset_fn from .track import Track from .utils import deep_update -# others -import numpy as np - - class F110Env(gym.Env): """ OpenAI gym environment for F1TENTH @@ -143,14 +139,14 @@ def __init__(self, config: dict = None, render_mode=None, **kwargs): model=self.model, action_type=self.action_type, ) - self.sim.set_map(self.map, config["scale"]) + self.sim.set_map(self.map, self.config["scale"]) if isinstance(self.map, Track): self.track = self.map else: self.track = Track.from_track_name( self.map, - track_scale=config["scale"], + track_scale=self.config["scale"], ) # load track in gym env for convenience # observations @@ -202,7 +198,6 @@ def fullscale_vehicle_params(cls) -> dict: "I": 1538.8533713561394, "width": 1.674, "length": 4.298, - # steering constraints "s_min": -0.91, "s_max": 0.91, @@ -212,17 +207,15 @@ def fullscale_vehicle_params(cls) -> dict: "kappa_dot_max": 0.4, # maximum curvature rate rate "kappa_dot_dot_max": 20, - # Longitudinal constraints "v_switch": 4.755, "a_max": 11.5, "v_min": -13.9, "v_max": 45.8, # maximum longitudinal jerk [m/s^3] - "j_max": 10.0e+3, + "j_max": 10.0e3, # maximum longitudinal jerk change [m/s^4] "j_dot_max": 10.0e3, - # Extra parameters (for future use in multibody simulation) # sprung mass [kg] SMASS "m_s": 1094.542720290477, @@ -230,7 +223,6 @@ def fullscale_vehicle_params(cls) -> dict: "m_uf": 65.67256321742863, # unsprung mass rear [kg] UMASSR "m_ur": 65.67256321742863, - # moments of inertia of sprung mass # moment of inertia for sprung mass in roll [kg m^2] IXS "I_Phi_s": 244.04723069965206, @@ -240,7 +232,6 @@ def fullscale_vehicle_params(cls) -> dict: "I_z": 1538.8533713561394, # moment of inertia cross product [kg m^2] IXZ "I_xz_s": 0.0, - # suspension parameters # suspension spring rate (front) [N/m] KSF "K_sf": 21898.332429625985, @@ -250,7 +241,6 @@ def fullscale_vehicle_params(cls) -> dict: "K_sr": 21898.332429625985, # suspension damping rate (rear) [N s/m] KSDR "K_sdr": 1459.3902937206362, - # geometric parameters # track width front [m] TRWF "T_f": 1.389888, @@ -258,7 +248,6 @@ def fullscale_vehicle_params(cls) -> dict: "T_r": 1.423416, # lateral spring rate at compliant compliant pin joint between M_s and M_u [N/m] KRAS "K_ras": 175186.65943700788, - # auxiliary torsion roll stiffness per axle (normally negative) (front) [N m/rad] KTSF "K_tsf": -12880.270509148304, # auxiliary torsion roll stiffness per axle (normally negative) (rear) [N m/rad] KTSR @@ -267,33 +256,27 @@ def fullscale_vehicle_params(cls) -> dict: "K_rad": 10215.732056044453, # vertical spring rate of tire [N/m] KZT "K_zt": 189785.5477234252, - # center of gravity height of total mass [m] HCG (mainly required for conversion to other vehicle models) "h_cg": 0.5577840000000001, # height of roll axis above ground (front) [m] HRAF "h_raf": 0.0, # height of roll axis above ground (rear) [m] HRAR "h_rar": 0.0, - # M_s center of gravity above ground [m] HS "h_s": 0.59436, - # moment of inertia for unsprung mass about x-axis (front) [kg m^2] IXUF "I_uf": 32.53963075995361, # moment of inertia for unsprung mass about x-axis (rear) [kg m^2] IXUR "I_ur": 32.53963075995361, # wheel inertia, from internet forum for 235/65 R 17 [kg m^2] "I_y_w": 1.7, - # lateral compliance rate of tire, wheel, and suspension, per tire [m/N] KLT "K_lt": 1.0278264878518764e-05, # effective wheel/tire radius chosen as tire rolling radius RR taken from ADAMS documentation [m] "R_w": 0.344, - # split of brake and engine torque "T_sb": 0.76, "T_se": 1, - # suspension parameters # [rad/m] DF "D_f": -0.6233595800524934, @@ -303,7 +286,6 @@ def fullscale_vehicle_params(cls) -> dict: "E_f": 0, # [needs conversion if nonzero] ER "E_r": 0, - } return params @@ -369,7 +351,9 @@ def configure(self, config: dict) -> None: if hasattr(self, "action_space"): # if some parameters changed, recompute action space - self.action_type = CarAction(self.config["control_input"], params=self.params) + self.action_type = CarAction( + self.config["control_input"], params=self.params + ) self.action_space = from_single_to_multi_action_space( self.action_type.space, self.num_agents ) diff --git a/f1tenth_gym/envs/rendering/__init__.py b/f1tenth_gym/envs/rendering/__init__.py index ea6ac128..bcfa6bfb 100644 --- a/f1tenth_gym/envs/rendering/__init__.py +++ b/f1tenth_gym/envs/rendering/__init__.py @@ -2,12 +2,12 @@ from typing import Any, Optional from .renderer import RenderSpec, EnvRenderer -from ..track import Track +# from ..track import Track This is due to a circular import def make_renderer( params: dict[str, Any], - track: Track, + track: "Track", agent_ids: list[str], render_mode: Optional[str] = None, render_fps: Optional[int] = 100, @@ -33,7 +33,7 @@ def make_renderer( if render_spec.render_type == "pygame": from .rendering_pygame import PygameEnvRenderer as EnvRenderer - elif render_spec.render_type == "pyqt6": + elif render_spec.render_type == "pyqt6": from .rendering_pyqt import PyQtEnvRenderer as EnvRenderer else: raise ValueError(f"Unknown render type: {render_spec.render_type}") diff --git a/poetry.lock b/poetry.lock index d1b4be77..2a6de40f 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1644,6 +1644,84 @@ files = [ [package.extras] diagrams = ["jinja2", "railroad-diagrams"] +[[package]] +name = "pyqt6" +version = "6.7.1" +description = "Python bindings for the Qt cross platform application toolkit" +optional = false +python-versions = ">=3.8" +files = [ + {file = "PyQt6-6.7.1-1-cp38-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:7f397f4b38b23b5588eb2c0933510deb953d96b1f0323a916c4839c2a66ccccc"}, + {file = "PyQt6-6.7.1-1-cp38-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:c2f202b7941aa74e5c7e1463a6f27d9131dbc1e6cabe85571d7364f5b3de7397"}, + {file = "PyQt6-6.7.1-cp38-abi3-macosx_11_0_universal2.whl", hash = "sha256:f053378e3aef6248fa612c8afddda17f942fb63f9fe8a9aeb2a6b6b4cbb0eba9"}, + {file = "PyQt6-6.7.1-cp38-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:0adb7914c732ad1dee46d9cec838a98cb2b11bc38cc3b7b36fbd8701ae64bf47"}, + {file = "PyQt6-6.7.1-cp38-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:2d771fa0981514cb1ee937633dfa64f14caa902707d9afffab66677f3a73e3da"}, + {file = "PyQt6-6.7.1-cp38-abi3-win_amd64.whl", hash = "sha256:fa3954698233fe286a8afc477b84d8517f0788eb46b74da69d3ccc0170d3714c"}, + {file = "PyQt6-6.7.1.tar.gz", hash = "sha256:3672a82ccd3a62e99ab200a13903421e2928e399fda25ced98d140313ad59cb9"}, +] + +[package.dependencies] +PyQt6-Qt6 = ">=6.7.0,<6.8.0" +PyQt6-sip = ">=13.8,<14" + +[[package]] +name = "pyqt6-qt6" +version = "6.7.2" +description = "The subset of a Qt installation needed by PyQt6." +optional = false +python-versions = "*" +files = [ + {file = "PyQt6_Qt6-6.7.2-py3-none-macosx_10_14_x86_64.whl", hash = "sha256:065415589219a2f364aba29d6a98920bb32810286301acbfa157e522d30369e3"}, + {file = "PyQt6_Qt6-6.7.2-py3-none-macosx_11_0_arm64.whl", hash = "sha256:7f817efa86a0e8eda9152c85b73405463fbf3266299090f32bbb2266da540ead"}, + {file = "PyQt6_Qt6-6.7.2-py3-none-manylinux_2_28_aarch64.whl", hash = "sha256:05f2c7d195d316d9e678a92ecac0252a24ed175bd2444cc6077441807d756580"}, + {file = "PyQt6_Qt6-6.7.2-py3-none-manylinux_2_28_x86_64.whl", hash = "sha256:fc93945eaef4536d68bd53566535efcbe78a7c05c2a533790a8fd022bac8bfaa"}, + {file = "PyQt6_Qt6-6.7.2-py3-none-win_amd64.whl", hash = "sha256:b2d7e5ddb1b9764cd60f1d730fa7bf7a1f0f61b2630967c81761d3d0a5a8a2e0"}, +] + +[[package]] +name = "pyqt6-sip" +version = "13.8.0" +description = "The sip module support for PyQt6" +optional = false +python-versions = ">=3.8" +files = [ + {file = "PyQt6_sip-13.8.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:cedd554c643e54c4c2e12b5874781a87441a1b405acf3650a4a2e1df42aae231"}, + {file = "PyQt6_sip-13.8.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f57275b5af774529f9838adcfb58869ba3ebdaf805daea113bb0697a96a3f3cb"}, + {file = "PyQt6_sip-13.8.0-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:835ed22eab977f75fd77e60d4ff308a1fa794b1d0c04849311f36d2a080cdf3b"}, + {file = "PyQt6_sip-13.8.0-cp310-cp310-win_amd64.whl", hash = "sha256:d8b22a6850917c68ce83fc152a8b606ecb2efaaeed35be53110468885d6cdd9d"}, + {file = "PyQt6_sip-13.8.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b203b6fbae4a8f2d27f35b7df46200057033d9ecd9134bcf30e3eab66d43572c"}, + {file = "PyQt6_sip-13.8.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:beaddc1ec96b342f4e239702f91802706a80cb403166c2da318cec4ad8b790cb"}, + {file = "PyQt6_sip-13.8.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:a5c086b7c9c7996ea9b7522646cc24eebbf3591ec9dd38f65c0a3fdb0dbeaac7"}, + {file = "PyQt6_sip-13.8.0-cp311-cp311-win_amd64.whl", hash = "sha256:dd168667addf01f8a4b0fa7755323e43e4cd12ca4bade558c61f713a5d48ba1a"}, + {file = "PyQt6_sip-13.8.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:33d9b399fc9c9dc99496266842b0fb2735d924604774e97cf9b555667cc0fc59"}, + {file = "PyQt6_sip-13.8.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:056af69d1d8d28d5968066ec5da908afd82fc0be07b67cf2b84b9f02228416ce"}, + {file = "PyQt6_sip-13.8.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:08dd81037a2864982ece2bf9891f3bf4558e247034e112993ea1a3fe239458cb"}, + {file = "PyQt6_sip-13.8.0-cp312-cp312-win_amd64.whl", hash = "sha256:fbb249b82c53180f1420571ece5dc24fea1188ba435923edd055599dffe7abfb"}, + {file = "PyQt6_sip-13.8.0-cp38-cp38-macosx_11_0_universal2.whl", hash = "sha256:6bce6bc5870d9e87efe5338b1ee4a7b9d7d26cdd16a79a5757d80b6f25e71edc"}, + {file = "PyQt6_sip-13.8.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cd81144b0770084e8005d3a121c9382e6f9bc8d0bb320dd618718ffe5090e0e6"}, + {file = "PyQt6_sip-13.8.0-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:755beb5d271d081e56618fb30342cdd901464f721450495cb7cb0212764da89e"}, + {file = "PyQt6_sip-13.8.0-cp38-cp38-win_amd64.whl", hash = "sha256:7a0bbc0918eab5b6351735d40cf22cbfa5aa2476b55e0d5fe881aeed7d871c29"}, + {file = "PyQt6_sip-13.8.0-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:7f84c472afdc7d316ff683f63129350d645ef82d9b3fd75a609b08472d1f7291"}, + {file = "PyQt6_sip-13.8.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b1bf29e95f10a8a00819dac804ca7e5eba5fc1769adcd74c837c11477bf81954"}, + {file = "PyQt6_sip-13.8.0-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:9ea9223c94906efd68148f12ae45b51a21d67e86704225ddc92bce9c54e4d93c"}, + {file = "PyQt6_sip-13.8.0-cp39-cp39-win_amd64.whl", hash = "sha256:2559afa68825d08de09d71c42f3b6ad839dcc30f91e7c6d0785e07830d5541a5"}, + {file = "PyQt6_sip-13.8.0.tar.gz", hash = "sha256:2f74cf3d6d9cab5152bd9f49d570b2dfb87553ebb5c4919abfde27f5b9fd69d4"}, +] + +[[package]] +name = "pyqtgraph" +version = "0.13.7" +description = "Scientific Graphics and GUI Library for Python" +optional = false +python-versions = ">=3.9" +files = [ + {file = "pyqtgraph-0.13.7-py3-none-any.whl", hash = "sha256:7754edbefb6c367fa0dfb176e2d0610da3ada20aa7a5318516c74af5fb72bf7a"}, + {file = "pyqtgraph-0.13.7.tar.gz", hash = "sha256:64f84f1935c6996d0e09b1ee66fe478a7771e3ca6f3aaa05f00f6e068321d9e3"}, +] + +[package.dependencies] +numpy = ">=1.22.0" + [[package]] name = "pytest" version = "7.4.4" @@ -2174,4 +2252,4 @@ type = ["pytest-mypy"] [metadata] lock-version = "2.0" python-versions = ">=3.9" -content-hash = "efdbfe91976ae78442e45faa2c5eda3e54ccbf6d92323c504fcedf0ac3637dcc" +content-hash = "122155f8f9834afa2311682f69cf154059146c4f15599cb87c4f7db9a7d19bb4" From 3052c43b23010f3ac8cb1054dd76a4865c0677c4 Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 21 Sep 2024 17:57:56 -0400 Subject: [PATCH 35/55] Updated so KeyboardInterrupt does not segfault on macOS --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 71 ++++++++++---------- 1 file changed, 35 insertions(+), 36 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index d4010c28..0054066d 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -2,6 +2,7 @@ import logging import math from typing import Any, Callable, Optional +import signal import cv2 import numpy as np @@ -52,7 +53,7 @@ def __init__( render_mode : str rendering mode in ["human", "human_fast", "rgb_array"] render_fps : int - number of frames per second + number of frames per second """ super().__init__() self.params = params @@ -71,8 +72,10 @@ def __init__( self.app = QtWidgets.QApplication([]) self.window = pg.GraphicsLayoutWidget() self.window.setWindowTitle("F1Tenth Gym") - self.window.setGeometry(0, 0, self.render_spec.window_size, self.render_spec.window_size) - self.canvas : pg.PlotItem = self.window.addPlot() + self.window.setGeometry( + 0, 0, self.render_spec.window_size, self.render_spec.window_size + ) + self.canvas: pg.PlotItem = self.window.addPlot() # Disable interactivity self.canvas.setMouseEnabled(x=False, y=False) # Disable mouse panning & zooming @@ -84,33 +87,29 @@ def __init__( legend.mouseDragEvent = lambda *args, **kwargs: None legend.hoverEvent = lambda *args, **kwargs: None # self.scene() is a pyqtgraph.GraphicsScene.GraphicsScene.GraphicsScene - self.window.scene().sigMouseClicked.connect(self.mouse_clicked) + self.window.scene().sigMouseClicked.connect(self.mouse_clicked) self.window.keyPressEvent = self.key_pressed # Remove axes - self.canvas.hideAxis('bottom') - self.canvas.hideAxis('left') + self.canvas.hideAxis("bottom") + self.canvas.hideAxis("left") - # setting plot window background color to yellow - self.window.setBackground('w') + # setting plot window background color to yellow + self.window.setBackground("w") # fps and time renderer self.clock = FrameCounter() - self.fps_renderer = TextObject( - parent=self.canvas, position="bottom_left" - ) - self.time_renderer = TextObject( - parent=self.canvas, position="bottom_right" - ) + self.fps_renderer = TextObject(parent=self.canvas, position="bottom_left") + self.time_renderer = TextObject(parent=self.canvas, position="bottom_right") self.bottom_info_renderer = TextObject( parent=self.canvas, position="bottom_center" ) - self.top_info_renderer = TextObject( - parent=self.canvas, position="top_center" - ) + self.top_info_renderer = TextObject(parent=self.canvas, position="top_center") if self.render_mode in ["human", "human_fast"]: - self.clock.sigFpsUpdate.connect(lambda fps: self.fps_renderer.render(f'FPS: {fps:.1f}')) + self.clock.sigFpsUpdate.connect( + lambda fps: self.fps_renderer.render(f"FPS: {fps:.1f}") + ) colors_rgb = [ [rgb for rgb in ImageColor.getcolor(c, "RGB")] @@ -139,7 +138,7 @@ def __init__( self.image_item = pg.ImageItem(track_map) # Example: Transformed display of ImageItem tr = QtGui.QTransform() # prepare ImageItem transformation: - # Translate image by the origin of the map + # Translate image by the origin of the map tr.translate(self.map_origin[0], self.map_origin[1]) # Scale image by the resolution of the map tr.scale(self.map_resolution, self.map_resolution) @@ -160,6 +159,8 @@ def __init__( self.follow_agent_flag: bool = False self.agent_to_follow: int = None + # Allow a KeyboardInterrupt to kill the window without segfaulting + signal.signal(signal.SIGINT, signal.SIG_DFL) self.window.show() def update(self, state: dict) -> None: @@ -202,7 +203,7 @@ def add_renderer_callback(self, callback_fn: Callable[[EnvRenderer], None]) -> N callback function to be called at every rendering step """ self.callbacks.append(callback_fn) - + def key_pressed(self, event: QtGui.QKeyEvent) -> None: """ Handle key press events. @@ -233,9 +234,7 @@ def mouse_clicked(self, event: QtGui.QMouseEvent) -> None: if self.agent_to_follow is None: self.agent_to_follow = 0 else: - self.agent_to_follow = (self.agent_to_follow + 1) % len( - self.agent_ids - ) + self.agent_to_follow = (self.agent_to_follow + 1) % len(self.agent_ids) self.active_map_renderer = "car" elif event.button() == QtCore.Qt.MouseButton.RightButton: @@ -245,9 +244,7 @@ def mouse_clicked(self, event: QtGui.QMouseEvent) -> None: if self.agent_to_follow is None: self.agent_to_follow = 0 else: - self.agent_to_follow = (self.agent_to_follow - 1) % len( - self.agent_ids - ) + self.agent_to_follow = (self.agent_to_follow - 1) % len(self.agent_ids) self.active_map_renderer = "car" elif event.button() == QtCore.Qt.MouseButton.MiddleButton: @@ -257,7 +254,7 @@ def mouse_clicked(self, event: QtGui.QMouseEvent) -> None: self.agent_to_follow = None self.active_map_renderer = "map" - + def render(self) -> Optional[np.ndarray]: """ Render the current state in a frame. @@ -269,7 +266,6 @@ def render(self) -> Optional[np.ndarray]: if render_mode is "rgb_array", returns the rendered frame as an array """ if self.draw_flag: - # draw cars for i in range(len(self.agent_ids)): self.cars[i].render() @@ -284,15 +280,13 @@ def render(self) -> Optional[np.ndarray]: self.canvas.setYRange(ego_y - 10, ego_y + 10) else: self.canvas.autoRange() - + agent_to_follow_id = ( self.agent_ids[self.agent_to_follow] if self.agent_to_follow is not None else None ) - self.bottom_info_renderer.render( - text=f"Focus on: {agent_to_follow_id}" - ) + self.bottom_info_renderer.render(text=f"Focus on: {agent_to_follow_id}") if self.render_spec.show_info: self.top_info_renderer.render(text=INSTRUCTION_TEXT) @@ -303,7 +297,7 @@ def render(self) -> Optional[np.ndarray]: if self.render_mode in ["human", "human_fast"]: assert self.window is not None - else: + else: # rgb_array # TODO: extract the frame from the canvas frame = None @@ -328,7 +322,13 @@ def render_points( size of the points in pixels, by default 1 """ return self.canvas.plot( - points[:, 0], points[:, 1], pen=None, symbol="o", symbolPen=pg.mkPen(color=color, width=0), symbolBrush=pg.mkBrush(color=color, width=0), symbolSize=size + points[:, 0], + points[:, 1], + pen=None, + symbol="o", + symbolPen=pg.mkPen(color=color, width=0), + symbolBrush=pg.mkBrush(color=color, width=0), + symbolSize=size, ) def render_lines( @@ -374,7 +374,7 @@ def render_closed_lines( """ # Append the first point to the end to close the loop points = np.vstack([points, points[0]]) - + pen = pg.mkPen(color=pg.mkColor(*color), width=size) pen.setCapStyle(pg.QtCore.Qt.PenCapStyle.RoundCap) pen.setJoinStyle(pg.QtCore.Qt.PenJoinStyle.RoundJoin) @@ -383,7 +383,6 @@ def render_closed_lines( points[:, 0], points[:, 1], pen=pen, cosmetic=True, antialias=True ) ## setting pen=None disables line drawing - def close(self) -> None: """ Close the rendering environment. From 4c9a5b9341abbf9cfb9b9b3ebbd87cc43afcc506 Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 21 Sep 2024 18:54:07 -0400 Subject: [PATCH 36/55] Fixed typing error --- f1tenth_gym/envs/base_classes.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/f1tenth_gym/envs/base_classes.py b/f1tenth_gym/envs/base_classes.py index e1ab03cf..57afa81b 100644 --- a/f1tenth_gym/envs/base_classes.py +++ b/f1tenth_gym/envs/base_classes.py @@ -26,12 +26,13 @@ Replacement of the old RaceCar, Simulator classes in C++ Author: Hongrui Zheng """ + from __future__ import annotations import numpy as np from .dynamic_models import DynamicModel from .action import CarAction from .collision_models import collision_multiple, get_vertices -from .integrator import EulerIntegrator, IntegratorType +from .integrator import EulerIntegrator, Integrator from .laser_models import ScanSimulator2D, check_ttc_jit, ray_cast from .track import Track @@ -380,7 +381,7 @@ def __init__( num_agents, seed, action_type: CarAction, - integrator=IntegratorType.RK4, + integrator=Integrator, model=DynamicModel.ST, time_step=0.01, ego_idx=0, From b1856c5f09c312b836d4d0e327ea9a72227d4ee4 Mon Sep 17 00:00:00 2001 From: nandant Date: Mon, 23 Sep 2024 23:32:15 +0200 Subject: [PATCH 37/55] Working MB commit --- f1tenth_gym/envs/base_classes.py | 4 +- f1tenth_gym/envs/dynamic_models/__init__.py | 13 +- f1tenth_gym/envs/dynamic_models/kinematic.py | 76 ++- f1tenth_gym/envs/dynamic_models/multi_body.py | 0 .../dynamic_models/multi_body/__init__.py | 121 ++++ .../dynamic_models/multi_body/multi_body.py | 596 ++++++++++++++++++ .../dynamic_models/multi_body/tire_model.py | 184 ++++++ .../envs/dynamic_models/single_track.py | 130 ++-- .../envs/dynamic_models/tire_models.py | 0 f1tenth_gym/envs/dynamic_models/utils.py | 1 + f1tenth_gym/envs/f110_env.py | 35 + f1tenth_gym/envs/integrator.py | 108 +--- 12 files changed, 1061 insertions(+), 207 deletions(-) delete mode 100644 f1tenth_gym/envs/dynamic_models/multi_body.py create mode 100644 f1tenth_gym/envs/dynamic_models/multi_body/__init__.py create mode 100644 f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py create mode 100644 f1tenth_gym/envs/dynamic_models/multi_body/tire_model.py delete mode 100644 f1tenth_gym/envs/dynamic_models/tire_models.py diff --git a/f1tenth_gym/envs/base_classes.py b/f1tenth_gym/envs/base_classes.py index 57afa81b..0dea4e6e 100644 --- a/f1tenth_gym/envs/base_classes.py +++ b/f1tenth_gym/envs/base_classes.py @@ -104,7 +104,7 @@ def __init__( self.model = model # state of the vehicle - self.state = self.model.get_initial_state() + self.state = self.model.get_initial_state(params=self.params) # pose of opponents in the world self.opp_poses = None @@ -205,7 +205,7 @@ def reset(self, pose): # clear collision indicator self.in_collision = False # init state from pose - self.state = self.model.get_initial_state(pose=pose) + self.state = self.model.get_initial_state(pose=pose, params=self.params) self.steer_buffer = np.empty((0,)) # reset scan random generator diff --git a/f1tenth_gym/envs/dynamic_models/__init__.py b/f1tenth_gym/envs/dynamic_models/__init__.py index 3f0bfaf6..9f79507c 100644 --- a/f1tenth_gym/envs/dynamic_models/__init__.py +++ b/f1tenth_gym/envs/dynamic_models/__init__.py @@ -2,14 +2,17 @@ This module contains the dynamic models available in the F1Tenth Gym. Each submodule contains a single model, and the equations or their source is documented alongside it. Many of the models are from the CommonRoad repository, available here: https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/ """ + import warnings from enum import Enum import numpy as np from .kinematic import vehicle_dynamics_ks from .single_track import vehicle_dynamics_st +from .multi_body import init_mb, vehicle_dynamics_mb from .utils import pid_steer, pid_accl + class DynamicModel(Enum): KS = 1 # Kinematic Single Track ST = 2 # Single Track @@ -29,7 +32,10 @@ def from_string(model: str): else: raise ValueError(f"Unknown model type {model}") - def get_initial_state(self, pose=None): + def get_initial_state(self, pose=None, params: dict = None): + # Assert that if self is MB, params is not None + if self == DynamicModel.MB and params is None: + raise ValueError("MultiBody model requires parameters to be provided.") # initialize zero state if self == DynamicModel.KS: # state is [x, y, steer_angle, vel, yaw_angle] @@ -48,6 +54,9 @@ def get_initial_state(self, pose=None): state[0:2] = pose[0:2] state[4] = pose[2] + # If state is MultiBody, we must inflate the state to 29D + if self == DynamicModel.MB: + state = init_mb(state, params) return state @property @@ -56,5 +65,7 @@ def f_dynamics(self): return vehicle_dynamics_ks elif self == DynamicModel.ST: return vehicle_dynamics_st + elif self == DynamicModel.MB: + return vehicle_dynamics_mb else: raise ValueError(f"Unknown model type {self}") diff --git a/f1tenth_gym/envs/dynamic_models/kinematic.py b/f1tenth_gym/envs/dynamic_models/kinematic.py index 84feb08f..1af38b03 100644 --- a/f1tenth_gym/envs/dynamic_models/kinematic.py +++ b/f1tenth_gym/envs/dynamic_models/kinematic.py @@ -3,27 +3,8 @@ from .utils import steering_constraint, accl_constraints -@njit(cache=True) -def vehicle_dynamics_ks( - x, - u_init, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): + +def vehicle_dynamics_ks(x: np.ndarray, u_init: np.ndarray, params: dict): """ Single Track Kinematic Vehicle Dynamics. Follows https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/-/blob/master/vehicleModels_commonRoad.pdf, section 5 @@ -38,22 +19,23 @@ def vehicle_dynamics_ks( u (numpy.ndarray (2, )): control input vector (u1, u2) u1: steering angle velocity of front wheels u2: longitudinal acceleration - mu (float): friction coefficient - C_Sf (float): cornering stiffness of front wheels - C_Sr (float): cornering stiffness of rear wheels - lf (float): distance from center of gravity to front axle - lr (float): distance from center of gravity to rear axle - h (float): height of center of gravity - m (float): mass of vehicle - I (float): moment of inertia of vehicle, about Z axis - s_min (float): minimum steering angle - s_max (float): maximum steering angle - sv_min (float): minimum steering velocity - sv_max (float): maximum steering velocity - v_switch (float): velocity above which the acceleration is no longer able to create wheel slip - a_max (float): maximum allowed acceleration - v_min (float): minimum allowed velocity - v_max (float): maximum allowed velocity + params (dict): dictionary containing the following parameters: + mu (float): friction coefficient + C_Sf (float): cornering stiffness of front wheels + C_Sr (float): cornering stiffness of rear wheels + lf (float): distance from center of gravity to front axle + lr (float): distance from center of gravity to rear axle + h (float): height of center of gravity + m (float): mass of vehicle + I (float): moment of inertia of vehicle, about Z axis + s_min (float): minimum steering angle + s_max (float): maximum steering angle + sv_min (float): minimum steering velocity + sv_max (float): maximum steering velocity + v_switch (float): velocity above which the acceleration is no longer able to create wheel slip + a_max (float): maximum allowed acceleration + v_min (float): minimum allowed velocity + v_max (float): maximum allowed velocity Returns: f (numpy.ndarray): right hand side of differential equations @@ -68,13 +50,27 @@ def vehicle_dynamics_ks( RAW_STEER_VEL = u_init[0] RAW_ACCL = u_init[1] # wheelbase - lwb = lf + lr + lwb = params["lf"] + params["lr"] # constraints u = np.array( [ - steering_constraint(DELTA, RAW_STEER_VEL, s_min, s_max, sv_min, sv_max), - accl_constraints(V, RAW_ACCL, v_switch, a_max, v_min, v_max), + steering_constraint( + DELTA, + RAW_STEER_VEL, + params["s_min"], + params["s_max"], + params["sv_min"], + params["sv_max"], + ), + accl_constraints( + V, + RAW_ACCL, + params["v_switch"], + params["a_max"], + params["v_min"], + params["v_max"], + ), ] ) # Corrected Actions diff --git a/f1tenth_gym/envs/dynamic_models/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body.py deleted file mode 100644 index e69de29b..00000000 diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/__init__.py b/f1tenth_gym/envs/dynamic_models/multi_body/__init__.py new file mode 100644 index 00000000..c6ef9afa --- /dev/null +++ b/f1tenth_gym/envs/dynamic_models/multi_body/__init__.py @@ -0,0 +1,121 @@ +""" +Multi-body model initialization functions +""" + +import numpy as np +from numba import njit + +from .multi_body import vehicle_dynamics_mb + + +def init_mb(init_state, params: dict) -> np.ndarray: + # init_MB - generates the initial state vector for the multi-body model + # + # Syntax: + # x0 = init_MB(init_state, p) + # + # Inputs: + # init_state - core initial states + # p - parameter vector + # + # Outputs: + # x0 - initial state vector + # + # Example: + # + # See also: --- + + # Author: Matthias Althoff + # Written: 11-January-2017 + # Last update: --- + # Last revision:--- + + ### Parameters + ## steering constraints + s_min = params["s_min"] # minimum steering angle [rad] + s_max = params["s_max"] # maximum steering angle [rad] + ## longitudinal constraints + v_min = params["v_min"] # minimum velocity [m/s] + v_max = params["v_max"] # minimum velocity [m/s] + ## masses + m_s = params["m_s"] # sprung mass [kg] SMASS + m_uf = params["m_uf"] # unsprung mass front [kg] UMASSF + m_ur = params["m_ur"] # unsprung mass rear [kg] UMASSR + ## axes distances + lf = params["lf"] + # distance from spring mass center of gravity to front axle [m] LENA + lr = params["lr"] + # distance from spring mass center of gravity to rear axle [m] LENB + + ## geometric parameters + K_zt = params["K_zt"] # vertical spring rate of tire [N/m] TSPRINGR + R_w = params["R_w"] + # effective wheel/tire radius chosen as tire rolling radius RR taken from ADAMS documentation [m] + # create equivalent bicycle parameters + g = 9.81 # [m/s^2] + + # obtain initial states from vector + sx0 = init_state[0] # x-position in a global coordinate system + sy0 = init_state[1] # y-position in a global coordinate system + delta0 = init_state[2] # steering angle of front wheels + vel0 = init_state[3] # speed of the car + Psi0 = init_state[4] # yaw angle + dotPsi0 = init_state[5] # yaw rate + beta0 = init_state[6] # slip angle + + if delta0 > s_max: + delta0 = s_max + + if delta0 < s_min: + delta0 = s_min + + if vel0 > v_max: + vel0 = v_max + + if vel0 < v_min: + vel0 = v_min + + # auxiliary initial states + F0_z_f = m_s * g * lr / (lf + lr) + m_uf * g + F0_z_r = m_s * g * lf / (lf + lr) + m_ur * g + + # sprung mass states + x0 = np.zeros((29,)) # init initial state vector + x0[0] = sx0 # x-position in a global coordinate system + x0[1] = sy0 # y-position in a global coordinate system + x0[2] = delta0 # steering angle of front wheels + x0[3] = np.cos(beta0) * vel0 # velocity in x-direction + x0[4] = Psi0 # yaw angle + x0[5] = dotPsi0 # yaw rate + x0[6] = 0 # roll angle + x0[7] = 0 # roll rate + x0[8] = 0 # pitch angle + x0[9] = 0 # pitch rate + x0[10] = np.sin(beta0) * vel0 # velocity in y-direction + x0[11] = 0 # z-position (zero height corresponds to steady state solution) + x0[12] = 0 # velocity in z-direction + + # unsprung mass states (front) + x0[13] = 0 # roll angle front + x0[14] = 0 # roll rate front + x0[15] = np.sin(beta0) * vel0 + lf * dotPsi0 # velocity in y-direction front + x0[16] = (F0_z_f) / (2 * K_zt) # z-position front + x0[17] = 0 # velocity in z-direction front + + # unsprung mass states (rear) + x0[18] = 0 # roll angle rear + x0[19] = 0 # roll rate rear + x0[20] = np.sin(beta0) * vel0 - lr * dotPsi0 # velocity in y-direction rear + x0[21] = (F0_z_r) / (2 * K_zt) # z-position rear + x0[22] = 0 # velocity in z-direction rear + + # wheel states + x0[23] = x0[3] / (R_w) # left front wheel angular speed + x0[24] = x0[3] / (R_w) # right front wheel angular speed + x0[25] = x0[3] / (R_w) # left rear wheel angular speed + x0[26] = x0[3] / (R_w) # right rear wheel angular speed + + x0[27] = 0 # delta_y_f + x0[28] = 0 # delta_y_r + + return x0 diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py new file mode 100644 index 00000000..102239f5 --- /dev/null +++ b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py @@ -0,0 +1,596 @@ +import numpy as np +from numba import njit + +from .tire_model import ( + formula_lateral, + formula_lateral_comb, + formula_longitudinal, + formula_longitudinal_comb, +) +from ..kinematic import vehicle_dynamics_ks + + +def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): + """ + vehicleDynamics_mb - multi-body vehicle dynamics based on the DoT (department of transportation) vehicle dynamics + reference point: center of mass + + Syntax: + f = vehicleDynamics_mb(x,u,p) + + Inputs: + :param x: vehicle state vector + :param uInit: vehicle input vector + :param params: vehicle parameter vector + + Outputs: + :return f: right-hand side of differential equations + """ + + # ------------- BEGIN CODE -------------- + + # set gravity constant + g = 9.81 # [m/s^2] + + # states + # x1 = x-position in a global coordinate system + # x2 = y-position in a global coordinate system + # x3 = steering angle of front wheels + # x4 = velocity in x-direction + # x5 = yaw angle + # x6 = yaw rate + + # x7 = roll angle + # x8 = roll rate + # x9 = pitch angle + # x10 = pitch rate + # x11 = velocity in y-direction + # x12 = z-position + # x13 = velocity in z-direction + + # x14 = roll angle front + # x15 = roll rate front + # x16 = velocity in y-direction front + # x17 = z-position front + # x18 = velocity in z-direction front + + # x19 = roll angle rear + # x20 = roll rate rear + # x21 = velocity in y-direction rear + # x22 = z-position rear + # x23 = velocity in z-direction rear + + # x24 = left front wheel angular speed + # x25 = right front wheel angular speed + # x26 = left rear wheel angular speed + # x27 = right rear wheel angular speed + + # x28 = delta_y_f + # x29 = delta_y_r + + # u1 = steering angle velocity of front wheels + # u2 = acceleration + + u = u_init + + # vehicle body dimensions + length = params["length"] # vehicle length [m] + width = params["width"] # vehicle width [m] + + # steering constraints + s_min = params["s_min"] # minimum steering angle [rad] + s_max = params["s_max"] # maximum steering angle [rad] + sv_min = params["sv_min"] # minimum steering velocity [rad/s] + sv_max = params["sv_max"] # maximum steering velocity [rad/s] + + # longitudinal constraints + v_min = params["s_min"] # minimum velocity [m/s] + v_max = params["s_max"] # minimum velocity [m/s] + v_switch = params["sv_min"] # switching velocity [m/s] + a_max = params["sv_max"] # maximum absolute acceleration [m/s^2] + + # masses + m = params["m"] # vehicle mass [kg] MASS + m_s = params["m_s"] # sprung mass [kg] SMASS + m_uf = params["m_uf"] # unsprung mass front [kg] UMASSF + m_ur = params["m_ur"] # unsprung mass rear [kg] UMASSR + + # axes distances + lf = params["lf"] + # distance from spring mass center of gravity to front axle [m] LENA + lr = params["lf"] + # distance from spring mass center of gravity to rear axle [m] LENB + + # moments of inertia of sprung mass + I_Phi_s = params["I_Phi_s"] + # moment of inertia for sprung mass in roll [kg m^2] IXS + I_y_s = params["I_y_s"] # moment of inertia for sprung mass in pitch [kg m^2] IYS + I_z = params["I_z"] # moment of inertia for sprung mass in yaw [kg m^2] IZZ + I_xz_s = params["I_xz_s"] # moment of inertia cross product [kg m^2] IXZ + + # suspension parameters + K_sf = params["K_sf"] # suspension spring rate (front) [N/m] KSF + K_sdf = params["K_sdf"] # suspension damping rate (front) [N s/m] KSDF + K_sr = params["K_sr"] # suspension spring rate (rear) [N/m] KSR + K_sdr = params["K_sdr"] # suspension damping rate (rear) [N s/m] KSDR + + # geometric parameters + T_f = params["T_f"] # track width front [m] TRWF + T_r = params["T_r"] # track width rear [m] TRWB + K_ras = params["K_ras"] + # lateral spring rate at compliant compliant pin joint between M_s and M_u [N/m] KRAS + + K_tsf = params["K_tsf"] + # auxiliary torsion roll stiffness per axle (normally negative) (front) [N m/rad] KTSF + K_tsr = params["K_tsr"] + # auxiliary torsion roll stiffness per axle (normally negative) (rear) [N m/rad] KTSR + K_rad = params["K_rad"] + # damping rate at compliant compliant pin joint between M_s and M_u [N s/m] KRADP + K_zt = params["K_zt"] # vertical spring rate of tire [N/m] TSPRINGR + + h_cg = params["h_cg"] + # center of gravity height of total mass [m] HCG (mainly required for conversion to other vehicle models) + h_raf = params["h_raf"] # height of roll axis above ground (front) [m] HRAF + h_rar = params["h_rar"] # height of roll axis above ground (rear) [m] HRAR + + h_s = params["h_s"] # M_s center of gravity above ground [m] HS + + I_uf = params["I_uf"] + # moment of inertia for unsprung mass about x-axis (front) [kg m^2] IXUF + I_ur = params["I_ur"] + # moment of inertia for unsprung mass about x-axis (rear) [kg m^2] IXUR + I_y_w = params["I_y_w"] + # wheel inertia, from internet forum for 235/65 R 17 [kg m^2] + + K_lt = params["K_lt"] + # lateral compliance rate of tire, wheel, and suspension, per tire [m/N] KLT + R_w = params["R_w"] + # effective wheel/tire radius chosen as tire rolling radius RR taken from ADAMS documentation [m] + + # split of brake and engine torque + T_sb = params["T_sb"] + T_se = params["T_se"] + + # suspension parameters + D_f = params["D_f"] # [rad/m] DF + D_r = params["D_r"] # [rad/m] DR + E_f = params["E_f"] # [needs conversion if nonzero] EF + E_r = params["E_r"] # [needs conversion if nonzero] ER + + use_kinematic = True if x[3] < 0.1 else False + + # consider steering and acceleration constraints - outside of the integration + # u = np.array([steering_constraint(x[2], u_init[0], s_min, s_max, sv_min, sv_max), accl_constraints(x[3], u_init[1], v_switch, a_max, v_min, v_max)]) + + # compute slip angle at cg - outside of the integration + # switch to kinematic model for small velocities handeled outside + if use_kinematic: + beta = 0.0 + else: + beta = np.arctan(x[10] / x[3]) + vel = np.sqrt(x[3] ** 2 + x[10] ** 2) + + # vertical tire forces + F_z_LF = (x[16] + R_w * (np.cos(x[13]) - 1) - 0.5 * T_f * np.sin(x[13])) * K_zt + F_z_RF = (x[16] + R_w * (np.cos(x[13]) - 1) + 0.5 * T_f * np.sin(x[13])) * K_zt + F_z_LR = (x[21] + R_w * (np.cos(x[18]) - 1) - 0.5 * T_r * np.sin(x[18])) * K_zt + F_z_RR = (x[21] + R_w * (np.cos(x[18]) - 1) + 0.5 * T_r * np.sin(x[18])) * K_zt + + # obtain individual tire speeds + u_w_lf = (x[3] + 0.5 * T_f * x[5]) * np.cos(x[2]) + (x[10] + lf * x[5]) * np.sin( + x[2] + ) + u_w_rf = (x[3] - 0.5 * T_f * x[5]) * np.cos(x[2]) + (x[10] + lf * x[5]) * np.sin( + x[2] + ) + u_w_lr = x[3] + 0.5 * T_r * x[5] + u_w_rr = x[3] - 0.5 * T_r * x[5] + + # negative wheel spin forbidden + u_w_lf = np.maximum(u_w_lf, 0.0) + u_w_rf = np.maximum(u_w_rf, 0.0) + u_w_lr = np.maximum(u_w_lr, 0.0) + u_w_rr = np.maximum(u_w_rr, 0.0) + # if u_w_lf < 0.0: + # u_w_lf *= 0 + # + # if u_w_rf < 0.0: + # u_w_rf *= 0 + # + # if u_w_lr < 0.0: + # u_w_lr *= 0 + # + # if u_w_rr < 0.0: + # u_w_rr *= 0 + + # compute longitudinal slip + # switch to kinematic model for small velocities + if use_kinematic: + s_lf = 0.0 + s_rf = 0.0 + s_lr = 0.0 + s_rr = 0.0 + else: + s_lf = 1 - R_w * x[23] / u_w_lf + s_rf = 1 - R_w * x[24] / u_w_rf + s_lr = 1 - R_w * x[25] / u_w_lr + s_rr = 1 - R_w * x[26] / u_w_rr + + # lateral slip angles + # switch to kinematic model for small velocities + if use_kinematic: + alpha_LF = 0.0 + alpha_RF = 0.0 + alpha_LR = 0.0 + alpha_RR = 0.0 + else: + alpha_LF = ( + np.arctan( + (x[10] + lf * x[5] - x[14] * (R_w - x[16])) / (x[3] + 0.5 * T_f * x[5]) + ) + - x[2] + ) + alpha_RF = ( + np.arctan( + (x[10] + lf * x[5] - x[14] * (R_w - x[16])) / (x[3] - 0.5 * T_f * x[5]) + ) + - x[2] + ) + alpha_LR = np.arctan( + (x[10] - lr * x[5] - x[19] * (R_w - x[21])) / (x[3] + 0.5 * T_r * x[5]) + ) + alpha_RR = np.arctan( + (x[10] - lr * x[5] - x[19] * (R_w - x[21])) / (x[3] - 0.5 * T_r * x[5]) + ) + + # auxiliary suspension movement + z_SLF = ( + (h_s - R_w + x[16] - x[11]) / np.cos(x[6]) + - h_s + + R_w + + lf * x[8] + + 0.5 * (x[6] - x[13]) * T_f + ) + z_SRF = ( + (h_s - R_w + x[16] - x[11]) / np.cos(x[6]) + - h_s + + R_w + + lf * x[8] + - 0.5 * (x[6] - x[13]) * T_f + ) + z_SLR = ( + (h_s - R_w + x[21] - x[11]) / np.cos(x[6]) + - h_s + + R_w + - lr * x[8] + + 0.5 * (x[6] - x[18]) * T_r + ) + z_SRR = ( + (h_s - R_w + x[21] - x[11]) / np.cos(x[6]) + - h_s + + R_w + - lr * x[8] + - 0.5 * (x[6] - x[18]) * T_r + ) + + dz_SLF = x[17] - x[12] + lf * x[9] + 0.5 * (x[7] - x[14]) * T_f + dz_SRF = x[17] - x[12] + lf * x[9] - 0.5 * (x[7] - x[14]) * T_f + dz_SLR = x[22] - x[12] - lr * x[9] + 0.5 * (x[7] - x[19]) * T_r + dz_SRR = x[22] - x[12] - lr * x[9] - 0.5 * (x[7] - x[19]) * T_r + + # camber angles + gamma_LF = x[6] + D_f * z_SLF + E_f * (z_SLF) ** 2 + gamma_RF = x[6] - D_f * z_SRF - E_f * (z_SRF) ** 2 + gamma_LR = x[6] + D_r * z_SLR + E_r * (z_SLR) ** 2 + gamma_RR = x[6] - D_r * z_SRR - E_r * (z_SRR) ** 2 + + # compute longitudinal tire forces using the magic formula for pure slip + F0_x_LF = formula_longitudinal(s_lf, gamma_LF, F_z_LF, params) + F0_x_RF = formula_longitudinal(s_rf, gamma_RF, F_z_RF, params) + F0_x_LR = formula_longitudinal(s_lr, gamma_LR, F_z_LR, params) + F0_x_RR = formula_longitudinal(s_rr, gamma_RR, F_z_RR, params) + + # compute lateral tire forces using the magic formula for pure slip + res = formula_lateral(alpha_LF, gamma_LF, F_z_LF, params) + F0_y_LF = res[0] + mu_y_LF = res[1] + res = formula_lateral(alpha_RF, gamma_RF, F_z_RF, params) + F0_y_RF = res[0] + mu_y_RF = res[1] + res = formula_lateral(alpha_LR, gamma_LR, F_z_LR, params) + F0_y_LR = res[0] + mu_y_LR = res[1] + res = formula_lateral(alpha_RR, gamma_RR, F_z_RR, params) + F0_y_RR = res[0] + mu_y_RR = res[1] + + # compute longitudinal tire forces using the magic formula for combined slip + F_x_LF = formula_longitudinal_comb(s_lf, alpha_LF, F0_x_LF, params) + F_x_RF = formula_longitudinal_comb(s_rf, alpha_RF, F0_x_RF, params) + F_x_LR = formula_longitudinal_comb(s_lr, alpha_LR, F0_x_LR, params) + F_x_RR = formula_longitudinal_comb(s_rr, alpha_RR, F0_x_RR, params) + + # compute lateral tire forces using the magic formula for combined slip + F_y_LF = formula_lateral_comb( + s_lf, alpha_LF, gamma_LF, mu_y_LF, F_z_LF, F0_y_LF, params + ) + F_y_RF = formula_lateral_comb( + s_rf, alpha_RF, gamma_RF, mu_y_RF, F_z_RF, F0_y_RF, params + ) + F_y_LR = formula_lateral_comb( + s_lr, alpha_LR, gamma_LR, mu_y_LR, F_z_LR, F0_y_LR, params + ) + F_y_RR = formula_lateral_comb( + s_rr, alpha_RR, gamma_RR, mu_y_RR, F_z_RR, F0_y_RR, params + ) + + # auxiliary movements for compliant joint equations + delta_z_f = h_s - R_w + x[16] - x[11] + delta_z_r = h_s - R_w + x[21] - x[11] + + delta_phi_f = x[6] - x[13] + delta_phi_r = x[6] - x[18] + + dot_delta_phi_f = x[7] - x[14] + dot_delta_phi_r = x[7] - x[19] + + dot_delta_z_f = x[17] - x[12] + dot_delta_z_r = x[22] - x[12] + + dot_delta_y_f = x[10] + lf * x[5] - x[15] + dot_delta_y_r = x[10] - lr * x[5] - x[20] + + delta_f = ( + delta_z_f * np.sin(x[6]) + - x[27] * np.cos(x[6]) + - (h_raf - R_w) * np.sin(delta_phi_f) + ) + delta_r = ( + delta_z_r * np.sin(x[6]) + - x[28] * np.cos(x[6]) + - (h_rar - R_w) * np.sin(delta_phi_r) + ) + + dot_delta_f = ( + (delta_z_f * np.cos(x[6]) + x[27] * np.sin(x[6])) * x[7] + + dot_delta_z_f * np.sin(x[6]) + - dot_delta_y_f * np.cos(x[6]) + - (h_raf - R_w) * np.cos(delta_phi_f) * dot_delta_phi_f + ) + dot_delta_r = ( + (delta_z_r * np.cos(x[6]) + x[28] * np.sin(x[6])) * x[7] + + dot_delta_z_r * np.sin(x[6]) + - dot_delta_y_r * np.cos(x[6]) + - (h_rar - R_w) * np.cos(delta_phi_r) * dot_delta_phi_r + ) + + # compliant joint forces + F_RAF = delta_f * K_ras + dot_delta_f * K_rad + F_RAR = delta_r * K_ras + dot_delta_r * K_rad + + # auxiliary suspension forces (bump stop neglected squat/lift forces neglected) + F_SLF = ( + m_s * g * lr / (2 * (lf + lr)) + - z_SLF * K_sf + - dz_SLF * K_sdf + + (x[6] - x[13]) * K_tsf / T_f + ) + + F_SRF = ( + m_s * g * lr / (2 * (lf + lr)) + - z_SRF * K_sf + - dz_SRF * K_sdf + - (x[6] - x[13]) * K_tsf / T_f + ) + + F_SLR = ( + m_s * g * lf / (2 * (lf + lr)) + - z_SLR * K_sr + - dz_SLR * K_sdr + + (x[6] - x[18]) * K_tsr / T_r + ) + + F_SRR = ( + m_s * g * lf / (2 * (lf + lr)) + - z_SRR * K_sr + - dz_SRR * K_sdr + - (x[6] - x[18]) * K_tsr / T_r + ) + + # auxiliary variables sprung mass + sumX = ( + F_x_LR + + F_x_RR + + (F_x_LF + F_x_RF) * np.cos(x[2]) + - (F_y_LF + F_y_RF) * np.sin(x[2]) + ) + + sumN = ( + (F_y_LF + F_y_RF) * lf * np.cos(x[2]) + + (F_x_LF + F_x_RF) * lf * np.sin(x[2]) + + (F_y_RF - F_y_LF) * 0.5 * T_f * np.sin(x[2]) + + (F_x_LF - F_x_RF) * 0.5 * T_f * np.cos(x[2]) + + (F_x_LR - F_x_RR) * 0.5 * T_r + - (F_y_LR + F_y_RR) * lr + ) + + sumY_s = (F_RAF + F_RAR) * np.cos(x[6]) + (F_SLF + F_SLR + F_SRF + F_SRR) * np.sin( + x[6] + ) + + sumL = ( + 0.5 * F_SLF * T_f + + 0.5 * F_SLR * T_r + - 0.5 * F_SRF * T_f + - 0.5 * F_SRR * T_r + - F_RAF + / np.cos(x[6]) + * (h_s - x[11] - R_w + x[16] - (h_raf - R_w) * np.cos(x[13])) + - F_RAR + / np.cos(x[6]) + * (h_s - x[11] - R_w + x[21] - (h_rar - R_w) * np.cos(x[18])) + ) + + sumZ_s = (F_SLF + F_SLR + F_SRF + F_SRR) * np.cos(x[6]) - (F_RAF + F_RAR) * np.sin( + x[6] + ) + + sumM_s = ( + lf * (F_SLF + F_SRF) + - lr * (F_SLR + F_SRR) + + ( + (F_x_LF + F_x_RF) * np.cos(x[2]) + - (F_y_LF + F_y_RF) * np.sin(x[2]) + + F_x_LR + + F_x_RR + ) + * (h_s - x[11]) + ) + + # auxiliary variables unsprung mass + sumL_uf = ( + 0.5 * F_SRF * T_f + - 0.5 * F_SLF * T_f + - F_RAF * (h_raf - R_w) + + F_z_LF * (R_w * np.sin(x[13]) + 0.5 * T_f * np.cos(x[13]) - K_lt * F_y_LF) + - F_z_RF * (-R_w * np.sin(x[13]) + 0.5 * T_f * np.cos(x[13]) + K_lt * F_y_RF) + - ((F_y_LF + F_y_RF) * np.cos(x[2]) + (F_x_LF + F_x_RF) * np.sin(x[2])) + * (R_w - x[16]) + ) + + sumL_ur = ( + 0.5 * F_SRR * T_r + - 0.5 * F_SLR * T_r + - F_RAR * (h_rar - R_w) + + F_z_LR * (R_w * np.sin(x[18]) + 0.5 * T_r * np.cos(x[18]) - K_lt * F_y_LR) + - F_z_RR * (-R_w * np.sin(x[18]) + 0.5 * T_r * np.cos(x[18]) + K_lt * F_y_RR) + - (F_y_LR + F_y_RR) * (R_w - x[21]) + ) + + sumZ_uf = F_z_LF + F_z_RF + F_RAF * np.sin(x[6]) - (F_SLF + F_SRF) * np.cos(x[6]) + + sumZ_ur = F_z_LR + F_z_RR + F_RAR * np.sin(x[6]) - (F_SLR + F_SRR) * np.cos(x[6]) + + sumY_uf = ( + (F_y_LF + F_y_RF) * np.cos(x[2]) + + (F_x_LF + F_x_RF) * np.sin(x[2]) + - F_RAF * np.cos(x[6]) + - (F_SLF + F_SRF) * np.sin(x[6]) + ) + + sumY_ur = (F_y_LR + F_y_RR) - F_RAR * np.cos(x[6]) - (F_SLR + F_SRR) * np.sin(x[6]) + + # dynamics common with single-track model + f = np.zeros((29,)) # init 'right hand side' + # switch to kinematic model for small velocities + if use_kinematic: + # wheelbase + # lwb = lf + lr + + # system dynamics + # x_ks = [x[0], x[1], x[2], x[3], x[4]] + # f_ks = vehicle_dynamics_ks(x_ks, u, p) + # f.extend(f_ks) + # f.append(u[1]*lwb*np.tan(x[2]) + x[3]/(lwb*np.cos(x[2])**2)*u[0]) + + # Use kinematic model with reference point at center of mass + # wheelbase + lwb = lf + lr + + # system dynamics + x_ks = x[0:5] + # kinematic model + # f_ks = vehicle_dynamics_ks_cog(x_ks, u, p) + # f = [f_ks[0], f_ks[1], f_ks[2], f_ks[3], f_ks[4]] # 1 2 3 4 5 + f_ks = vehicle_dynamics_ks(x_ks, u, params) + f[0:5] = f_ks + # derivative of slip angle and yaw rate + d_beta = (lr * u[0]) / ( + lwb * np.cos(x[2]) ** 2 * (1 + (np.tan(x[2]) ** 2 * lr / lwb) ** 2) + ) + dd_psi = ( + 1 + / lwb + * ( + u[1] * np.cos(x[6]) * np.tan(x[2]) + - x[3] * np.sin(x[6]) * d_beta * np.tan(x[2]) + + x[3] * np.cos(x[6]) * u[0] / np.cos(x[2]) ** 2 + ) + ) + # f.append(dd_psi) # 6 + f[5] = dd_psi + + else: + f[0] = np.cos(beta + x[4]) * vel # 1 + f[1] = np.sin(beta + x[4]) * vel # 2 + f[2] = u[0] # 3 + f[3] = 1 / m * sumX + x[5] * x[10] # 4 + f[4] = x[5] # 5 + f[5] = ( + 1 / (I_z - (I_xz_s) ** 2 / I_Phi_s) * (sumN + I_xz_s / I_Phi_s * sumL) + ) # 6 + + # remaining sprung mass dynamics + f[6] = x[7] # 7 + f[7] = 1 / (I_Phi_s - (I_xz_s) ** 2 / I_z) * (I_xz_s / I_z * sumN + sumL) # 8 + f[8] = x[9] # 9 + f[9] = 1 / I_y_s * sumM_s # 10 + f[10] = 1 / m_s * sumY_s - x[5] * x[3] # 11 + f[11] = x[12] # 12 + f[12] = g - 1 / m_s * sumZ_s # 13 + + # unsprung mass dynamics (front) + f[13] = x[14] # 14 + f[14] = 1 / I_uf * sumL_uf # 15 + f[15] = 1 / m_uf * sumY_uf - x[5] * x[3] # 16 + f[16] = x[17] # 17 + f[17] = g - 1 / m_uf * sumZ_uf # 18 + + # unsprung mass dynamics (rear) + f[18] = x[19] # 19 + f[19] = 1 / I_ur * sumL_ur # 20 + f[20] = 1 / m_ur * sumY_ur - x[5] * x[3] # 21 + f[21] = x[22] # 22 + f[22] = g - 1 / m_ur * sumZ_ur # 23 + + # convert acceleration input to brake and engine torque - splitting for brake/drive torque is outside of the integration + if u[0] > 0: + T_B = 0.0 + T_E = m * R_w * u[0] + else: + T_B = m * R_w * u[0] + T_E = 0.0 + + # wheel dynamics (p.T new parameter for torque splitting) - splitting for brake/drive torque is outside of the integration + f[23] = 1 / I_y_w * (-R_w * F_x_LF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) # 24 + f[24] = 1 / I_y_w * (-R_w * F_x_RF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) # 25 + f[25] = ( + 1 / I_y_w * (-R_w * F_x_LR + 0.5 * (1 - T_sb) * T_B + 0.5 * (1 - T_se) * T_E) + ) # 26 + f[26] = ( + 1 / I_y_w * (-R_w * F_x_RR + 0.5 * (1 - T_sb) * T_B + 0.5 * (1 - T_se) * T_E) + ) # 27 + + # negative wheel spin forbidden handeled outside of this function + for iState in range(23, 27): + if x[iState] < 0.0: + x[iState] = 0.0 + f[iState] = 0.0 + + # compliant joint equations + f[27] = dot_delta_y_f # 28 + f[28] = dot_delta_y_r # 29 + + # longitudinal slip + # s_lf + # s_rf + # s_lr + # s_rr + + # lateral slip + # alpha_LF + # alpha_RF + # alpha_LR + # alpha_RR + + return f diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/tire_model.py b/f1tenth_gym/envs/dynamic_models/multi_body/tire_model.py new file mode 100644 index 00000000..6fc6f704 --- /dev/null +++ b/f1tenth_gym/envs/dynamic_models/multi_body/tire_model.py @@ -0,0 +1,184 @@ +import numpy as np +from numba import njit + + +# longitudinal tire forces +def formula_longitudinal(kappa, gamma, F_z, params: dict): + # longitudinal coefficients + tire_p_cx1 = params["tire_p_cx1"] # Shape factor Cfx for longitudinal force + tire_p_dx1 = params["tire_p_dx1"] # Longitudinal friction Mux at Fznom + tire_p_dx3 = params["tire_p_dx3"] # Variation of friction Mux with camber + tire_p_ex1 = params["tire_p_ex1"] # Longitudinal curvature Efx at Fznom + tire_p_kx1 = params["tire_p_kx1"] # Longitudinal slip stiffness Kfx/Fz at Fznom + tire_p_hx1 = params["tire_p_hx1"] # Horizontal shift Shx at Fznom + tire_p_vx1 = params["tire_p_vx1"] # Vertical shift Svx/Fz at Fznom + + # turn slip is neglected, so xi_i=1 + # all scaling factors lambda = 1 + + # coordinate system transformation + kappa = -kappa + + S_hx = tire_p_hx1 + S_vx = F_z * tire_p_vx1 + + kappa_x = kappa + S_hx + mu_x = tire_p_dx1 * (1 - tire_p_dx3 * gamma**2) + + C_x = tire_p_cx1 + D_x = mu_x * F_z + E_x = tire_p_ex1 + K_x = F_z * tire_p_kx1 + B_x = K_x / (C_x * D_x) + + # magic tire formula + return D_x * np.sin( + C_x + * np.arctan(B_x * kappa_x - E_x * (B_x * kappa_x - np.arctan(B_x * kappa_x))) + + S_vx + ) + + +# lateral tire forces +def formula_lateral(alpha, gamma, F_z, params: dict): + # lateral coefficients + tire_p_cy1 = params["tire_p_cy1"] # Shape factor Cfy for lateral forces + tire_p_dy1 = params["tire_p_dy1"] # Lateral friction Muy + tire_p_dy3 = params["tire_p_dy3"] # Variation of friction Muy with squared camber + tire_p_ey1 = params["tire_p_ey1"] # Lateral curvature Efy at Fznom + tire_p_ky1 = params["tire_p_ky1"] # Maximum value of stiffness Kfy/Fznom + tire_p_hy1 = params["tire_p_hy1"] # Horizontal shift Shy at Fznom + tire_p_hy3 = params["tire_p_hy3"] # Variation of shift Shy with camber + tire_p_vy1 = params["tire_p_vy1"] # Vertical shift in Svy/Fz at Fznom + tire_p_vy3 = params["tire_p_vy3"] # Variation of shift Svy/Fz with camber + + # turn slip is neglected, so xi_i=1 + # all scaling factors lambda = 1 + + # coordinate system transformation + # alpha = -alpha + + S_hy = np.sign(gamma) * (tire_p_hy1 + tire_p_hy3 * np.fabs(gamma)) + S_vy = np.sign(gamma) * F_z * (tire_p_vy1 + tire_p_vy3 * np.fabs(gamma)) + + alpha_y = alpha + S_hy + mu_y = tire_p_dy1 * (1 - tire_p_dy3 * gamma**2) + + C_y = tire_p_cy1 + D_y = mu_y * F_z + E_y = tire_p_ey1 + K_y = F_z * tire_p_ky1 # simplify K_y0 to tire_p_ky1*F_z + B_y = K_y / (C_y * D_y) + + # magic tire formula + F_y = ( + D_y + * np.sin( + C_y + * np.arctan( + B_y * alpha_y - E_y * (B_y * alpha_y - np.arctan(B_y * alpha_y)) + ) + ) + + S_vy + ) + + res = [] + res.append(F_y) + res.append(mu_y) + return res + + +# longitudinal tire forces for combined slip +def formula_longitudinal_comb(kappa, alpha, F0_x, params: dict): + # longitudinal coefficients + tire_r_bx1 = params["tire_r_bx1"] # Slope factor for combined slip Fx reduction + tire_r_bx2 = params["tire_r_bx2"] # Variation of slope Fx reduction with kappa + tire_r_cx1 = params["tire_r_cx1"] # Shape factor for combined slip Fx reduction + tire_r_ex1 = params["tire_r_ex1"] # Curvature factor of combined Fx + tire_r_hx1 = params["tire_r_hx1"] # Shift factor for combined slip Fx reduction + + # turn slip '' neglected, so xi_i=1 + # all scaling factors lambda = 1 + + S_hxalpha = tire_r_hx1 + + alpha_s = alpha + S_hxalpha + + B_xalpha = tire_r_bx1 * np.cos(np.arctan(tire_r_bx2 * kappa)) + C_xalpha = tire_r_cx1 + E_xalpha = tire_r_ex1 + D_xalpha = F0_x / ( + np.cos( + C_xalpha + * np.arctan( + B_xalpha * S_hxalpha + - E_xalpha * (B_xalpha * S_hxalpha - np.arctan(B_xalpha * S_hxalpha)) + ) + ) + ) + + # magic tire formula + return D_xalpha * np.cos( + C_xalpha + * np.arctan( + B_xalpha * alpha_s + - E_xalpha * (B_xalpha * alpha_s - np.arctan(B_xalpha * alpha_s)) + ) + ) + + +# lateral tire forces for combined slip +def formula_lateral_comb(kappa, alpha, gamma, mu_y, F_z, F0_y, params: dict): + # lateral coefficients + tire_r_by1 = params["tire_r_by1"] # Slope factor for combined Fy reduction + tire_r_by2 = params["tire_r_by2"] # Variation of slope Fy reduction with alpha + tire_r_by3 = params["tire_r_by3"] # Shift term for alpha in slope Fy reduction + tire_r_cy1 = params["tire_r_cy1"] # Shape factor for combined Fy reduction + tire_r_ey1 = params["tire_r_ey1"] # Curvature factor of combined Fy + tire_r_hy1 = params["tire_r_hy1"] # Shift factor for combined Fy reduction + tire_r_vy1 = params["tire_r_vy1"] # Kappa induced side force Svyk/Muy*Fz at Fznom + tire_r_vy3 = params["tire_r_vy3"] # Variation of Svyk/Muy*Fz with camber + tire_r_vy4 = params["tire_r_vy4"] # Variation of Svyk/Muy*Fz with alpha + tire_r_vy5 = params["tire_r_vy5"] # Variation of Svyk/Muy*Fz with kappa + tire_r_vy6 = params["tire_r_vy6"] # Variation of Svyk/Muy*Fz with atan(kappa) + + # turn slip is neglected, so xi_i=1 + # all scaling factors lambda = 1 + + S_hykappa = tire_r_hy1 + + kappa_s = kappa + S_hykappa + + B_ykappa = tire_r_by1 * np.cos(np.arctan(tire_r_by2 * (alpha - tire_r_by3))) + C_ykappa = tire_r_cy1 + E_ykappa = tire_r_ey1 + D_ykappa = F0_y / ( + np.cos( + C_ykappa + * np.arctan( + B_ykappa * S_hykappa + - E_ykappa * (B_ykappa * S_hykappa - np.arctan(B_ykappa * S_hykappa)) + ) + ) + ) + + D_vykappa = ( + mu_y + * F_z + * (tire_r_vy1 + tire_r_vy3 * gamma) + * np.cos(np.arctan(tire_r_vy4 * alpha)) + ) + S_vykappa = D_vykappa * np.sin(tire_r_vy5 * np.arctan(tire_r_vy6 * kappa)) + + # magic tire formula + return ( + D_ykappa + * np.cos( + C_ykappa + * np.arctan( + B_ykappa * kappa_s + - E_ykappa * (B_ykappa * kappa_s - np.arctan(B_ykappa * kappa_s)) + ) + ) + + S_vykappa + ) diff --git a/f1tenth_gym/envs/dynamic_models/single_track.py b/f1tenth_gym/envs/dynamic_models/single_track.py index 16b53b7a..8ce62d0e 100644 --- a/f1tenth_gym/envs/dynamic_models/single_track.py +++ b/f1tenth_gym/envs/dynamic_models/single_track.py @@ -3,27 +3,8 @@ from .utils import steering_constraint, accl_constraints -@njit(cache=True) -def vehicle_dynamics_st( - x, - u_init, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, -): + +def vehicle_dynamics_st(x: np.ndarray, u_init: np.ndarray, params: dict): """ Single Track Vehicle Dynamics. From https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/-/blob/master/vehicleModels_commonRoad.pdf, section 7 @@ -40,22 +21,23 @@ def vehicle_dynamics_st( u (numpy.ndarray (2, )): control input vector (u1, u2) u1: steering angle velocity of front wheels u2: longitudinal acceleration - mu (float): friction coefficient - C_Sf (float): cornering stiffness of front wheels - C_Sr (float): cornering stiffness of rear wheels - lf (float): distance from center of gravity to front axle - lr (float): distance from center of gravity to rear axle - h (float): height of center of gravity - m (float): mass of vehicle - I (float): moment of inertia of vehicle, about Z axis - s_min (float): minimum steering angle - s_max (float): maximum steering angle - sv_min (float): minimum steering velocity - sv_max (float): maximum steering velocity - v_switch (float): velocity above which the acceleration is no longer able to create wheel spin - a_max (float): maximum allowed acceleration - v_min (float): minimum allowed velocity - v_max (float): maximum allowed velocity + params (dict): dictionary containing the following parameters: + mu (float): friction coefficient + C_Sf (float): cornering stiffness of front wheels + C_Sr (float): cornering stiffness of rear wheels + lf (float): distance from center of gravity to front axle + lr (float): distance from center of gravity to rear axle + h (float): height of center of gravity + m (float): mass of vehicle + I (float): moment of inertia of vehicle, about Z axis + s_min (float): minimum steering angle + s_max (float): maximum steering angle + sv_min (float): minimum steering velocity + sv_max (float): maximum steering velocity + v_switch (float): velocity above which the acceleration is no longer able to create wheel spin + a_max (float): maximum allowed acceleration + v_min (float): minimum allowed velocity + v_max (float): maximum allowed velocity Returns: f (numpy.ndarray): right hand side of differential equations @@ -77,8 +59,22 @@ def vehicle_dynamics_st( # constraints u = np.array( [ - steering_constraint(DELTA, u_init[0], s_min, s_max, sv_min, sv_max), - accl_constraints(V, u_init[1], v_switch, a_max, v_min, v_max), + steering_constraint( + DELTA, + u_init[0], + params["s_min"], + params["s_max"], + params["sv_min"], + params["sv_max"], + ), + accl_constraints( + V, + u_init[1], + params["v_switch"], + params["a_max"], + params["v_min"], + params["v_max"], + ), ] ) # Controls @@ -88,11 +84,11 @@ def vehicle_dynamics_st( # switch to kinematic model for small velocities if V < 0.1: # wheelbase - lwb = lf + lr - BETA_HAT = np.arctan(np.tan(DELTA) * lr / lwb) + lwb = params["lf"] + params["lr"] + BETA_HAT = np.arctan(np.tan(DELTA) * params["lr"] / lwb) BETA_DOT = ( - (1 / (1 + (np.tan(DELTA) * (lr / lwb)) ** 2)) - * (lr / (lwb * np.cos(DELTA) ** 2)) + (1 / (1 + (np.tan(DELTA) * (params["lr"] / lwb)) ** 2)) + * (params["lr"] / (lwb * np.cos(DELTA) ** 2)) * STEER_VEL ) f = np.array( @@ -113,8 +109,8 @@ def vehicle_dynamics_st( ) else: # system dynamics - glr = (g * lr - ACCL * h) - glf = (g * lf + ACCL * h) + glr = g * params["lr"] - ACCL * params["h"] + glf = g * params["lf"] + ACCL * params["h"] f = np.array( [ V * np.cos(PSI + BETA), # X_DOT @@ -122,22 +118,34 @@ def vehicle_dynamics_st( STEER_VEL, # DELTA_DOT ACCL, # V_DOT PSI_DOT, # PSI_DOT - ((mu * m) / (I * (lf + lr))) * ( - lf * C_Sf * (g * lr - ACCL * h) * DELTA - + ( - lr * C_Sr * (g * lf + ACCL * h) - lf * C_Sf * (g * lr - ACCL * h) - ) * BETA - - ( - lf * lf * C_Sf * (g * lr - ACCL * h) + lr * lr * C_Sr * (g * lf + ACCL * h) - ) * (PSI_DOT / V) - ), # PSI_DOT_DOT - (mu / (V * (lr + lf))) * ( - C_Sf * (g * lr - ACCL * h) * DELTA \ - - (C_Sr * (g * lf + ACCL * h) + C_Sf * (g * lr - ACCL * h)) * BETA - + ( - C_Sr * (g * lf + ACCL * h) * lr - C_Sf * (g * lr - ACCL * h) * lf - ) * (PSI_DOT / V) - ) - PSI_DOT, # BETA_DOT + ( + (params["mu"] * params["m"]) + / (params["I"] * (params["lf"] + params["lr"])) + ) + * ( + params["lf"] * params["C_Sf"] * (glr) * DELTA + + ( + params["lr"] * params["C_Sr"] * (glf) + - params["lf"] * params["C_Sf"] * (glr) + ) + * BETA + - ( + params["lf"] * params["lf"] * params["C_Sf"] * (glr) + + params["lr"] * params["lr"] * params["C_Sr"] * (glf) + ) + * (PSI_DOT / V) + ), # PSI_DOT_DOT + (params["mu"] / (V * (params["lr"] + params["lf"]))) + * ( + params["C_Sf"] * (glr) * DELTA + - (params["C_Sr"] * (glf) + params["C_Sf"] * (glr)) * BETA + + ( + params["C_Sr"] * (glf) * params["lr"] + - params["C_Sf"] * (glr) * params["lf"] + ) + * (PSI_DOT / V) + ) + - PSI_DOT, # BETA_DOT ] ) diff --git a/f1tenth_gym/envs/dynamic_models/tire_models.py b/f1tenth_gym/envs/dynamic_models/tire_models.py deleted file mode 100644 index e69de29b..00000000 diff --git a/f1tenth_gym/envs/dynamic_models/utils.py b/f1tenth_gym/envs/dynamic_models/utils.py index 2044e3c5..6115bc77 100644 --- a/f1tenth_gym/envs/dynamic_models/utils.py +++ b/f1tenth_gym/envs/dynamic_models/utils.py @@ -1,6 +1,7 @@ import numpy as np from numba import njit + @njit(cache=True) def upper_accel_limit(vel, a_max, v_switch): """ diff --git a/f1tenth_gym/envs/f110_env.py b/f1tenth_gym/envs/f110_env.py index f6b62916..ba446614 100644 --- a/f1tenth_gym/envs/f110_env.py +++ b/f1tenth_gym/envs/f110_env.py @@ -286,6 +286,41 @@ def fullscale_vehicle_params(cls) -> dict: "E_f": 0, # [needs conversion if nonzero] ER "E_r": 0, + # tire parameters from ADAMS handbook + # longitudinal coefficients + "tire_p_cx1": 1.6411, # Shape factor Cfx for longitudinal force + "tire_p_dx1": 1.1739, # Longitudinal friction Mux at Fznom + "tire_p_dx3": 0, # Variation of friction Mux with camber + "tire_p_ex1": 0.46403, # Longitudinal curvature Efx at Fznom + "tire_p_kx1": 22.303, # Longitudinal slip stiffness Kfx/Fz at Fznom + "tire_p_hx1": 0.0012297, # Horizontal shift Shx at Fznom + "tire_p_vx1": -8.8098e-006, # Vertical shift Svx/Fz at Fznom + "tire_r_bx1": 13.276, # Slope factor for combined slip Fx reduction + "tire_r_bx2": -13.778, # Variation of slope Fx reduction with kappa + "tire_r_cx1": 1.2568, # Shape factor for combined slip Fx reduction + "tire_r_ex1": 0.65225, # Curvature factor of combined Fx + "tire_r_hx1": 0.0050722, # Shift factor for combined slip Fx reduction + # lateral coefficients + "tire_p_cy1": 1.3507, # Shape factor Cfy for lateral forces + "tire_p_dy1": 1.0489, # Lateral friction Muy + "tire_p_dy3": -2.8821, # Variation of friction Muy with squared camber + "tire_p_ey1": -0.0074722, # Lateral curvature Efy at Fznom + "tire_p_ky1": -21.92, # Maximum value of stiffness Kfy/Fznom + "tire_p_hy1": 0.0026747, # Horizontal shift Shy at Fznom + "tire_p_hy3": 0.031415, # Variation of shift Shy with camber + "tire_p_vy1": 0.037318, # Vertical shift in Svy/Fz at Fznom + "tire_p_vy3": -0.32931, # Variation of shift Svy/Fz with camber + "tire_r_by1": 7.1433, # Slope factor for combined Fy reduction + "tire_r_by2": 9.1916, # Variation of slope Fy reduction with alpha + "tire_r_by3": -0.027856, # Shift term for alpha in slope Fy reduction + "tire_r_cy1": 1.0719, # Shape factor for combined Fy reduction + "tire_r_ey1": -0.27572, # Curvature factor of combined Fy + "tire_r_hy1": 5.7448e-006, # Shift factor for combined Fy reduction + "tire_r_vy1": -0.027825, # Kappa induced side force Svyk/Muy*Fz at Fznom + "tire_r_vy3": -0.27568, # Variation of Svyk/Muy*Fz with camber + "tire_r_vy4": 12.12, # Variation of Svyk/Muy*Fz with alpha + "tire_r_vy5": 1.9, # Variation of Svyk/Muy*Fz with kappa + "tire_r_vy6": -10.704, # Variation of Svyk/Muy*Fz with atan(kappa) } return params diff --git a/f1tenth_gym/envs/integrator.py b/f1tenth_gym/envs/integrator.py index bfc796be..0987fbfe 100644 --- a/f1tenth_gym/envs/integrator.py +++ b/f1tenth_gym/envs/integrator.py @@ -35,95 +35,16 @@ def __init__(self) -> None: self._integrator_type = "rk4" def integrate(self, f, x, u, dt, params): - k1 = f( - x, - u, - params["mu"], - params["C_Sf"], - params["C_Sr"], - params["lf"], - params["lr"], - params["h"], - params["m"], - params["I"], - params["s_min"], - params["s_max"], - params["sv_min"], - params["sv_max"], - params["v_switch"], - params["a_max"], - params["v_min"], - params["v_max"], - ) + k1 = f(x, u, params) k2_state = x + dt * (k1 / 2) - - k2 = f( - k2_state, - u, - params["mu"], - params["C_Sf"], - params["C_Sr"], - params["lf"], - params["lr"], - params["h"], - params["m"], - params["I"], - params["s_min"], - params["s_max"], - params["sv_min"], - params["sv_max"], - params["v_switch"], - params["a_max"], - params["v_min"], - params["v_max"], - ) + k2 = f(k2_state, u, params) k3_state = x + dt * (k2 / 2) - - k3 = f( - k3_state, - u, - params["mu"], - params["C_Sf"], - params["C_Sr"], - params["lf"], - params["lr"], - params["h"], - params["m"], - params["I"], - params["s_min"], - params["s_max"], - params["sv_min"], - params["sv_max"], - params["v_switch"], - params["a_max"], - params["v_min"], - params["v_max"], - ) + k3 = f(k3_state, u, params) k4_state = x + dt * k3 - - k4 = f( - k4_state, - u, - params["mu"], - params["C_Sf"], - params["C_Sr"], - params["lf"], - params["lr"], - params["h"], - params["m"], - params["I"], - params["s_min"], - params["s_max"], - params["sv_min"], - params["sv_max"], - params["v_switch"], - params["a_max"], - params["v_min"], - params["v_max"], - ) + k4 = f(k4_state, u, params) # dynamics integration x = x + dt * (1 / 6) * (k1 + 2 * k2 + 2 * k3 + k4) @@ -136,25 +57,6 @@ def __init__(self) -> None: self._integrator_type = "euler" def integrate(self, f, x, u, dt, params): - dstate = f( - x, - u, - params["mu"], - params["C_Sf"], - params["C_Sr"], - params["lf"], - params["lr"], - params["h"], - params["m"], - params["I"], - params["s_min"], - params["s_max"], - params["sv_min"], - params["sv_max"], - params["v_switch"], - params["a_max"], - params["v_min"], - params["v_max"], - ) + dstate = f(x, u, params) x = x + dt * dstate return x From 9b173e6c94f1103d19eea0d030e3fa0868862aa1 Mon Sep 17 00:00:00 2001 From: nandant Date: Mon, 23 Sep 2024 23:38:40 +0200 Subject: [PATCH 38/55] Updated speed and kinematic threshold for numerical stability. --- examples/waypoint_follow.py | 36 +++++++++++++++---- .../dynamic_models/multi_body/multi_body.py | 2 +- 2 files changed, 31 insertions(+), 7 deletions(-) diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index 53b89cd3..7eb7173e 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -1,3 +1,4 @@ +# %% import time from typing import Tuple @@ -7,6 +8,7 @@ from f1tenth_gym.envs.f110_env import F110Env +# %% """ Planner Helpers """ @@ -207,7 +209,9 @@ def render_lookahead_point(self, e): if self.lookahead_point is not None: points = self.lookahead_point[:2][None] # shape (1, 2)~ if self.lookahead_point_render is None: - self.lookahead_point_render = e.render_points(points, color=(0, 0, 128), size=2) + self.lookahead_point_render = e.render_points( + points, color=(0, 0, 128), size=2 + ) else: self.lookahead_point_render.setData(points) @@ -218,7 +222,9 @@ def render_local_plan(self, e): if self.current_index is not None: points = self.waypoints[self.current_index : self.current_index + 10, :2] if self.local_plan_render is None: - self.local_plan_render = e.render_lines(points, color=(0, 128, 0), size=1) + self.local_plan_render = e.render_lines( + points, color=(0, 128, 0), size=1 + ) else: self.local_plan_render.updateItems(points) @@ -289,6 +295,7 @@ def plan(self, pose_x, pose_y, pose_theta, lookahead_distance, vgain): return speed, steering_angle +# %% def main(): """ main entry point @@ -297,8 +304,8 @@ def main(): work = { "mass": 3.463388126201571, "lf": 0.15597534362552312, - "tlad": 0.82461887897713965*10, - "vgain": 1, + "tlad": 0.82461887897713965 * 10, + "vgain": 100, } num_agents = 1 @@ -310,7 +317,7 @@ def main(): "timestep": 0.01, "integrator": "rk4", "control_input": ["speed", "steering_angle"], - "model": "st", + "model": "mb", "observation_config": {"type": "kinematic_state"}, "params": F110Env.fullscale_vehicle_params(), "reset_config": {"type": "rl_random_static"}, @@ -320,7 +327,13 @@ def main(): ) track = env.unwrapped.track - planner = PurePursuitPlanner(track=track, wb=(F110Env.fullscale_vehicle_params()["lf"] + F110Env.fullscale_vehicle_params()["lr"])) + planner = PurePursuitPlanner( + track=track, + wb=( + F110Env.fullscale_vehicle_params()["lf"] + + F110Env.fullscale_vehicle_params()["lr"] + ), + ) env.unwrapped.add_render_callback(track.raceline.render_waypoints) env.unwrapped.add_render_callback(planner.render_local_plan) @@ -352,5 +365,16 @@ def main(): print("Sim elapsed time:", laptime, "Real elapsed time:", time.time() - start) +# %% + if __name__ == "__main__": main() +# %% +work = { + "mass": 3.463388126201571, + "lf": 0.15597534362552312, + "tlad": 0.82461887897713965 * 10, + "vgain": 1, +} + +num_agents = 1 diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py index 102239f5..5e5ae6f6 100644 --- a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py +++ b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py @@ -157,7 +157,7 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): E_f = params["E_f"] # [needs conversion if nonzero] EF E_r = params["E_r"] # [needs conversion if nonzero] ER - use_kinematic = True if x[3] < 0.1 else False + use_kinematic = True if x[3] < 0.5 else False # consider steering and acceleration constraints - outside of the integration # u = np.array([steering_constraint(x[2], u_init[0], s_min, s_max, sv_min, sv_max), accl_constraints(x[3], u_init[1], v_switch, a_max, v_min, v_max)]) From dc91a46e445908f54ad5958c35a90e845afde5c5 Mon Sep 17 00:00:00 2001 From: nandant Date: Mon, 23 Sep 2024 23:43:17 +0200 Subject: [PATCH 39/55] Updated dynamics tests --- tests/test_dynamics.py | 69 ++++++++++++++++++++++-------------------- 1 file changed, 37 insertions(+), 32 deletions(-) diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index 39fb6c1f..ca2d6593 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -28,6 +28,7 @@ vehicle_dynamics_st, ) + def func_KS( x, t, @@ -52,22 +53,24 @@ def func_KS( f = vehicle_dynamics_ks( x, u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, + params={ + "mu": mu, + "C_Sf": C_Sf, + "C_Sr": C_Sr, + "lf": lf, + "lr": lr, + "h": h, + "m": m, + "I": I, + "s_min": s_min, + "s_max": s_max, + "sv_min": sv_min, + "sv_max": sv_max, + "v_switch": v_switch, + "a_max": a_max, + "v_min": v_min, + "v_max": v_max, + }, ) return f @@ -96,22 +99,24 @@ def func_ST( f = vehicle_dynamics_st( x, u, - mu, - C_Sf, - C_Sr, - lf, - lr, - h, - m, - I, - s_min, - s_max, - sv_min, - sv_max, - v_switch, - a_max, - v_min, - v_max, + params={ + "mu": mu, + "C_Sf": C_Sf, + "C_Sr": C_Sr, + "lf": lf, + "lr": lr, + "h": h, + "m": m, + "I": I, + "s_min": s_min, + "s_max": s_max, + "sv_min": sv_min, + "sv_max": sv_max, + "v_switch": v_switch, + "a_max": a_max, + "v_min": v_min, + "v_max": v_max, + }, ) return f From cea4ea3264327e71446d9670d84014fe91ba4e0e Mon Sep 17 00:00:00 2001 From: nandant Date: Tue, 24 Sep 2024 16:39:05 +0200 Subject: [PATCH 40/55] Fully working MB model --- examples/waypoint_follow.py | 12 +- f1tenth_gym/envs/dynamic_models/__init__.py | 2 +- f1tenth_gym/envs/dynamic_models/kinematic.py | 83 ++++++ .../dynamic_models/multi_body/multi_body.py | 240 ++++++++---------- f1tenth_gym/envs/dynamic_models/utils.py | 4 - 5 files changed, 197 insertions(+), 144 deletions(-) diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index 7eb7173e..f61a7c72 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -1,4 +1,3 @@ -# %% import time from typing import Tuple @@ -8,7 +7,6 @@ from f1tenth_gym.envs.f110_env import F110Env -# %% """ Planner Helpers """ @@ -295,7 +293,6 @@ def plan(self, pose_x, pose_y, pose_theta, lookahead_distance, vgain): return speed, steering_angle -# %% def main(): """ main entry point @@ -305,7 +302,7 @@ def main(): "mass": 3.463388126201571, "lf": 0.15597534362552312, "tlad": 0.82461887897713965 * 10, - "vgain": 100, + "vgain": 1.0, } num_agents = 1 @@ -346,7 +343,8 @@ def main(): laptime = 0.0 start = time.time() - while not done: + i = 1 + while not done or i < 1000: action = env.action_space.sample() for i, agent_id in enumerate(obs.keys()): speed, steer = planner.plan( @@ -357,16 +355,14 @@ def main(): work["vgain"], ) action[i] = np.array([steer, speed]) - obs, step_reward, done, truncated, info = env.step(action) laptime += step_reward frame = env.render() + i += 1 print("Sim elapsed time:", laptime, "Real elapsed time:", time.time() - start) -# %% - if __name__ == "__main__": main() # %% diff --git a/f1tenth_gym/envs/dynamic_models/__init__.py b/f1tenth_gym/envs/dynamic_models/__init__.py index 9f79507c..8dec7f4d 100644 --- a/f1tenth_gym/envs/dynamic_models/__init__.py +++ b/f1tenth_gym/envs/dynamic_models/__init__.py @@ -32,7 +32,7 @@ def from_string(model: str): else: raise ValueError(f"Unknown model type {model}") - def get_initial_state(self, pose=None, params: dict = None): + def get_initial_state(self, pose=None, params: dict|None = None): # Assert that if self is MB, params is not None if self == DynamicModel.MB and params is None: raise ValueError("MultiBody model requires parameters to be provided.") diff --git a/f1tenth_gym/envs/dynamic_models/kinematic.py b/f1tenth_gym/envs/dynamic_models/kinematic.py index 1af38b03..95804a95 100644 --- a/f1tenth_gym/envs/dynamic_models/kinematic.py +++ b/f1tenth_gym/envs/dynamic_models/kinematic.py @@ -88,3 +88,86 @@ def vehicle_dynamics_ks(x: np.ndarray, u_init: np.ndarray, params: dict): ] ) return f + + +def vehicle_dynamics_ks_cog(x: np.ndarray, u_init: np.ndarray, params: dict): + """ + Single Track Kinematic Vehicle Dynamics. + Follows https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/-/blob/master/vehicleModels_commonRoad.pdf, section 5 + + Args: + x (numpy.ndarray (5, )): vehicle state vector (x0, x1, x2, x3, x4) + x0: x position in global coordinates + x1: y position in global coordinates + x2: steering angle of front wheels + x3: velocity in x direction + x4: yaw angle + u (numpy.ndarray (2, )): control input vector (u1, u2) + u1: steering angle velocity of front wheels + u2: longitudinal acceleration + params (dict): dictionary containing the following parameters: + mu (float): friction coefficient + C_Sf (float): cornering stiffness of front wheels + C_Sr (float): cornering stiffness of rear wheels + lf (float): distance from center of gravity to front axle + lr (float): distance from center of gravity to rear axle + h (float): height of center of gravity + m (float): mass of vehicle + I (float): moment of inertia of vehicle, about Z axis + s_min (float): minimum steering angle + s_max (float): maximum steering angle + sv_min (float): minimum steering velocity + sv_max (float): maximum steering velocity + v_switch (float): velocity above which the acceleration is no longer able to create wheel slip + a_max (float): maximum allowed acceleration + v_min (float): minimum allowed velocity + v_max (float): maximum allowed velocity + + Returns: + f (numpy.ndarray): right hand side of differential equations + """ + # Controls + X = x[0] + Y = x[1] + DELTA = x[2] + V = x[3] + PSI = x[4] + # Raw Actions + RAW_STEER_VEL = u_init[0] + RAW_ACCL = u_init[1] + # wheelbase + lwb = params["lf"] + params["lr"] + # constraints + u = np.array( + [ + steering_constraint( + DELTA, + RAW_STEER_VEL, + params["s_min"], + params["s_max"], + params["sv_min"], + params["sv_max"], + ), + accl_constraints( + V, + RAW_ACCL, + params["v_switch"], + params["a_max"], + params["v_min"], + params["v_max"], + ), + ] + ) + # slip angle (beta) from vehicle kinematics + beta = np.atan(np.tan(x[2]) * params["lr"] / lwb) + + # system dynamics + f = [ + V * np.cos(beta + PSI), + V * np.sin(beta + PSI), + u[0], + u[1], + V * np.cos(beta) * np.tan(DELTA) / lwb, + ] + + return f diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py index 5e5ae6f6..e9ca761b 100644 --- a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py +++ b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py @@ -1,13 +1,15 @@ import numpy as np from numba import njit +from f1tenth_gym.envs.dynamic_models.utils import steering_constraint, accl_constraints + from .tire_model import ( formula_lateral, formula_lateral_comb, formula_longitudinal, formula_longitudinal_comb, ) -from ..kinematic import vehicle_dynamics_ks +from ..kinematic import vehicle_dynamics_ks_cog def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): @@ -33,45 +35,45 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): g = 9.81 # [m/s^2] # states - # x1 = x-position in a global coordinate system - # x2 = y-position in a global coordinate system - # x3 = steering angle of front wheels - # x4 = velocity in x-direction - # x5 = yaw angle - # x6 = yaw rate - - # x7 = roll angle - # x8 = roll rate - # x9 = pitch angle - # x10 = pitch rate - # x11 = velocity in y-direction - # x12 = z-position - # x13 = velocity in z-direction - - # x14 = roll angle front - # x15 = roll rate front - # x16 = velocity in y-direction front - # x17 = z-position front - # x18 = velocity in z-direction front - - # x19 = roll angle rear - # x20 = roll rate rear - # x21 = velocity in y-direction rear - # x22 = z-position rear - # x23 = velocity in z-direction rear - - # x24 = left front wheel angular speed - # x25 = right front wheel angular speed - # x26 = left rear wheel angular speed - # x27 = right rear wheel angular speed - - # x28 = delta_y_f - # x29 = delta_y_r - - # u1 = steering angle velocity of front wheels - # u2 = acceleration - - u = u_init + # x0 = x-position in a global coordinate system + # x1 = y-position in a global coordinate system + # x2 = steering angle of front wheels + # x3 = velocity in x-direction + # x4 = yaw angle + # x5 = yaw rate + + # x6 = roll angle + # x7 = roll rate + # x8 = pitch angle + # x9 = pitch rate + # x10 = velocity in y-direction + # x11 = z-position + # x12 = velocity in z-direction + + # x13 = roll angle front + # x14 = roll rate front + # x15 = velocity in y-direction front + # x16 = z-position front + # x17 = velocity in z-direction front + + # x18 = roll angle rear + # x19 = roll rate rear + # x20 = velocity in y-direction rear + # x21 = z-position rear + # x22 = velocity in z-direction rear + + # x23 = left front wheel angular speed + # x24 = right front wheel angular speed + # x25 = left rear wheel angular speed + # x26 = right rear wheel angular speed + + # x27 = delta_y_f + # x28 = delta_y_r + + # u0 = steering angle velocity of front wheels + # u1 = acceleration + + u = np.zeros_like(u_init) # vehicle body dimensions length = params["length"] # vehicle length [m] @@ -84,10 +86,10 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): sv_max = params["sv_max"] # maximum steering velocity [rad/s] # longitudinal constraints - v_min = params["s_min"] # minimum velocity [m/s] - v_max = params["s_max"] # minimum velocity [m/s] - v_switch = params["sv_min"] # switching velocity [m/s] - a_max = params["sv_max"] # maximum absolute acceleration [m/s^2] + v_min = params["v_min"] # minimum velocity [m/s] + v_max = params["v_max"] # minimum velocity [m/s] + v_switch = params["v_switch"] # switching velocity [m/s] + a_max = params["a_max"] # maximum absolute acceleration [m/s^2] # masses m = params["m"] # vehicle mass [kg] MASS @@ -157,18 +159,17 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): E_f = params["E_f"] # [needs conversion if nonzero] EF E_r = params["E_r"] # [needs conversion if nonzero] ER - use_kinematic = True if x[3] < 0.5 else False + KIN_THRESH = 0.5 # consider steering and acceleration constraints - outside of the integration - # u = np.array([steering_constraint(x[2], u_init[0], s_min, s_max, sv_min, sv_max), accl_constraints(x[3], u_init[1], v_switch, a_max, v_min, v_max)]) + u[0] = steering_constraint(x[2], u_init[0], s_min, s_max, sv_min, sv_max) + u[1] = accl_constraints(x[3], u_init[1], v_switch, a_max, v_min, v_max) - # compute slip angle at cg - outside of the integration - # switch to kinematic model for small velocities handeled outside - if use_kinematic: + if abs(x[3]) < KIN_THRESH: beta = 0.0 else: - beta = np.arctan(x[10] / x[3]) - vel = np.sqrt(x[3] ** 2 + x[10] ** 2) + beta = np.atan(x[10] / x[3]) + vel = np.sqrt(x[3] ** 2 + x[10] ** 2) # vertical tire forces F_z_LF = (x[16] + R_w * (np.cos(x[13]) - 1) - 0.5 * T_f * np.sin(x[13])) * K_zt @@ -187,25 +188,20 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): u_w_rr = x[3] - 0.5 * T_r * x[5] # negative wheel spin forbidden - u_w_lf = np.maximum(u_w_lf, 0.0) - u_w_rf = np.maximum(u_w_rf, 0.0) - u_w_lr = np.maximum(u_w_lr, 0.0) - u_w_rr = np.maximum(u_w_rr, 0.0) - # if u_w_lf < 0.0: - # u_w_lf *= 0 - # - # if u_w_rf < 0.0: - # u_w_rf *= 0 - # - # if u_w_lr < 0.0: - # u_w_lr *= 0 - # - # if u_w_rr < 0.0: - # u_w_rr *= 0 + if u_w_lf < 0.0: + u_w_lf *= 0 + + if u_w_rf < 0.0: + u_w_rf *= 0 + if u_w_lr < 0.0: + u_w_lr *= 0 + + if u_w_rr < 0.0: + u_w_rr *= 0 # compute longitudinal slip # switch to kinematic model for small velocities - if use_kinematic: + if abs(x[3]) < KIN_THRESH: s_lf = 0.0 s_rf = 0.0 s_lr = 0.0 @@ -218,28 +214,28 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): # lateral slip angles # switch to kinematic model for small velocities - if use_kinematic: + if abs(x[3]) < KIN_THRESH: alpha_LF = 0.0 alpha_RF = 0.0 alpha_LR = 0.0 alpha_RR = 0.0 else: alpha_LF = ( - np.arctan( + np.atan( (x[10] + lf * x[5] - x[14] * (R_w - x[16])) / (x[3] + 0.5 * T_f * x[5]) ) - x[2] ) alpha_RF = ( - np.arctan( + np.atan( (x[10] + lf * x[5] - x[14] * (R_w - x[16])) / (x[3] - 0.5 * T_f * x[5]) ) - x[2] ) - alpha_LR = np.arctan( + alpha_LR = np.atan( (x[10] - lr * x[5] - x[19] * (R_w - x[21])) / (x[3] + 0.5 * T_r * x[5]) ) - alpha_RR = np.arctan( + alpha_RR = np.atan( (x[10] - lr * x[5] - x[19] * (R_w - x[21])) / (x[3] - 0.5 * T_r * x[5]) ) @@ -481,9 +477,9 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): sumY_ur = (F_y_LR + F_y_RR) - F_RAR * np.cos(x[6]) - (F_SLR + F_SRR) * np.sin(x[6]) # dynamics common with single-track model - f = np.zeros((29,)) # init 'right hand side' + f = np.zeros(29) # init 'right hand side' # switch to kinematic model for small velocities - if use_kinematic: + if abs(x[3]) < KIN_THRESH: # wheelbase # lwb = lf + lr @@ -496,14 +492,11 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): # Use kinematic model with reference point at center of mass # wheelbase lwb = lf + lr - # system dynamics - x_ks = x[0:5] + x_ks = [x[0], x[1], x[2], x[3], x[4]] # kinematic model - # f_ks = vehicle_dynamics_ks_cog(x_ks, u, p) - # f = [f_ks[0], f_ks[1], f_ks[2], f_ks[3], f_ks[4]] # 1 2 3 4 5 - f_ks = vehicle_dynamics_ks(x_ks, u, params) - f[0:5] = f_ks + f_ks = vehicle_dynamics_ks_cog(np.array(x_ks), u, params) + f[0:5] = np.array([f_ks[0], f_ks[1], f_ks[2], f_ks[3], f_ks[4]]) # derivative of slip angle and yaw rate d_beta = (lr * u[0]) / ( lwb * np.cos(x[2]) ** 2 * (1 + (np.tan(x[2]) ** 2 * lr / lwb) ** 2) @@ -517,80 +510,65 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): + x[3] * np.cos(x[6]) * u[0] / np.cos(x[2]) ** 2 ) ) - # f.append(dd_psi) # 6 f[5] = dd_psi else: - f[0] = np.cos(beta + x[4]) * vel # 1 - f[1] = np.sin(beta + x[4]) * vel # 2 - f[2] = u[0] # 3 - f[3] = 1 / m * sumX + x[5] * x[10] # 4 - f[4] = x[5] # 5 - f[5] = ( - 1 / (I_z - (I_xz_s) ** 2 / I_Phi_s) * (sumN + I_xz_s / I_Phi_s * sumL) - ) # 6 + f[0] = np.cos(beta + x[4]) * vel + f[1] = np.sin(beta + x[4]) * vel + f[2] = u[0] + f[3] = 1 / m * sumX + x[5] * x[10] + f[4] = x[5] + f[5] = 1 / (I_z - (I_xz_s) ** 2 / I_Phi_s) * (sumN + I_xz_s / I_Phi_s * sumL) # remaining sprung mass dynamics - f[6] = x[7] # 7 - f[7] = 1 / (I_Phi_s - (I_xz_s) ** 2 / I_z) * (I_xz_s / I_z * sumN + sumL) # 8 - f[8] = x[9] # 9 - f[9] = 1 / I_y_s * sumM_s # 10 - f[10] = 1 / m_s * sumY_s - x[5] * x[3] # 11 - f[11] = x[12] # 12 - f[12] = g - 1 / m_s * sumZ_s # 13 + f[6] = x[7] + f[7] = 1 / (I_Phi_s - (I_xz_s) ** 2 / I_z) * (I_xz_s / I_z * sumN + sumL) + f[8] = x[9] + f[9] = 1 / I_y_s * sumM_s + f[10] = 1 / m_s * sumY_s - x[5] * x[3] + f[11] = x[12] + f[12] = g - 1 / m_s * sumZ_s # unsprung mass dynamics (front) - f[13] = x[14] # 14 - f[14] = 1 / I_uf * sumL_uf # 15 - f[15] = 1 / m_uf * sumY_uf - x[5] * x[3] # 16 - f[16] = x[17] # 17 - f[17] = g - 1 / m_uf * sumZ_uf # 18 + f[13] = x[14] + f[14] = 1 / I_uf * sumL_uf + f[15] = 1 / m_uf * sumY_uf - x[5] * x[3] + f[16] = x[17] + f[17] = g - 1 / m_uf * sumZ_uf # unsprung mass dynamics (rear) - f[18] = x[19] # 19 - f[19] = 1 / I_ur * sumL_ur # 20 - f[20] = 1 / m_ur * sumY_ur - x[5] * x[3] # 21 - f[21] = x[22] # 22 - f[22] = g - 1 / m_ur * sumZ_ur # 23 - - # convert acceleration input to brake and engine torque - splitting for brake/drive torque is outside of the integration - if u[0] > 0: + f[18] = x[19] + f[19] = 1 / I_ur * sumL_ur + f[20] = 1 / m_ur * sumY_ur - x[5] * x[3] + f[21] = x[22] + f[22] = g - 1 / m_ur * sumZ_ur + + # convert acceleration input to brake and engine torque + if u[1] > 0: T_B = 0.0 - T_E = m * R_w * u[0] + T_E = m * R_w * u[1] else: - T_B = m * R_w * u[0] + T_B = m * R_w * u[1] T_E = 0.0 - # wheel dynamics (p.T new parameter for torque splitting) - splitting for brake/drive torque is outside of the integration - f[23] = 1 / I_y_w * (-R_w * F_x_LF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) # 24 - f[24] = 1 / I_y_w * (-R_w * F_x_RF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) # 25 + # wheel dynamics (T new parameter for torque splitting) + f[23] = 1 / I_y_w * (-R_w * F_x_LF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) + f[24] = 1 / I_y_w * (-R_w * F_x_RF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) f[25] = ( 1 / I_y_w * (-R_w * F_x_LR + 0.5 * (1 - T_sb) * T_B + 0.5 * (1 - T_se) * T_E) - ) # 26 + ) f[26] = ( 1 / I_y_w * (-R_w * F_x_RR + 0.5 * (1 - T_sb) * T_B + 0.5 * (1 - T_se) * T_E) - ) # 27 + ) - # negative wheel spin forbidden handeled outside of this function + # negative wheel spin forbidden for iState in range(23, 27): if x[iState] < 0.0: x[iState] = 0.0 f[iState] = 0.0 # compliant joint equations - f[27] = dot_delta_y_f # 28 - f[28] = dot_delta_y_r # 29 - - # longitudinal slip - # s_lf - # s_rf - # s_lr - # s_rr - - # lateral slip - # alpha_LF - # alpha_RF - # alpha_LR - # alpha_RR + f[27] = dot_delta_y_f + f[28] = dot_delta_y_r return f diff --git a/f1tenth_gym/envs/dynamic_models/utils.py b/f1tenth_gym/envs/dynamic_models/utils.py index 6115bc77..3b5d420b 100644 --- a/f1tenth_gym/envs/dynamic_models/utils.py +++ b/f1tenth_gym/envs/dynamic_models/utils.py @@ -2,7 +2,6 @@ from numba import njit -@njit(cache=True) def upper_accel_limit(vel, a_max, v_switch): """ Upper acceleration limit, adjusts the acceleration based on constraints @@ -23,7 +22,6 @@ def upper_accel_limit(vel, a_max, v_switch): return pos_limit -@njit(cache=True) def accl_constraints(vel, a_long_d, v_switch, a_max, v_min, v_max): """ Acceleration constraints, adjusts the acceleration based on constraints @@ -86,7 +84,6 @@ def steering_constraint( return steering_velocity -@njit(cache=True) def pid_steer(steer, current_steer, max_sv): # steering steer_diff = steer - current_steer @@ -98,7 +95,6 @@ def pid_steer(steer, current_steer, max_sv): return sv -@njit(cache=True) def pid_accl(speed, current_speed, max_a, max_v, min_v): """ Basic controller for speed/steer -> accl./steer vel. From ab7a6ecb0599c52836b43439b374915175e47e0c Mon Sep 17 00:00:00 2001 From: nandant Date: Tue, 24 Sep 2024 17:59:31 +0200 Subject: [PATCH 41/55] Attempted speed optimization. --- .../dynamic_models/multi_body/multi_body.py | 504 +++++++++++------- f1tenth_gym/envs/dynamic_models/utils.py | 7 +- 2 files changed, 308 insertions(+), 203 deletions(-) diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py index e9ca761b..ea8bb377 100644 --- a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py +++ b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py @@ -80,90 +80,104 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): width = params["width"] # vehicle width [m] # steering constraints - s_min = params["s_min"] # minimum steering angle [rad] - s_max = params["s_max"] # maximum steering angle [rad] - sv_min = params["sv_min"] # minimum steering velocity [rad/s] - sv_max = params["sv_max"] # maximum steering velocity [rad/s] + # s_min = params["s_min"] # minimum steering angle [rad] + # s_max = params["s_max"] # maximum steering angle [rad] + # sv_min = params["sv_min"] # minimum steering velocity [rad/s] + # sv_max = params["sv_max"] # maximum steering velocity [rad/s] # longitudinal constraints - v_min = params["v_min"] # minimum velocity [m/s] - v_max = params["v_max"] # minimum velocity [m/s] - v_switch = params["v_switch"] # switching velocity [m/s] - a_max = params["a_max"] # maximum absolute acceleration [m/s^2] - - # masses - m = params["m"] # vehicle mass [kg] MASS - m_s = params["m_s"] # sprung mass [kg] SMASS - m_uf = params["m_uf"] # unsprung mass front [kg] UMASSF - m_ur = params["m_ur"] # unsprung mass rear [kg] UMASSR - - # axes distances - lf = params["lf"] - # distance from spring mass center of gravity to front axle [m] LENA - lr = params["lf"] - # distance from spring mass center of gravity to rear axle [m] LENB - - # moments of inertia of sprung mass - I_Phi_s = params["I_Phi_s"] - # moment of inertia for sprung mass in roll [kg m^2] IXS - I_y_s = params["I_y_s"] # moment of inertia for sprung mass in pitch [kg m^2] IYS - I_z = params["I_z"] # moment of inertia for sprung mass in yaw [kg m^2] IZZ - I_xz_s = params["I_xz_s"] # moment of inertia cross product [kg m^2] IXZ - - # suspension parameters - K_sf = params["K_sf"] # suspension spring rate (front) [N/m] KSF - K_sdf = params["K_sdf"] # suspension damping rate (front) [N s/m] KSDF - K_sr = params["K_sr"] # suspension spring rate (rear) [N/m] KSR - K_sdr = params["K_sdr"] # suspension damping rate (rear) [N s/m] KSDR - - # geometric parameters - T_f = params["T_f"] # track width front [m] TRWF - T_r = params["T_r"] # track width rear [m] TRWB - K_ras = params["K_ras"] - # lateral spring rate at compliant compliant pin joint between M_s and M_u [N/m] KRAS - - K_tsf = params["K_tsf"] - # auxiliary torsion roll stiffness per axle (normally negative) (front) [N m/rad] KTSF - K_tsr = params["K_tsr"] - # auxiliary torsion roll stiffness per axle (normally negative) (rear) [N m/rad] KTSR - K_rad = params["K_rad"] - # damping rate at compliant compliant pin joint between M_s and M_u [N s/m] KRADP - K_zt = params["K_zt"] # vertical spring rate of tire [N/m] TSPRINGR - - h_cg = params["h_cg"] - # center of gravity height of total mass [m] HCG (mainly required for conversion to other vehicle models) - h_raf = params["h_raf"] # height of roll axis above ground (front) [m] HRAF - h_rar = params["h_rar"] # height of roll axis above ground (rear) [m] HRAR - - h_s = params["h_s"] # M_s center of gravity above ground [m] HS - - I_uf = params["I_uf"] - # moment of inertia for unsprung mass about x-axis (front) [kg m^2] IXUF - I_ur = params["I_ur"] - # moment of inertia for unsprung mass about x-axis (rear) [kg m^2] IXUR - I_y_w = params["I_y_w"] - # wheel inertia, from internet forum for 235/65 R 17 [kg m^2] - - K_lt = params["K_lt"] - # lateral compliance rate of tire, wheel, and suspension, per tire [m/N] KLT - R_w = params["R_w"] - # effective wheel/tire radius chosen as tire rolling radius RR taken from ADAMS documentation [m] - - # split of brake and engine torque - T_sb = params["T_sb"] - T_se = params["T_se"] - - # suspension parameters - D_f = params["D_f"] # [rad/m] DF - D_r = params["D_r"] # [rad/m] DR - E_f = params["E_f"] # [needs conversion if nonzero] EF - E_r = params["E_r"] # [needs conversion if nonzero] ER + # v_min = params["v_min"] # minimum velocity [m/s] + # v_max = params["v_max"] # minimum velocity [m/s] + # v_switch = params["v_switch"] # switching velocity [m/s] + # a_max = params["a_max"] # maximum absolute acceleration [m/s^2] + + # # masses + # m = params["m"] # vehicle mass [kg] MASS + # m_s = params["m_s"] # sprung mass [kg] SMASS + # m_uf = params["m_uf"] # unsprung mass front [kg] UMASSF + # m_ur = params["m_ur"] # unsprung mass rear [kg] UMASSR + + # # axes distances + # lf = params["lf"] + # # distance from spring mass center of gravity to front axle [m] LENA + # lr = params["lf"] + # # distance from spring mass center of gravity to rear axle [m] LENB + + # # moments of inertia of sprung mass + # I_Phi_s = params["I_Phi_s"] + # # moment of inertia for sprung mass in roll [kg m^2] IXS + # I_y_s = params["I_y_s"] # moment of inertia for sprung mass in pitch [kg m^2] IYS + # I_z = params["I_z"] # moment of inertia for sprung mass in yaw [kg m^2] IZZ + # I_xz_s = params["I_xz_s"] # moment of inertia cross product [kg m^2] IXZ + + # # suspension parameters + # K_sf = params["K_sf"] # suspension spring rate (front) [N/m] KSF + # K_sdf = params["K_sdf"] # suspension damping rate (front) [N s/m] KSDF + # K_sr = params["K_sr"] # suspension spring rate (rear) [N/m] KSR + # K_sdr = params["K_sdr"] # suspension damping rate (rear) [N s/m] KSDR + + # # geometric parameters + # T_f = params["T_f"] # track width front [m] TRWF + # T_r = params["T_r"] # track width rear [m] TRWB + # K_ras = params["K_ras"] + # # lateral spring rate at compliant compliant pin joint between M_s and M_u [N/m] KRAS + + # K_tsf = params["K_tsf"] + # # auxiliary torsion roll stiffness per axle (normally negative) (front) [N m/rad] KTSF + # K_tsr = params["K_tsr"] + # # auxiliary torsion roll stiffness per axle (normally negative) (rear) [N m/rad] KTSR + # K_rad = params["K_rad"] + # # damping rate at compliant compliant pin joint between M_s and M_u [N s/m] KRADP + # K_zt = params["K_zt"] # vertical spring rate of tire [N/m] TSPRINGR + + # h_cg = params["h_cg"] + # # center of gravity height of total mass [m] HCG (mainly required for conversion to other vehicle models) + # h_raf = params["h_raf"] # height of roll axis above ground (front) [m] HRAF + # h_rar = params["h_rar"] # height of roll axis above ground (rear) [m] HRAR + + # h_s = params["h_s"] # M_s center of gravity above ground [m] HS + + # I_uf = params["I_uf"] + # # moment of inertia for unsprung mass about x-axis (front) [kg m^2] IXUF + # I_ur = params["I_ur"] + # # moment of inertia for unsprung mass about x-axis (rear) [kg m^2] IXUR + # I_y_w = params["I_y_w"] + # # wheel inertia, from internet forum for 235/65 R 17 [kg m^2] + + # K_lt = params["K_lt"] + # # lateral compliance rate of tire, wheel, and suspension, per tire [m/N] KLT + # R_w = params["R_w"] + # # effective wheel/tire radius chosen as tire rolling radius RR taken from ADAMS documentation [m] + + # # split of brake and engine torque + # T_sb = params["T_sb"] + # T_se = params["T_se"] + + # # suspension parameters + # D_f = params["D_f"] # [rad/m] DF + # D_r = params["D_r"] # [rad/m] DR + # E_f = params["E_f"] # [needs conversion if nonzero] EF + # E_r = params["E_r"] # [needs conversion if nonzero] ER KIN_THRESH = 0.5 # consider steering and acceleration constraints - outside of the integration - u[0] = steering_constraint(x[2], u_init[0], s_min, s_max, sv_min, sv_max) - u[1] = accl_constraints(x[3], u_init[1], v_switch, a_max, v_min, v_max) + u[0] = steering_constraint( + x[2], + u_init[0], + params["s_min"], + params["s_max"], + params["sv_min"], + params["sv_max"], + ) + u[1] = accl_constraints( + x[3], + u_init[1], + params["v_switch"], + params["a_max"], + params["v_min"], + params["v_max"], + ) if abs(x[3]) < KIN_THRESH: beta = 0.0 @@ -172,20 +186,36 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): vel = np.sqrt(x[3] ** 2 + x[10] ** 2) # vertical tire forces - F_z_LF = (x[16] + R_w * (np.cos(x[13]) - 1) - 0.5 * T_f * np.sin(x[13])) * K_zt - F_z_RF = (x[16] + R_w * (np.cos(x[13]) - 1) + 0.5 * T_f * np.sin(x[13])) * K_zt - F_z_LR = (x[21] + R_w * (np.cos(x[18]) - 1) - 0.5 * T_r * np.sin(x[18])) * K_zt - F_z_RR = (x[21] + R_w * (np.cos(x[18]) - 1) + 0.5 * T_r * np.sin(x[18])) * K_zt + F_z_LF = ( + x[16] + + params["R_w"] * (np.cos(x[13]) - 1) + - 0.5 * params["T_f"] * np.sin(x[13]) + ) * params["K_zt"] + F_z_RF = ( + x[16] + + params["R_w"] * (np.cos(x[13]) - 1) + + 0.5 * params["T_f"] * np.sin(x[13]) + ) * params["K_zt"] + F_z_LR = ( + x[21] + + params["R_w"] * (np.cos(x[18]) - 1) + - 0.5 * params["T_r"] * np.sin(x[18]) + ) * params["K_zt"] + F_z_RR = ( + x[21] + + params["R_w"] * (np.cos(x[18]) - 1) + + 0.5 * params["T_r"] * np.sin(x[18]) + ) * params["K_zt"] # obtain individual tire speeds - u_w_lf = (x[3] + 0.5 * T_f * x[5]) * np.cos(x[2]) + (x[10] + lf * x[5]) * np.sin( - x[2] - ) - u_w_rf = (x[3] - 0.5 * T_f * x[5]) * np.cos(x[2]) + (x[10] + lf * x[5]) * np.sin( - x[2] - ) - u_w_lr = x[3] + 0.5 * T_r * x[5] - u_w_rr = x[3] - 0.5 * T_r * x[5] + u_w_lf = (x[3] + 0.5 * params["T_f"] * x[5]) * np.cos(x[2]) + ( + x[10] + params["lf"] * x[5] + ) * np.sin(x[2]) + u_w_rf = (x[3] - 0.5 * params["T_f"] * x[5]) * np.cos(x[2]) + ( + x[10] + params["lf"] * x[5] + ) * np.sin(x[2]) + u_w_lr = x[3] + 0.5 * params["T_r"] * x[5] + u_w_rr = x[3] - 0.5 * params["T_r"] * x[5] # negative wheel spin forbidden if u_w_lf < 0.0: @@ -207,10 +237,10 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): s_lr = 0.0 s_rr = 0.0 else: - s_lf = 1 - R_w * x[23] / u_w_lf - s_rf = 1 - R_w * x[24] / u_w_rf - s_lr = 1 - R_w * x[25] / u_w_lr - s_rr = 1 - R_w * x[26] / u_w_rr + s_lf = 1 - params["R_w"] * x[23] / u_w_lf + s_rf = 1 - params["R_w"] * x[24] / u_w_rf + s_lr = 1 - params["R_w"] * x[25] / u_w_lr + s_rr = 1 - params["R_w"] * x[26] / u_w_rr # lateral slip angles # switch to kinematic model for small velocities @@ -222,63 +252,67 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): else: alpha_LF = ( np.atan( - (x[10] + lf * x[5] - x[14] * (R_w - x[16])) / (x[3] + 0.5 * T_f * x[5]) + (x[10] + params["lf"] * x[5] - x[14] * (params["R_w"] - x[16])) + / (x[3] + 0.5 * params["T_f"] * x[5]) ) - x[2] ) alpha_RF = ( np.atan( - (x[10] + lf * x[5] - x[14] * (R_w - x[16])) / (x[3] - 0.5 * T_f * x[5]) + (x[10] + params["lf"] * x[5] - x[14] * (params["R_w"] - x[16])) + / (x[3] - 0.5 * params["T_f"] * x[5]) ) - x[2] ) alpha_LR = np.atan( - (x[10] - lr * x[5] - x[19] * (R_w - x[21])) / (x[3] + 0.5 * T_r * x[5]) + (x[10] - params["lr"] * x[5] - x[19] * (params["R_w"] - x[21])) + / (x[3] + 0.5 * params["T_r"] * x[5]) ) alpha_RR = np.atan( - (x[10] - lr * x[5] - x[19] * (R_w - x[21])) / (x[3] - 0.5 * T_r * x[5]) + (x[10] - params["lr"] * x[5] - x[19] * (params["R_w"] - x[21])) + / (x[3] - 0.5 * params["T_r"] * x[5]) ) # auxiliary suspension movement z_SLF = ( - (h_s - R_w + x[16] - x[11]) / np.cos(x[6]) - - h_s - + R_w - + lf * x[8] - + 0.5 * (x[6] - x[13]) * T_f + (params["h_s"] - params["R_w"] + x[16] - x[11]) / np.cos(x[6]) + - params["h_s"] + + params["R_w"] + + params["lf"] * x[8] + + 0.5 * (x[6] - x[13]) * params["T_f"] ) z_SRF = ( - (h_s - R_w + x[16] - x[11]) / np.cos(x[6]) - - h_s - + R_w - + lf * x[8] - - 0.5 * (x[6] - x[13]) * T_f + (params["h_s"] - params["R_w"] + x[16] - x[11]) / np.cos(x[6]) + - params["h_s"] + + params["R_w"] + + params["lf"] * x[8] + - 0.5 * (x[6] - x[13]) * params["T_f"] ) z_SLR = ( - (h_s - R_w + x[21] - x[11]) / np.cos(x[6]) - - h_s - + R_w - - lr * x[8] - + 0.5 * (x[6] - x[18]) * T_r + (params["h_s"] - params["R_w"] + x[21] - x[11]) / np.cos(x[6]) + - params["h_s"] + + params["R_w"] + - params["lr"] * x[8] + + 0.5 * (x[6] - x[18]) * params["T_r"] ) z_SRR = ( - (h_s - R_w + x[21] - x[11]) / np.cos(x[6]) - - h_s - + R_w - - lr * x[8] - - 0.5 * (x[6] - x[18]) * T_r + (params["h_s"] - params["R_w"] + x[21] - x[11]) / np.cos(x[6]) + - params["h_s"] + + params["R_w"] + - params["lr"] * x[8] + - 0.5 * (x[6] - x[18]) * params["T_r"] ) - dz_SLF = x[17] - x[12] + lf * x[9] + 0.5 * (x[7] - x[14]) * T_f - dz_SRF = x[17] - x[12] + lf * x[9] - 0.5 * (x[7] - x[14]) * T_f - dz_SLR = x[22] - x[12] - lr * x[9] + 0.5 * (x[7] - x[19]) * T_r - dz_SRR = x[22] - x[12] - lr * x[9] - 0.5 * (x[7] - x[19]) * T_r + dz_SLF = x[17] - x[12] + params["lf"] * x[9] + 0.5 * (x[7] - x[14]) * params["T_f"] + dz_SRF = x[17] - x[12] + params["lf"] * x[9] - 0.5 * (x[7] - x[14]) * params["T_f"] + dz_SLR = x[22] - x[12] - params["lr"] * x[9] + 0.5 * (x[7] - x[19]) * params["T_r"] + dz_SRR = x[22] - x[12] - params["lr"] * x[9] - 0.5 * (x[7] - x[19]) * params["T_r"] # camber angles - gamma_LF = x[6] + D_f * z_SLF + E_f * (z_SLF) ** 2 - gamma_RF = x[6] - D_f * z_SRF - E_f * (z_SRF) ** 2 - gamma_LR = x[6] + D_r * z_SLR + E_r * (z_SLR) ** 2 - gamma_RR = x[6] - D_r * z_SRR - E_r * (z_SRR) ** 2 + gamma_LF = x[6] + params["D_f"] * z_SLF + params["E_f"] * (z_SLF) ** 2 + gamma_RF = x[6] - params["D_f"] * z_SRF - params["E_f"] * (z_SRF) ** 2 + gamma_LR = x[6] + params["D_r"] * z_SLR + params["E_r"] * (z_SLR) ** 2 + gamma_RR = x[6] - params["D_r"] * z_SRR - params["E_r"] * (z_SRR) ** 2 # compute longitudinal tire forces using the magic formula for pure slip F0_x_LF = formula_longitudinal(s_lf, gamma_LF, F_z_LF, params) @@ -321,8 +355,8 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): ) # auxiliary movements for compliant joint equations - delta_z_f = h_s - R_w + x[16] - x[11] - delta_z_r = h_s - R_w + x[21] - x[11] + delta_z_f = params["h_s"] - params["R_w"] + x[16] - x[11] + delta_z_r = params["h_s"] - params["R_w"] + x[21] - x[11] delta_phi_f = x[6] - x[13] delta_phi_r = x[6] - x[18] @@ -333,64 +367,64 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): dot_delta_z_f = x[17] - x[12] dot_delta_z_r = x[22] - x[12] - dot_delta_y_f = x[10] + lf * x[5] - x[15] - dot_delta_y_r = x[10] - lr * x[5] - x[20] + dot_delta_y_f = x[10] + params["lf"] * x[5] - x[15] + dot_delta_y_r = x[10] - params["lr"] * x[5] - x[20] delta_f = ( delta_z_f * np.sin(x[6]) - x[27] * np.cos(x[6]) - - (h_raf - R_w) * np.sin(delta_phi_f) + - (params["h_raf"] - params["R_w"]) * np.sin(delta_phi_f) ) delta_r = ( delta_z_r * np.sin(x[6]) - x[28] * np.cos(x[6]) - - (h_rar - R_w) * np.sin(delta_phi_r) + - (params["h_rar"] - params["R_w"]) * np.sin(delta_phi_r) ) dot_delta_f = ( (delta_z_f * np.cos(x[6]) + x[27] * np.sin(x[6])) * x[7] + dot_delta_z_f * np.sin(x[6]) - dot_delta_y_f * np.cos(x[6]) - - (h_raf - R_w) * np.cos(delta_phi_f) * dot_delta_phi_f + - (params["h_raf"] - params["R_w"]) * np.cos(delta_phi_f) * dot_delta_phi_f ) dot_delta_r = ( (delta_z_r * np.cos(x[6]) + x[28] * np.sin(x[6])) * x[7] + dot_delta_z_r * np.sin(x[6]) - dot_delta_y_r * np.cos(x[6]) - - (h_rar - R_w) * np.cos(delta_phi_r) * dot_delta_phi_r + - (params["h_rar"] - params["R_w"]) * np.cos(delta_phi_r) * dot_delta_phi_r ) # compliant joint forces - F_RAF = delta_f * K_ras + dot_delta_f * K_rad - F_RAR = delta_r * K_ras + dot_delta_r * K_rad + F_RAF = delta_f * params["K_ras"] + dot_delta_f * params["K_rad"] + F_RAR = delta_r * params["K_ras"] + dot_delta_r * params["K_rad"] # auxiliary suspension forces (bump stop neglected squat/lift forces neglected) F_SLF = ( - m_s * g * lr / (2 * (lf + lr)) - - z_SLF * K_sf - - dz_SLF * K_sdf - + (x[6] - x[13]) * K_tsf / T_f + params["m_s"] * g * params["lr"] / (2 * (params["lf"] + params["lr"])) + - z_SLF * params["K_sf"] + - dz_SLF * params["K_sdf"] + + (x[6] - x[13]) * params["K_tsf"] / params["T_f"] ) F_SRF = ( - m_s * g * lr / (2 * (lf + lr)) - - z_SRF * K_sf - - dz_SRF * K_sdf - - (x[6] - x[13]) * K_tsf / T_f + params["m_s"] * g * params["lr"] / (2 * (params["lf"] + params["lr"])) + - z_SRF * params["K_sf"] + - dz_SRF * params["K_sdf"] + - (x[6] - x[13]) * params["K_tsf"] / params["T_f"] ) F_SLR = ( - m_s * g * lf / (2 * (lf + lr)) - - z_SLR * K_sr - - dz_SLR * K_sdr - + (x[6] - x[18]) * K_tsr / T_r + params["m_s"] * g * params["lf"] / (2 * (params["lf"] + params["lr"])) + - z_SLR * params["K_sr"] + - dz_SLR * params["K_sdr"] + + (x[6] - x[18]) * params["K_tsr"] / params["T_r"] ) F_SRR = ( - m_s * g * lf / (2 * (lf + lr)) - - z_SRR * K_sr - - dz_SRR * K_sdr - - (x[6] - x[18]) * K_tsr / T_r + params["m_s"] * g * params["lf"] / (2 * (params["lf"] + params["lr"])) + - z_SRR * params["K_sr"] + - dz_SRR * params["K_sdr"] + - (x[6] - x[18]) * params["K_tsr"] / params["T_r"] ) # auxiliary variables sprung mass @@ -402,12 +436,12 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): ) sumN = ( - (F_y_LF + F_y_RF) * lf * np.cos(x[2]) - + (F_x_LF + F_x_RF) * lf * np.sin(x[2]) - + (F_y_RF - F_y_LF) * 0.5 * T_f * np.sin(x[2]) - + (F_x_LF - F_x_RF) * 0.5 * T_f * np.cos(x[2]) - + (F_x_LR - F_x_RR) * 0.5 * T_r - - (F_y_LR + F_y_RR) * lr + (F_y_LF + F_y_RF) * params["lf"] * np.cos(x[2]) + + (F_x_LF + F_x_RF) * params["lf"] * np.sin(x[2]) + + (F_y_RF - F_y_LF) * 0.5 * params["T_f"] * np.sin(x[2]) + + (F_x_LF - F_x_RF) * 0.5 * params["T_f"] * np.cos(x[2]) + + (F_x_LR - F_x_RR) * 0.5 * params["T_r"] + - (F_y_LR + F_y_RR) * params["lr"] ) sumY_s = (F_RAF + F_RAR) * np.cos(x[6]) + (F_SLF + F_SLR + F_SRF + F_SRR) * np.sin( @@ -415,16 +449,28 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): ) sumL = ( - 0.5 * F_SLF * T_f - + 0.5 * F_SLR * T_r - - 0.5 * F_SRF * T_f - - 0.5 * F_SRR * T_r + 0.5 * F_SLF * params["T_f"] + + 0.5 * F_SLR * params["T_r"] + - 0.5 * F_SRF * params["T_f"] + - 0.5 * F_SRR * params["T_r"] - F_RAF / np.cos(x[6]) - * (h_s - x[11] - R_w + x[16] - (h_raf - R_w) * np.cos(x[13])) + * ( + params["h_s"] + - x[11] + - params["R_w"] + + x[16] + - (params["h_raf"] - params["R_w"]) * np.cos(x[13]) + ) - F_RAR / np.cos(x[6]) - * (h_s - x[11] - R_w + x[21] - (h_rar - R_w) * np.cos(x[18])) + * ( + params["h_s"] + - x[11] + - params["R_w"] + + x[21] + - (params["h_rar"] - params["R_w"]) * np.cos(x[18]) + ) ) sumZ_s = (F_SLF + F_SLR + F_SRF + F_SRR) * np.cos(x[6]) - (F_RAF + F_RAR) * np.sin( @@ -432,35 +478,55 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): ) sumM_s = ( - lf * (F_SLF + F_SRF) - - lr * (F_SLR + F_SRR) + params["lf"] * (F_SLF + F_SRF) + - params["lr"] * (F_SLR + F_SRR) + ( (F_x_LF + F_x_RF) * np.cos(x[2]) - (F_y_LF + F_y_RF) * np.sin(x[2]) + F_x_LR + F_x_RR ) - * (h_s - x[11]) + * (params["h_s"] - x[11]) ) # auxiliary variables unsprung mass sumL_uf = ( - 0.5 * F_SRF * T_f - - 0.5 * F_SLF * T_f - - F_RAF * (h_raf - R_w) - + F_z_LF * (R_w * np.sin(x[13]) + 0.5 * T_f * np.cos(x[13]) - K_lt * F_y_LF) - - F_z_RF * (-R_w * np.sin(x[13]) + 0.5 * T_f * np.cos(x[13]) + K_lt * F_y_RF) + 0.5 * F_SRF * params["T_f"] + - 0.5 * F_SLF * params["T_f"] + - F_RAF * (params["h_raf"] - params["R_w"]) + + F_z_LF + * ( + params["R_w"] * np.sin(x[13]) + + 0.5 * params["T_f"] * np.cos(x[13]) + - params["K_lt"] * F_y_LF + ) + - F_z_RF + * ( + -params["R_w"] * np.sin(x[13]) + + 0.5 * params["T_f"] * np.cos(x[13]) + + params["K_lt"] * F_y_RF + ) - ((F_y_LF + F_y_RF) * np.cos(x[2]) + (F_x_LF + F_x_RF) * np.sin(x[2])) - * (R_w - x[16]) + * (params["R_w"] - x[16]) ) sumL_ur = ( - 0.5 * F_SRR * T_r - - 0.5 * F_SLR * T_r - - F_RAR * (h_rar - R_w) - + F_z_LR * (R_w * np.sin(x[18]) + 0.5 * T_r * np.cos(x[18]) - K_lt * F_y_LR) - - F_z_RR * (-R_w * np.sin(x[18]) + 0.5 * T_r * np.cos(x[18]) + K_lt * F_y_RR) - - (F_y_LR + F_y_RR) * (R_w - x[21]) + 0.5 * F_SRR * params["T_r"] + - 0.5 * F_SLR * params["T_r"] + - F_RAR * (params["h_rar"] - params["R_w"]) + + F_z_LR + * ( + params["R_w"] * np.sin(x[18]) + + 0.5 * params["T_r"] * np.cos(x[18]) + - params["K_lt"] * F_y_LR + ) + - F_z_RR + * ( + -params["R_w"] * np.sin(x[18]) + + 0.5 * params["T_r"] * np.cos(x[18]) + + params["K_lt"] * F_y_RR + ) + - (F_y_LR + F_y_RR) * (params["R_w"] - x[21]) ) sumZ_uf = F_z_LF + F_z_RF + F_RAF * np.sin(x[6]) - (F_SLF + F_SRF) * np.cos(x[6]) @@ -491,15 +557,17 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): # Use kinematic model with reference point at center of mass # wheelbase - lwb = lf + lr + lwb = params["lf"] + params["lr"] # system dynamics x_ks = [x[0], x[1], x[2], x[3], x[4]] # kinematic model f_ks = vehicle_dynamics_ks_cog(np.array(x_ks), u, params) f[0:5] = np.array([f_ks[0], f_ks[1], f_ks[2], f_ks[3], f_ks[4]]) # derivative of slip angle and yaw rate - d_beta = (lr * u[0]) / ( - lwb * np.cos(x[2]) ** 2 * (1 + (np.tan(x[2]) ** 2 * lr / lwb) ** 2) + d_beta = (params["lr"] * u[0]) / ( + lwb + * np.cos(x[2]) ** 2 + * (1 + (np.tan(x[2]) ** 2 * params["lr"] / lwb) ** 2) ) dd_psi = ( 1 @@ -516,49 +584,85 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): f[0] = np.cos(beta + x[4]) * vel f[1] = np.sin(beta + x[4]) * vel f[2] = u[0] - f[3] = 1 / m * sumX + x[5] * x[10] + f[3] = 1 / params["m"] * sumX + x[5] * x[10] f[4] = x[5] - f[5] = 1 / (I_z - (I_xz_s) ** 2 / I_Phi_s) * (sumN + I_xz_s / I_Phi_s * sumL) + f[5] = ( + 1 + / (params["I_z"] - (params["I_xz_s"]) ** 2 / params["I_Phi_s"]) + * (sumN + params["I_xz_s"] / params["I_Phi_s"] * sumL) + ) # remaining sprung mass dynamics f[6] = x[7] - f[7] = 1 / (I_Phi_s - (I_xz_s) ** 2 / I_z) * (I_xz_s / I_z * sumN + sumL) + f[7] = ( + 1 + / (params["I_Phi_s"] - (params["I_xz_s"]) ** 2 / params["I_z"]) + * (params["I_xz_s"] / params["I_z"] * sumN + sumL) + ) f[8] = x[9] - f[9] = 1 / I_y_s * sumM_s - f[10] = 1 / m_s * sumY_s - x[5] * x[3] + f[9] = 1 / params["I_y_s"] * sumM_s + f[10] = 1 / params["m_s"] * sumY_s - x[5] * x[3] f[11] = x[12] - f[12] = g - 1 / m_s * sumZ_s + f[12] = g - 1 / params["m_s"] * sumZ_s # unsprung mass dynamics (front) f[13] = x[14] - f[14] = 1 / I_uf * sumL_uf - f[15] = 1 / m_uf * sumY_uf - x[5] * x[3] + f[14] = 1 / params["I_uf"] * sumL_uf + f[15] = 1 / params["m_uf"] * sumY_uf - x[5] * x[3] f[16] = x[17] - f[17] = g - 1 / m_uf * sumZ_uf + f[17] = g - 1 / params["m_uf"] * sumZ_uf # unsprung mass dynamics (rear) f[18] = x[19] - f[19] = 1 / I_ur * sumL_ur - f[20] = 1 / m_ur * sumY_ur - x[5] * x[3] + f[19] = 1 / params["I_ur"] * sumL_ur + f[20] = 1 / params["m_ur"] * sumY_ur - x[5] * x[3] f[21] = x[22] - f[22] = g - 1 / m_ur * sumZ_ur + f[22] = g - 1 / params["m_ur"] * sumZ_ur # convert acceleration input to brake and engine torque if u[1] > 0: T_B = 0.0 - T_E = m * R_w * u[1] + T_E = params["m"] * params["R_w"] * u[1] else: - T_B = m * R_w * u[1] + T_B = params["m"] * params["R_w"] * u[1] T_E = 0.0 # wheel dynamics (T new parameter for torque splitting) - f[23] = 1 / I_y_w * (-R_w * F_x_LF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) - f[24] = 1 / I_y_w * (-R_w * F_x_RF + 0.5 * T_sb * T_B + 0.5 * T_se * T_E) + f[23] = ( + 1 + / params["I_y_w"] + * ( + -params["R_w"] * F_x_LF + + 0.5 * params["T_sb"] * T_B + + 0.5 * params["T_se"] * T_E + ) + ) + f[24] = ( + 1 + / params["I_y_w"] + * ( + -params["R_w"] * F_x_RF + + 0.5 * params["T_sb"] * T_B + + 0.5 * params["T_se"] * T_E + ) + ) f[25] = ( - 1 / I_y_w * (-R_w * F_x_LR + 0.5 * (1 - T_sb) * T_B + 0.5 * (1 - T_se) * T_E) + 1 + / params["I_y_w"] + * ( + -params["R_w"] * F_x_LR + + 0.5 * (1 - params["T_sb"]) * T_B + + 0.5 * (1 - params["T_se"]) * T_E + ) ) f[26] = ( - 1 / I_y_w * (-R_w * F_x_RR + 0.5 * (1 - T_sb) * T_B + 0.5 * (1 - T_se) * T_E) + 1 + / params["I_y_w"] + * ( + -params["R_w"] * F_x_RR + + 0.5 * (1 - params["T_sb"]) * T_B + + 0.5 * (1 - params["T_se"]) * T_E + ) ) # negative wheel spin forbidden diff --git a/f1tenth_gym/envs/dynamic_models/utils.py b/f1tenth_gym/envs/dynamic_models/utils.py index 3b5d420b..864da470 100644 --- a/f1tenth_gym/envs/dynamic_models/utils.py +++ b/f1tenth_gym/envs/dynamic_models/utils.py @@ -1,7 +1,7 @@ import numpy as np from numba import njit - +@njit(cache=True) def upper_accel_limit(vel, a_max, v_switch): """ Upper acceleration limit, adjusts the acceleration based on constraints @@ -21,7 +21,7 @@ def upper_accel_limit(vel, a_max, v_switch): return pos_limit - +@njit(cache=True) def accl_constraints(vel, a_long_d, v_switch, a_max, v_min, v_max): """ Acceleration constraints, adjusts the acceleration based on constraints @@ -83,7 +83,7 @@ def steering_constraint( return steering_velocity - +@njit(cache=True) def pid_steer(steer, current_steer, max_sv): # steering steer_diff = steer - current_steer @@ -95,6 +95,7 @@ def pid_steer(steer, current_steer, max_sv): return sv +@njit(cache=True) def pid_accl(speed, current_speed, max_a, max_v, min_v): """ Basic controller for speed/steer -> accl./steer vel. From 0348928e323cf616fffd200f703f08ba8fd7fe7a Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 24 Sep 2024 17:34:33 -0400 Subject: [PATCH 42/55] Fix rendering of tires to be correct --- f1tenth_gym/envs/rendering/pyqt_objects.py | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/f1tenth_gym/envs/rendering/pyqt_objects.py b/f1tenth_gym/envs/rendering/pyqt_objects.py index 046064d2..7f437252 100644 --- a/f1tenth_gym/envs/rendering/pyqt_objects.py +++ b/f1tenth_gym/envs/rendering/pyqt_objects.py @@ -172,9 +172,13 @@ def _get_tire_vertices(pose, length, width, tire_width, tire_length, index, stee vertices (np.ndarray, (4, 2)): corner vertices of the vehicle body """ pose_arr = np.array(pose) - pose_arr[2] = pose_arr[2] + steering - H = get_trmtx(pose_arr) if index == 'fl': + # Shift back, rotate + H_shift = get_trmtx(np.array([-(length/2 - tire_length/2), -(width/2 - tire_width/2), 0])) + H_steer = get_trmtx(np.array([0, 0, steering])) + H_back = get_trmtx(np.array([length/2 - tire_length/2, width/2 - tire_width/2, 0])) + H = get_trmtx(pose_arr) + H = H.dot(H_back).dot(H_steer).dot(H_shift) fl = H.dot(np.asarray([[length / 2], [width / 2], [0.0], [1.0]])).flatten() fr = H.dot(np.asarray([[length / 2], [width / 2 - tire_width], [0.0], [1.0]])).flatten() rr = H.dot(np.asarray([[length / 2 - tire_length], [width / 2 - tire_width], [0.0], [1.0]])).flatten() @@ -187,6 +191,13 @@ def _get_tire_vertices(pose, length, width, tire_width, tire_length, index, stee [[rl[0], rl[1]], [fl[0], fl[1]], [fr[0], fr[1]], [rr[0], rr[1]], [rl[0], rl[1]]] ) elif index == 'fr': + # Shift back, rotate + H_shift = get_trmtx(np.array([-(length/2 - tire_length/2), -(-width/2 + tire_width/2), 0])) + H_steer = get_trmtx(np.array([0, 0, steering])) + H_back = get_trmtx(np.array([length/2 - tire_length/2, -width/2 + tire_width/2, 0])) + H = get_trmtx(pose_arr) + H = H.dot(H_back).dot(H_steer).dot(H_shift) + fl = H.dot(np.asarray([[length / 2], [-width / 2 + tire_width], [0.0], [1.0]])).flatten() fr = H.dot(np.asarray([[length / 2], [-width / 2], [0.0], [1.0]])).flatten() rr = H.dot(np.asarray([[length / 2 - tire_length], [-width / 2], [0.0], [1.0]])).flatten() From 00e268d857477ee72c7310285ee7f29961f5ace3 Mon Sep 17 00:00:00 2001 From: nandant Date: Wed, 25 Sep 2024 00:36:36 +0200 Subject: [PATCH 43/55] Removing keepalive from example --- examples/waypoint_follow.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/examples/waypoint_follow.py b/examples/waypoint_follow.py index f61a7c72..07927199 100644 --- a/examples/waypoint_follow.py +++ b/examples/waypoint_follow.py @@ -343,8 +343,7 @@ def main(): laptime = 0.0 start = time.time() - i = 1 - while not done or i < 1000: + while not done: action = env.action_space.sample() for i, agent_id in enumerate(obs.keys()): speed, steer = planner.plan( @@ -358,7 +357,6 @@ def main(): obs, step_reward, done, truncated, info = env.step(action) laptime += step_reward frame = env.render() - i += 1 print("Sim elapsed time:", laptime, "Real elapsed time:", time.time() - start) From c782fb41d7ef8b18f42c3dd71e07cd8e976a5b75 Mon Sep 17 00:00:00 2001 From: nandant Date: Sat, 28 Sep 2024 01:13:58 +0200 Subject: [PATCH 44/55] Updated observations for futher compatibility. --- f1tenth_gym/envs/base_classes.py | 13 ++- f1tenth_gym/envs/dynamic_models/__init__.py | 23 +++- f1tenth_gym/envs/dynamic_models/kinematic.py | 16 +++ .../dynamic_models/multi_body/__init__.py | 2 +- .../dynamic_models/multi_body/multi_body.py | 16 +++ .../envs/dynamic_models/single_track.py | 16 +++ f1tenth_gym/envs/observation.py | 36 +++---- tests/test_dynamics.py | 102 +++++++++--------- 8 files changed, 149 insertions(+), 75 deletions(-) diff --git a/f1tenth_gym/envs/base_classes.py b/f1tenth_gym/envs/base_classes.py index 0dea4e6e..4bfe5c82 100644 --- a/f1tenth_gym/envs/base_classes.py +++ b/f1tenth_gym/envs/base_classes.py @@ -102,6 +102,7 @@ def __init__( self.integrator = integrator self.action_type = action_type self.model = model + self.standard_state_fn = self.model.get_standardized_state_fn() # state of the vehicle self.state = self.model.get_initial_state(params=self.params) @@ -312,7 +313,7 @@ def update_pose(self, raw_steer, vel): ) # bound yaw angle - self.state[4] %= 2 * np.pi + self.state[4] %= 2 * np.pi # TODO: This is a problem waiting to happen # update scan current_scan = RaceCar.scan_simulator.scan( @@ -356,6 +357,16 @@ def update_scan(self, agent_scans, agent_index): agent_scans[agent_index] = new_scan + @property + def standard_state(self) -> dict: + """ + Returns the state of the vehicle as an observation + + Returns: + np.ndarray (7, ): state of the vehicle + """ + return self.standard_state_fn(self.state) + class Simulator(object): """ diff --git a/f1tenth_gym/envs/dynamic_models/__init__.py b/f1tenth_gym/envs/dynamic_models/__init__.py index 8dec7f4d..9837f013 100644 --- a/f1tenth_gym/envs/dynamic_models/__init__.py +++ b/f1tenth_gym/envs/dynamic_models/__init__.py @@ -7,9 +7,9 @@ from enum import Enum import numpy as np -from .kinematic import vehicle_dynamics_ks -from .single_track import vehicle_dynamics_st -from .multi_body import init_mb, vehicle_dynamics_mb +from .kinematic import vehicle_dynamics_ks, get_standardized_state_ks +from .single_track import vehicle_dynamics_st, get_standardized_state_st +from .multi_body import init_mb, vehicle_dynamics_mb, get_standardized_state_mb from .utils import pid_steer, pid_accl @@ -32,7 +32,7 @@ def from_string(model: str): else: raise ValueError(f"Unknown model type {model}") - def get_initial_state(self, pose=None, params: dict|None = None): + def get_initial_state(self, pose=None, params: dict | None = None): # Assert that if self is MB, params is not None if self == DynamicModel.MB and params is None: raise ValueError("MultiBody model requires parameters to be provided.") @@ -69,3 +69,18 @@ def f_dynamics(self): return vehicle_dynamics_mb else: raise ValueError(f"Unknown model type {self}") + + def get_standardized_state_fn(self): + """ + This function returns the standardized state information for the model. + This needs to be a function, because the state information is different for each model. + Slip is not directly available from the MB model. + """ + if self == DynamicModel.KS: + return get_standardized_state_ks + elif self == DynamicModel.ST: + return get_standardized_state_st + elif self == DynamicModel.MB: + return get_standardized_state_mb + else: + raise ValueError(f"Unknown model type {self}") diff --git a/f1tenth_gym/envs/dynamic_models/kinematic.py b/f1tenth_gym/envs/dynamic_models/kinematic.py index 95804a95..db4df61f 100644 --- a/f1tenth_gym/envs/dynamic_models/kinematic.py +++ b/f1tenth_gym/envs/dynamic_models/kinematic.py @@ -1,5 +1,6 @@ import numpy as np from numba import njit +from numba.typed import Dict from .utils import steering_constraint, accl_constraints @@ -171,3 +172,18 @@ def vehicle_dynamics_ks_cog(x: np.ndarray, u_init: np.ndarray, params: dict): ] return f + + +@njit(cache=True) +def get_standardized_state_ks(x: np.ndarray) -> dict: + """[X,Y,DELTA,V_X, V_Y,YAW,YAW_RATE,SLIP]""" + d = dict() + d["x"] = x[0] + d["y"] = x[1] + d["delta"] = x[2] + d["v_x"] = x[3] + d["v_y"] = 0.0 + d["yaw"] = x[4] + d["yaw_rate"] = x[5] + d["slip"] = 0.0 + return d diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/__init__.py b/f1tenth_gym/envs/dynamic_models/multi_body/__init__.py index c6ef9afa..40d6db10 100644 --- a/f1tenth_gym/envs/dynamic_models/multi_body/__init__.py +++ b/f1tenth_gym/envs/dynamic_models/multi_body/__init__.py @@ -5,7 +5,7 @@ import numpy as np from numba import njit -from .multi_body import vehicle_dynamics_mb +from .multi_body import vehicle_dynamics_mb, get_standardized_state_mb def init_mb(init_state, params: dict) -> np.ndarray: diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py index ea8bb377..dbe83fb9 100644 --- a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py +++ b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py @@ -1,5 +1,6 @@ import numpy as np from numba import njit +from numba.typed import Dict from f1tenth_gym.envs.dynamic_models.utils import steering_constraint, accl_constraints @@ -676,3 +677,18 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): f[28] = dot_delta_y_r return f + + +@njit(cache=True) +def get_standardized_state_mb(x: np.ndarray) -> dict: + """[X,Y,DELTA,V_X, V_Y,YAW,YAW_RATE,SLIP]""" + d = dict() + d["x"] = x[0] + d["y"] = x[1] + d["delta"] = x[2] + d["v_x"] = x[3] + d["v_y"] = x[10] + d["yaw"] = x[4] + d["yaw_rate"] = x[5] + d["slip"] = np.arctan2(x[10], x[3]) + return d diff --git a/f1tenth_gym/envs/dynamic_models/single_track.py b/f1tenth_gym/envs/dynamic_models/single_track.py index 8ce62d0e..522a57be 100644 --- a/f1tenth_gym/envs/dynamic_models/single_track.py +++ b/f1tenth_gym/envs/dynamic_models/single_track.py @@ -1,5 +1,6 @@ import numpy as np from numba import njit +from numba.typed import Dict from .utils import steering_constraint, accl_constraints @@ -150,3 +151,18 @@ def vehicle_dynamics_st(x: np.ndarray, u_init: np.ndarray, params: dict): ) return f + + +@njit(cache=True) +def get_standardized_state_st(x: np.ndarray) -> dict: + """[X,Y,DELTA,V_X, V_Y,YAW,YAW_RATE,SLIP]""" + d = dict() + d["x"] = x[0] + d["y"] = x[1] + d["delta"] = x[2] + d["v_x"] = x[3] * np.cos(x[6]) + d["v_y"] = x[3] * np.sin(x[6]) + d["yaw"] = x[4] + d["yaw_rate"] = x[5] + d["slip"] = x[6] + return d diff --git a/f1tenth_gym/envs/observation.py b/f1tenth_gym/envs/observation.py index c4031706..3b3c4929 100644 --- a/f1tenth_gym/envs/observation.py +++ b/f1tenth_gym/envs/observation.py @@ -124,11 +124,13 @@ def observe(self): lap_count = self.env.lap_counts[i] collision = self.env.sim.collisions[i] - x, y, theta = agent.state[xi], agent.state[yi], agent.state[yawi] - vx, vy = agent.state[vxi], 0.0 - angvel = ( - 0.0 if len(agent.state) < 7 else agent.state[yaw_ratei] - ) # set 0.0 when KST Model + std_state = agent.standard_state + + x, y, theta = std_state["x"], std_state["y"], std_state["yaw"] + + vx = std_state["v_x"] + vy = std_state["v_y"] + angvel = std_state["yaw_rate"] observations["scans"].append(agent_scan) observations["poses_x"].append(x) @@ -209,11 +211,6 @@ def space(self): return obs_space def observe(self): - # state indices - xi, yi, deltai, vxi, yawi, yaw_ratei, slipi = range( - 7 - ) # 7 largest state size (ST Model) - obs = {} # dictionary agent_id -> observation dict for i, agent_id in enumerate(self.env.agent_ids): @@ -222,17 +219,14 @@ def observe(self): lap_time = self.env.lap_times[i] lap_count = self.env.lap_counts[i] - x, y, theta = agent.state[xi], agent.state[yi], agent.state[yawi] - vlong = agent.state[vxi] - delta = agent.state[deltai] - beta = ( - 0.0 if len(agent.state) < 7 else agent.state[slipi] - ) # set 0.0 when KST Model - vx = vlong * np.cos(beta) - vy = vlong * np.sin(beta) - angvel = ( - 0.0 if len(agent.state) < 7 else agent.state[yaw_ratei] - ) # set 0.0 when KST Model + std_state = agent.standard_state + + x, y, theta = std_state["x"], std_state["y"], std_state["yaw"] + delta = std_state["delta"] + beta = std_state["slip"] + vx = std_state["v_x"] + vy = std_state["v_y"] + angvel = std_state["yaw_rate"] # create agent's observation dict agent_obs = { diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index ca2d6593..d0d6433e 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -193,42 +193,46 @@ def test_derivatives(self): f_ks = vehicle_dynamics_ks( x_ks, u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, + params={ + "mu": self.mu, + "C_Sf": self.C_Sf, + "C_Sr": self.C_Sr, + "lf": self.lf, + "lr": self.lr, + "h": self.h, + "m": self.m, + "I": self.I, + "s_min": self.s_min, + "s_max": self.s_max, + "sv_min": self.sv_min, + "sv_max": self.sv_max, + "v_switch": self.v_switch, + "a_max": self.a_max, + "v_min": self.v_min, + "v_max": self.v_max, + }, ) f_st = vehicle_dynamics_st( x_st, u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, + params={ + "mu": self.mu, + "C_Sf": self.C_Sf, + "C_Sr": self.C_Sr, + "lf": self.lf, + "lr": self.lr, + "h": self.h, + "m": self.m, + "I": self.I, + "s_min": self.s_min, + "s_max": self.s_max, + "sv_min": self.sv_min, + "sv_max": self.sv_max, + "v_switch": self.v_switch, + "a_max": self.a_max, + "v_min": self.v_min, + "v_max": self.v_max, + }, ) start = time.time() @@ -236,22 +240,24 @@ def test_derivatives(self): f_st = vehicle_dynamics_st( x_st, u, - self.mu, - self.C_Sf, - self.C_Sr, - self.lf, - self.lr, - self.h, - self.m, - self.I, - self.s_min, - self.s_max, - self.sv_min, - self.sv_max, - self.v_switch, - self.a_max, - self.v_min, - self.v_max, + params={ + "mu": self.mu, + "C_Sf": self.C_Sf, + "C_Sr": self.C_Sr, + "lf": self.lf, + "lr": self.lr, + "h": self.h, + "m": self.m, + "I": self.I, + "s_min": self.s_min, + "s_max": self.s_max, + "sv_min": self.sv_min, + "sv_max": self.sv_max, + "v_switch": self.v_switch, + "a_max": self.a_max, + "v_min": self.v_min, + "v_max": self.v_max, + }, ) duration = time.time() - start avg_fps = 10000 / duration From 78e394e82bcc6dd77ea604acb78e1f3d51b07a91 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Fri, 27 Sep 2024 20:15:37 -0400 Subject: [PATCH 45/55] Add scale to default_dict. Fix setting scale --- f1tenth_gym/envs/f110_env.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/f1tenth_gym/envs/f110_env.py b/f1tenth_gym/envs/f110_env.py index ba301e76..1ba02c37 100644 --- a/f1tenth_gym/envs/f110_env.py +++ b/f1tenth_gym/envs/f110_env.py @@ -143,14 +143,14 @@ def __init__(self, config: dict = None, render_mode=None, **kwargs): model=self.model, action_type=self.action_type, ) - self.sim.set_map(self.map, config["scale"]) + self.sim.set_map(self.map, self.config["scale"]) if isinstance(self.map, Track): self.track = self.map else: self.track = Track.from_track_name( self.map, - track_scale=config["scale"], + track_scale=self.config["scale"], ) # load track in gym env for convenience # observations @@ -357,6 +357,7 @@ def default_config(cls) -> dict: "control_input": ["speed", "steering_angle"], "observation_config": {"type": None}, "reset_config": {"type": None}, + "scale": 1.0, } def configure(self, config: dict) -> None: From 74435edf29f36299433c06c681f8b6ccb3ce76f8 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Fri, 27 Sep 2024 20:49:48 -0400 Subject: [PATCH 46/55] Qt rgb is rendering now returns rgb no alpha --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 1ea7a593..15bf2e6e 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -318,7 +318,7 @@ def render(self) -> Optional[np.ndarray]: ptr.setsize(height * width * 4) frame = np.array(ptr).reshape(height, width, 4) # Copies the data - return frame + return frame[:, :, :3] # remove alpha channel def render_points( self, From 33c9d3d60f9997adaf1eca72fd4b8d9ec54c4602 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Fri, 27 Sep 2024 21:22:45 -0400 Subject: [PATCH 47/55] Renders car and callbacks in rgb mode --- f1tenth_gym/envs/rendering/rendering_pyqt.py | 45 ++++++++++---------- 1 file changed, 22 insertions(+), 23 deletions(-) diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 15bf2e6e..1e14c4b6 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -272,34 +272,33 @@ def render(self) -> Optional[np.ndarray]: Optional[np.ndarray] if render_mode is "rgb_array", returns the rendered frame as an array """ - if self.draw_flag: - - # draw cars - for i in range(len(self.agent_ids)): - self.cars[i].render() + # draw cars + for i in range(len(self.agent_ids)): + self.cars[i].render() - # call callbacks - for callback_fn in self.callbacks: - callback_fn(self) + # call callbacks + for callback_fn in self.callbacks: + callback_fn(self) - if self.follow_agent_flag: - ego_x, ego_y = self.cars[self.agent_to_follow].pose[:2] - self.canvas.setXRange(ego_x - 10, ego_x + 10) - self.canvas.setYRange(ego_y - 10, ego_y + 10) - else: - self.canvas.autoRange() - - agent_to_follow_id = ( - self.agent_ids[self.agent_to_follow] - if self.agent_to_follow is not None - else None - ) - self.bottom_info_renderer.render( - text=f"Focus on: {agent_to_follow_id}" - ) + if self.follow_agent_flag: + ego_x, ego_y = self.cars[self.agent_to_follow].pose[:2] + self.canvas.setXRange(ego_x - 10, ego_x + 10) + self.canvas.setYRange(ego_y - 10, ego_y + 10) + else: + self.canvas.autoRange() + + agent_to_follow_id = ( + self.agent_ids[self.agent_to_follow] + if self.agent_to_follow is not None + else None + ) + self.bottom_info_renderer.render( + text=f"Focus on: {agent_to_follow_id}" + ) if self.render_spec.show_info: self.top_info_renderer.render(text=INSTRUCTION_TEXT) + self.time_renderer.render(text=f"{self.sim_time:.2f}") self.clock.update() self.app.processEvents() From 339a5b804003a1c8b5832f6f1d7695f056ffe0df Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 30 Sep 2024 18:55:08 -0400 Subject: [PATCH 48/55] Update ci to install qt dependencies and make qt headless --- .github/workflows/ci.yml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 7f33e43d..c6bad22d 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -20,7 +20,10 @@ jobs: steps: - name: Install openGL - run: sudo apt install freeglut3-dev + run: sudo apt install freeglut3-dev libglib2.0-0 libsm6 libxrender1 libxext6 libxkbcommon-x11-0 libdbus-1-dev + + - name: Set QT to be headless + run: export QT_QPA_PLATFORM=offscreen - uses: actions/checkout@v2 From 1dfd64890a1e577a1f20673e5280eb45bbc0eaf4 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Mon, 30 Sep 2024 23:38:11 -0400 Subject: [PATCH 49/55] Replace export in CI with variables --- .github/workflows/ci.yml | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index c6bad22d..1f661d03 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -11,6 +11,8 @@ permissions: jobs: build: + variables: + QT_QPA_PLATFORM: "offscreen" runs-on: ubuntu-latest strategy: @@ -22,9 +24,6 @@ jobs: - name: Install openGL run: sudo apt install freeglut3-dev libglib2.0-0 libsm6 libxrender1 libxext6 libxkbcommon-x11-0 libdbus-1-dev - - name: Set QT to be headless - run: export QT_QPA_PLATFORM=offscreen - - uses: actions/checkout@v2 - name: Set up Python ${{ matrix.python-version }} From cb7455bb3c5b7024b2613218813252e3f29e0387 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 1 Oct 2024 00:21:02 -0400 Subject: [PATCH 50/55] Switch to env in ci --- .github/workflows/ci.yml | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 1f661d03..72a9dcfa 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -11,14 +11,13 @@ permissions: jobs: build: - variables: - QT_QPA_PLATFORM: "offscreen" - runs-on: ubuntu-latest strategy: fail-fast: false matrix: python-version: ["3.9", "3.10", "3.11", "3.12"] + env: + QT_QPA_PLATFORM: offscreen steps: - name: Install openGL From 75e62f192bc984f5fcc450809bd16e055690a460 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Tue, 1 Oct 2024 14:16:48 -0400 Subject: [PATCH 51/55] Instantiate QApp for rgb_array_list test --- .github/workflows/ci.yml | 5 ++++- f1tenth_gym/envs/rendering/rendering_pyqt.py | 3 ++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 72a9dcfa..e73f6915 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -20,8 +20,11 @@ jobs: QT_QPA_PLATFORM: offscreen steps: + - name: Update apt + run: sudo apt update + - name: Install openGL - run: sudo apt install freeglut3-dev libglib2.0-0 libsm6 libxrender1 libxext6 libxkbcommon-x11-0 libdbus-1-dev + run: sudo apt install -y freeglut3-dev libglib2.0-0 libsm6 libxrender1 libxext6 libxkbcommon-x11-0 libdbus-1-dev - uses: actions/checkout@v2 diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 1e14c4b6..363e9e78 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -69,7 +69,7 @@ def __init__( self.render_fps = render_fps # create the canvas - self.app = QtWidgets.QApplication([]) + self.app = QtWidgets.QApplication.instance() or QtWidgets.QApplication([]) self.window = pg.GraphicsLayoutWidget() self.window.setWindowTitle("F1Tenth Gym") self.window.setGeometry(0, 0, self.render_spec.window_size, self.render_spec.window_size) @@ -399,3 +399,4 @@ def close(self) -> None: Close the rendering environment. """ self.app.exit() + From de442706986bf796bd5e8ff013df8f0057df9dc8 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Fri, 27 Sep 2024 15:35:42 -0400 Subject: [PATCH 52/55] Update dynamics to use arctan. Update tests to use func_KS, func_ST --- f1tenth_gym/envs/dynamic_models/kinematic.py | 2 +- .../envs/dynamic_models/multi_body/multi_body.py | 10 +++++----- tests/test_dynamics.py | 9 ++++++--- 3 files changed, 12 insertions(+), 9 deletions(-) diff --git a/f1tenth_gym/envs/dynamic_models/kinematic.py b/f1tenth_gym/envs/dynamic_models/kinematic.py index db4df61f..cdd6a468 100644 --- a/f1tenth_gym/envs/dynamic_models/kinematic.py +++ b/f1tenth_gym/envs/dynamic_models/kinematic.py @@ -160,7 +160,7 @@ def vehicle_dynamics_ks_cog(x: np.ndarray, u_init: np.ndarray, params: dict): ] ) # slip angle (beta) from vehicle kinematics - beta = np.atan(np.tan(x[2]) * params["lr"] / lwb) + beta = np.arctan(np.tan(x[2]) * params["lr"] / lwb) # system dynamics f = [ diff --git a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py index dbe83fb9..bcdafdaf 100644 --- a/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py +++ b/f1tenth_gym/envs/dynamic_models/multi_body/multi_body.py @@ -183,7 +183,7 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): if abs(x[3]) < KIN_THRESH: beta = 0.0 else: - beta = np.atan(x[10] / x[3]) + beta = np.arctan(x[10] / x[3]) vel = np.sqrt(x[3] ** 2 + x[10] ** 2) # vertical tire forces @@ -252,24 +252,24 @@ def vehicle_dynamics_mb(x: np.ndarray, u_init: np.ndarray, params: dict): alpha_RR = 0.0 else: alpha_LF = ( - np.atan( + np.arctan( (x[10] + params["lf"] * x[5] - x[14] * (params["R_w"] - x[16])) / (x[3] + 0.5 * params["T_f"] * x[5]) ) - x[2] ) alpha_RF = ( - np.atan( + np.arctan( (x[10] + params["lf"] * x[5] - x[14] * (params["R_w"] - x[16])) / (x[3] - 0.5 * params["T_f"] * x[5]) ) - x[2] ) - alpha_LR = np.atan( + alpha_LR = np.arctan( (x[10] - params["lr"] * x[5] - x[19] * (params["R_w"] - x[21])) / (x[3] + 0.5 * params["T_r"] * x[5]) ) - alpha_RR = np.atan( + alpha_RR = np.arctan( (x[10] - params["lr"] * x[5] - x[19] * (params["R_w"] - x[21])) / (x[3] - 0.5 * params["T_r"] * x[5]) ) diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index d0d6433e..3e60f522 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -190,8 +190,9 @@ def test_derivatives(self): acc = 0.63 * g u = np.array([v_delta, acc]) - f_ks = vehicle_dynamics_ks( + f_ks = func_KS( x_ks, + 0, u, params={ "mu": self.mu, @@ -212,8 +213,9 @@ def test_derivatives(self): "v_max": self.v_max, }, ) - f_st = vehicle_dynamics_st( + f_st = func_ST( x_st, + 0, u, params={ "mu": self.mu, @@ -237,8 +239,9 @@ def test_derivatives(self): start = time.time() for i in range(10000): - f_st = vehicle_dynamics_st( + f_st = func_ST( x_st, + 0, u, params={ "mu": self.mu, From dfe00de9e24df205d129850bd4b6b2eed4fc8698 Mon Sep 17 00:00:00 2001 From: Ahmad Amine Date: Wed, 2 Oct 2024 14:46:43 -0400 Subject: [PATCH 53/55] Fix test to correct calls of func_KS/ST --- tests/test_dynamics.py | 102 +++++++++++++++++++---------------------- 1 file changed, 48 insertions(+), 54 deletions(-) diff --git a/tests/test_dynamics.py b/tests/test_dynamics.py index 3e60f522..9c30707c 100644 --- a/tests/test_dynamics.py +++ b/tests/test_dynamics.py @@ -194,47 +194,43 @@ def test_derivatives(self): x_ks, 0, u, - params={ - "mu": self.mu, - "C_Sf": self.C_Sf, - "C_Sr": self.C_Sr, - "lf": self.lf, - "lr": self.lr, - "h": self.h, - "m": self.m, - "I": self.I, - "s_min": self.s_min, - "s_max": self.s_max, - "sv_min": self.sv_min, - "sv_max": self.sv_max, - "v_switch": self.v_switch, - "a_max": self.a_max, - "v_min": self.v_min, - "v_max": self.v_max, - }, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, ) f_st = func_ST( x_st, 0, u, - params={ - "mu": self.mu, - "C_Sf": self.C_Sf, - "C_Sr": self.C_Sr, - "lf": self.lf, - "lr": self.lr, - "h": self.h, - "m": self.m, - "I": self.I, - "s_min": self.s_min, - "s_max": self.s_max, - "sv_min": self.sv_min, - "sv_max": self.sv_max, - "v_switch": self.v_switch, - "a_max": self.a_max, - "v_min": self.v_min, - "v_max": self.v_max, - }, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, ) start = time.time() @@ -243,24 +239,22 @@ def test_derivatives(self): x_st, 0, u, - params={ - "mu": self.mu, - "C_Sf": self.C_Sf, - "C_Sr": self.C_Sr, - "lf": self.lf, - "lr": self.lr, - "h": self.h, - "m": self.m, - "I": self.I, - "s_min": self.s_min, - "s_max": self.s_max, - "sv_min": self.sv_min, - "sv_max": self.sv_max, - "v_switch": self.v_switch, - "a_max": self.a_max, - "v_min": self.v_min, - "v_max": self.v_max, - }, + self.mu, + self.C_Sf, + self.C_Sr, + self.lf, + self.lr, + self.h, + self.m, + self.I, + self.s_min, + self.s_max, + self.sv_min, + self.sv_max, + self.v_switch, + self.a_max, + self.v_min, + self.v_max, ) duration = time.time() - start avg_fps = 10000 / duration From 67d72cf10c35842392d23161ee4b50131d595d28 Mon Sep 17 00:00:00 2001 From: Nandan Tumu Date: Wed, 2 Oct 2024 19:48:52 +0000 Subject: [PATCH 54/55] Set environment variable --- .github/workflows/ci.yml | 4 ++-- f1tenth_gym/envs/rendering/rendering_pyqt.py | 2 ++ 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index e73f6915..1728df58 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -16,8 +16,8 @@ jobs: fail-fast: false matrix: python-version: ["3.9", "3.10", "3.11", "3.12"] - env: - QT_QPA_PLATFORM: offscreen + # env: + # QT_QPA_PLATFORM: offscreen steps: - name: Update apt diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index ecd2469e..900a5a3f 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -3,6 +3,7 @@ import math from typing import Any, Callable, Optional import signal +import os import cv2 import numpy as np @@ -164,6 +165,7 @@ def __init__( signal.signal(signal.SIGINT, signal.SIG_DFL) self.window.show() elif self.render_mode == "rgb_array": + os.environ["QT_QPA_PLATFORM"] = "offscreen" self.exporter = ImageExporter(self.canvas) def update(self, state: dict) -> None: From 967e1aaa927da485694c6878138efc7bb8eafed6 Mon Sep 17 00:00:00 2001 From: Nandan Tumu Date: Wed, 2 Oct 2024 20:29:31 +0000 Subject: [PATCH 55/55] Fixing last commit --- f1tenth_gym/envs/rendering/__init__.py | 2 ++ f1tenth_gym/envs/rendering/rendering_pyqt.py | 2 -- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/f1tenth_gym/envs/rendering/__init__.py b/f1tenth_gym/envs/rendering/__init__.py index bcfa6bfb..0e52410f 100644 --- a/f1tenth_gym/envs/rendering/__init__.py +++ b/f1tenth_gym/envs/rendering/__init__.py @@ -1,4 +1,5 @@ import pathlib +import os from typing import Any, Optional from .renderer import RenderSpec, EnvRenderer @@ -34,6 +35,7 @@ def make_renderer( if render_spec.render_type == "pygame": from .rendering_pygame import PygameEnvRenderer as EnvRenderer elif render_spec.render_type == "pyqt6": + os.environ["QT_QPA_PLATFORM"] = "offscreen" from .rendering_pyqt import PyQtEnvRenderer as EnvRenderer else: raise ValueError(f"Unknown render type: {render_spec.render_type}") diff --git a/f1tenth_gym/envs/rendering/rendering_pyqt.py b/f1tenth_gym/envs/rendering/rendering_pyqt.py index 900a5a3f..ecd2469e 100644 --- a/f1tenth_gym/envs/rendering/rendering_pyqt.py +++ b/f1tenth_gym/envs/rendering/rendering_pyqt.py @@ -3,7 +3,6 @@ import math from typing import Any, Callable, Optional import signal -import os import cv2 import numpy as np @@ -165,7 +164,6 @@ def __init__( signal.signal(signal.SIGINT, signal.SIG_DFL) self.window.show() elif self.render_mode == "rgb_array": - os.environ["QT_QPA_PLATFORM"] = "offscreen" self.exporter = ImageExporter(self.canvas) def update(self, state: dict) -> None: