From f6bf9bff469d272bcf11f75ea21ece3807e48ad9 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Fri, 24 Mar 2023 10:06:15 +0100 Subject: [PATCH 01/26] updates to exp function from real world testing --- mppiisaac/planner/mppi.py | 25 ++++++++++++++++++++----- 1 file changed, 20 insertions(+), 5 deletions(-) diff --git a/mppiisaac/planner/mppi.py b/mppiisaac/planner/mppi.py index 50c1f12..d708f51 100644 --- a/mppiisaac/planner/mppi.py +++ b/mppiisaac/planner/mppi.py @@ -180,11 +180,11 @@ def __init__(self, cfg: MPPIConfig, nx: int, dynamics: Callable, running_cost: C self.noise_sigma = self.noise_sigma.view(-1, 1) # Halton sampling - self.knot_scale = 4 # From mppi config storm + self.knot_scale = 1 # From mppi config storm self.seed_val = 0 # From mppi config storm self.n_knots = self.T//self.knot_scale self.ndims = self.n_knots * self.nu - self.degree = 2 # From sample_lib storm + self.degree = 1 # From sample_lib storm self.Z_seq = torch.zeros(1, self.T, self.nu, **self.tensor_args) self.cov_action = torch.diagonal(self.noise_sigma, 0) self.scale_tril = torch.sqrt(self.cov_action) @@ -226,9 +226,24 @@ def _exp_util(self, costs, actions): traj_costs = traj_costs[:,0] #control_costs = self._control_costs(actions) - total_costs = traj_costs #+ self.beta * control_costs - - w = torch.softmax((-1.0/self.beta) * total_costs, dim=0) + total_costs = traj_costs - torch.min(traj_costs) #+ self.beta * control_costs + + # Normalization of the weights + exp_ = torch.exp((-1.0/self.beta) * total_costs) + eta = torch.sum(exp_) # tells how many significant samples we have, more or less + w = 1/eta*exp_ + # print(self.beta) + eta_u_bound = 50 + eta_l_bound = 20 + beta_lm = 0.9 + beta_um = 1.2 + # beta update + if eta > eta_u_bound: + self.beta = self.beta*beta_lm + elif eta < eta_l_bound: + self.beta = self.beta*beta_um + + #w = torch.softmax((-1.0/self.beta) * total_costs, dim=0) self.total_costs = total_costs return w From b661e68ef4f6daf3b78fb74b9af19158a2f09dd8 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 27 Mar 2023 09:41:14 +0200 Subject: [PATCH 02/26] ft[Add example isaacgym]: Support for isaacgym as simulator --- .../robots/franka_panda_stick.urdf | 202 ++++++++++++++++++ conf/config_panda_push.yaml | 13 ++ conf/mppi/panda_push.yaml | 23 ++ examples/panda_isaacgym_client.py | 72 +++++++ examples/panda_isaacgym_server.py | 76 +++++++ examples/panda_push_client.py | 146 +++++++++++++ examples/panda_push_server.py | 114 ++++++++++ mppiisaac/planner/isaacgym_wrapper.py | 27 ++- mppiisaac/planner/mppi_isaac.py | 40 +++- mppiisaac/utils/config_store.py | 1 + 10 files changed, 706 insertions(+), 8 deletions(-) create mode 100644 assets/urdf/panda_isaac/robots/franka_panda_stick.urdf create mode 100644 conf/config_panda_push.yaml create mode 100644 conf/mppi/panda_push.yaml create mode 100644 examples/panda_isaacgym_client.py create mode 100644 examples/panda_isaacgym_server.py create mode 100644 examples/panda_push_client.py create mode 100644 examples/panda_push_server.py diff --git a/assets/urdf/panda_isaac/robots/franka_panda_stick.urdf b/assets/urdf/panda_isaac/robots/franka_panda_stick.urdf new file mode 100644 index 0000000..99bacf0 --- /dev/null +++ b/assets/urdf/panda_isaac/robots/franka_panda_stick.urdf @@ -0,0 +1,202 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/conf/config_panda_push.yaml b/conf/config_panda_push.yaml new file mode 100644 index 0000000..f921701 --- /dev/null +++ b/conf/config_panda_push.yaml @@ -0,0 +1,13 @@ +defaults: + - mppi: panda_push + - isaacgym: slow + +goal: [0.5, 0.4, 0.7] +render: true +n_steps: 10000 +urdf_file: "panda_isaac/robots/franka_panda_stick.urdf" +ee_link: "panda_link7" +fix_base: true +flip_visual: true +disable_gravity: true +nx: 14 diff --git a/conf/mppi/panda_push.yaml b/conf/mppi/panda_push.yaml new file mode 100644 index 0000000..73470a9 --- /dev/null +++ b/conf/mppi/panda_push.yaml @@ -0,0 +1,23 @@ +defaults: + - base_mppi + +mppi_mode: "halton-spline" # halton-spline, simple +sampling_method: "halton" # halton, random +num_samples: 400 +horizon: 20 # At least 12 for Halton Sampling +device: "cuda:0" +u_min: [-0.2] +u_max: [0.2] +lambda_: 0.05 +noise_sigma: [[0.1, 0., 0., 0., 0., 0., 0.], + [0., 0.1, 0., 0., 0., 0., 0.], + [0., 0., 0.1, 0., 0., 0., 0.], + [0., 0., 0., 0.1, 0., 0., 0.], + [0., 0., 0., 0., 0.1, 0., 0.], + [0., 0., 0., 0., 0., 0.1, 0.], + [0., 0., 0., 0., 0., 0., 0.1]] +rollout_var_discount: 0.95 +update_cov: False +sample_null_action: True +filter_u: False +use_priors: False diff --git a/examples/panda_isaacgym_client.py b/examples/panda_isaacgym_client.py new file mode 100644 index 0000000..d8bf9c1 --- /dev/null +++ b/examples/panda_isaacgym_client.py @@ -0,0 +1,72 @@ + +import gym +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +from urdfenvs.robots.generic_urdf import GenericUrdfReacher +import hydra +from omegaconf import OmegaConf +import os +import torch +from mppiisaac.priors.fabrics_panda import FabricsPandaPrior +import zerorpc + +from mppiisaac.utils.config_store import ExampleConfig + +class JointSpaceGoalObjective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + + def compute_cost(self, sim): + pos = torch.cat( + ( + sim.dof_state[:, 0].unsqueeze(1), + sim.dof_state[:, 2].unsqueeze(1), + sim.dof_state[:, 4].unsqueeze(1), + sim.dof_state[:, 6].unsqueeze(1), + sim.dof_state[:, 8].unsqueeze(1), + sim.dof_state[:, 10].unsqueeze(1), + sim.dof_state[:, 12].unsqueeze(1), + ), + 1, + ) + # dof_states = gym.acquire_dof_state_tensor(sim) + return torch.clamp( + torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 + ) + + +class EndEffectorGoalObjective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + self.ort_goal = torch.tensor([1, 0, 0, 0], device=cfg.mppi.device) + + def compute_cost(self, sim): + pos = sim.rigid_body_state[:, sim.robot_rigid_body_ee_idx, :3] + ort = sim.rigid_body_state[:, sim.robot_rigid_body_ee_idx, 3:7] + # dof_states = gym.acquire_dof_state_tensor(sim) + + reach_cost = torch.linalg.norm(pos - self.nav_goal, axis=1) + align_cost = torch.linalg.norm(ort - self.ort_goal, axis=1) + return 10 * reach_cost + align_cost + # return torch.clamp( + # torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 + # ) + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_panda") +def run_panda_robot(cfg: ExampleConfig): + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + objective = EndEffectorGoalObjective(cfg, cfg.mppi.device) + # objective = JointSpaceGoalObjective(cfg, cfg.mppi.device) + if cfg.mppi.use_priors == True: + prior = FabricsPandaPrior(cfg) + else: + prior = None + planner = zerorpc.Server(MPPIisaacPlanner(cfg, objective, prior)) + planner.bind("tcp://0.0.0.0:4242") + planner.run() + +if __name__ == "__main__": + run_panda_robot() diff --git a/examples/panda_isaacgym_server.py b/examples/panda_isaacgym_server.py new file mode 100644 index 0000000..45c3171 --- /dev/null +++ b/examples/panda_isaacgym_server.py @@ -0,0 +1,76 @@ +import gym +from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +from urdfenvs.robots.generic_urdf import GenericUrdfReacher +import hydra +from omegaconf import OmegaConf +import os +import torch +from mppiisaac.priors.fabrics_panda import FabricsPandaPrior +import zerorpc +from mppiisaac.utils.config_store import ExampleConfig +from isaacgym import gymapi + +import io + +def torch_to_bytes(t: torch.Tensor) -> bytes: + buff = io.BytesIO() + torch.save(t, buff) + buff.seek(0) + return buff.read() + + +def bytes_to_torch(b: bytes) -> torch.Tensor: + buff = io.BytesIO(b) + return torch.load(buff) + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_panda") +def run_panda_robot(cfg: ExampleConfig): + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + sim = IsaacGymWrapper( + cfg.isaacgym, + cfg.urdf_file, + cfg.fix_base, + cfg.flip_visual, + num_envs=1, + ee_link=cfg.ee_link, + disable_gravity=cfg.disable_gravity, + viewer=True, + ) + + sim.gym.viewer_camera_look_at( + sim.viewer, None, gymapi.Vec3(1.5, 2, 3), gymapi.Vec3(1.5, 0, 0) + ) + + planner = zerorpc.Client() + planner.connect("tcp://127.0.0.1:4242") + print("Mppi server found!") + + pi = 3.14 + sim.set_dof_state_tensor(torch.tensor([0, 0, 0, 0, 0, 0, -pi/2, 0, 0, 0, pi/2, 0, pi/4, 0], device="cuda:0")) + + for _ in range(cfg.n_steps): + # Reset state + planner.reset_rollout_sim( + torch_to_bytes(sim.dof_state[0]), + torch_to_bytes(sim.root_state[0]), + torch_to_bytes(sim.rigid_body_state[0]), + ) + + # Compute action + action = bytes_to_torch(planner.command()) + + # Apply action + sim.set_dof_velocity_target_tensor(action) + + # Step simulator + sim.step() + return {} + + +if __name__ == "__main__": + res = run_panda_robot() diff --git a/examples/panda_push_client.py b/examples/panda_push_client.py new file mode 100644 index 0000000..bf2984b --- /dev/null +++ b/examples/panda_push_client.py @@ -0,0 +1,146 @@ + +import gym +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +from urdfenvs.robots.generic_urdf import GenericUrdfReacher +import hydra +from omegaconf import OmegaConf +import os +import torch +from mppiisaac.priors.fabrics_panda import FabricsPandaPrior +import zerorpc +import pytorch3d.transforms + +from mppiisaac.utils.config_store import ExampleConfig + +class Objective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + self.block_goal = torch.tensor([0.5, 0, 0.138], device=cfg.mppi.device) + self.ort_goal = torch.tensor([1, 0, 0, 0], device=cfg.mppi.device) + self.ort_goal_euler = torch.tensor([0, 0, 0], device=cfg.mppi.device) + #self.block_goal_ort = torch.tensor([-0.5, 0.5, -0.5, 0.5], device=cfg.mppi.device) + self.block_goal_ort = torch.tensor([0, 0, 0, 1.0], device=cfg.mppi.device) + self.block_goal_ort = torch.tensor([0, 0, 0.7071068, 0.7071068], device=cfg.mppi.device) + + self.w_robot_to_block_pos= 10#0.2 + self.w_block_to_goal_pos= 100#2.0 + self.w_block_to_goal_ort= 10#0.2 + self.w_ee_hover= 60#5 + self.w_ee_align= 0#1 + self.w_ee_contact= 0.1#0.02 + self.w_push_align= 5#1 + self.ee_hover_height= 0.14#0.14 + + def orientation_error(self, q1, q2_batch): + """ + Computes the orientation error between a single quaternion and a batch of quaternions. + + Parameters: + ----------- + q1 : torch.Tensor + A tensor of shape (4,) representing the first quaternion. + q2_batch : torch.Tensor + An tensor of shape (batch_size, 4) representing the second set of quaternions. + + Returns: + -------- + error_batch : torch.Tensor + An tensor of shape (batch_size,) containing the orientation error between the first quaternion and each quaternion in the batch. + """ + + # Expand the first quaternion to match the batch size of the second quaternion + q1_batch = q1.expand(q2_batch.shape[0], -1) + + # Normalize the quaternions + q1_batch = q1_batch / torch.norm(q1_batch, dim=1, keepdim=True) + q2_batch = q2_batch / torch.norm(q2_batch, dim=1, keepdim=True) + + # Compute the dot product between the quaternions in the batch + dot_product_batch = torch.sum(q1_batch * q2_batch, dim=1) + + # Compute the angle between the quaternions in the batch + # chatgpt + #angle_batch = 2 * torch.acos(torch.abs(dot_product_batch)) + # method2 + angle_batch = torch.acos(2*torch.square(dot_product_batch)-1) + # method 3 + # angle_batch = 1 - torch.square(dot_product_batch) + # Return the orientation error for each quaternion in the batch + error_batch = angle_batch + + return error_batch + + def compute_cost(self, sim): + ee_index = 11 + block_index = 4 + r_pos = sim.rigid_body_state[:, ee_index, :3] + r_ort = sim.rigid_body_state[:, ee_index, 3:7] + ee_height = r_pos[:, 2] + block_pos = sim.root_state[:, block_index, :3] + block_ort = sim.root_state[:, block_index, 3:7] + robot_to_block = r_pos - block_pos + block_to_goal = self.block_goal[0:2] - block_pos[:, 0:2] + + block_yaws = pytorch3d.transforms.matrix_to_euler_angles(pytorch3d.transforms.quaternion_to_matrix(block_ort), "ZYX")[:, -1] + robot_euler = pytorch3d.transforms.matrix_to_euler_angles(pytorch3d.transforms.quaternion_to_matrix(r_ort), "ZYX") + + # Costs + robot_to_block_cost = torch.linalg.norm(robot_to_block[:, 0:2], axis=1) + block_to_goal_pos_cost = torch.linalg.norm(block_to_goal, axis=1) + block_to_goal_ort_cost = self.orientation_error(self.block_goal_ort, block_ort) + ee_hover_cost = torch.abs(ee_height - self.ee_hover_height) + push_align_cost = torch.sum(robot_to_block[:, 0:2] * block_to_goal, 1) / ( + robot_to_block_cost * block_to_goal_pos_cost + ) + #ee_align_cost = torch.linalg.norm(r_ort - self.ort_goal, axis=1) + #ee_align_cost = torch.pow(block_yaws, 2) + ee_align_cost = torch.linalg.norm(robot_euler - self.ort_goal_euler, axis=1) + + # minimize contact + # Only z component should be added here + net_cf = torch.sum( + torch.abs( + torch.cat( + ( + sim.net_cf[:, 0].unsqueeze(1), + sim.net_cf[:, 1].unsqueeze(1), + sim.net_cf[:, 2].unsqueeze(1), + ), + 1, + ) + ), + 1, + ) + contact_cost = torch.abs( + net_cf.reshape([block_pos.size()[0], -1])[:, block_index] + ) + + total_cost = ( + self.w_robot_to_block_pos * robot_to_block_cost + + self.w_block_to_goal_pos * block_to_goal_pos_cost + + self.w_block_to_goal_ort * block_to_goal_ort_cost + + self.w_ee_hover * ee_hover_cost + + self.w_ee_align * ee_align_cost + + self.w_ee_contact * contact_cost + + self.w_push_align * push_align_cost + ) + + return total_cost + +@hydra.main(version_base=None, config_path="../conf", config_name="config_panda_push") +def run_panda_robot(cfg: ExampleConfig): + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + objective = Objective(cfg, cfg.mppi.device) + if cfg.mppi.use_priors == True: + prior = FabricsPandaPrior(cfg) + else: + prior = None + planner = zerorpc.Server(MPPIisaacPlanner(cfg, objective, prior)) + planner.bind("tcp://0.0.0.0:4242") + planner.run() + +if __name__ == "__main__": + run_panda_robot() diff --git a/examples/panda_push_server.py b/examples/panda_push_server.py new file mode 100644 index 0000000..09df603 --- /dev/null +++ b/examples/panda_push_server.py @@ -0,0 +1,114 @@ +import gym +from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +from urdfenvs.robots.generic_urdf import GenericUrdfReacher +import hydra +from omegaconf import OmegaConf +import os +import torch +from mppiisaac.priors.fabrics_panda import FabricsPandaPrior +import zerorpc +from mppiisaac.utils.config_store import ExampleConfig +from isaacgym import gymapi +import time + +import io + +def torch_to_bytes(t: torch.Tensor) -> bytes: + buff = io.BytesIO() + torch.save(t, buff) + buff.seek(0) + return buff.read() + + +def bytes_to_torch(b: bytes) -> torch.Tensor: + buff = io.BytesIO(b) + return torch.load(buff) + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_panda_push") +def run_panda_robot(cfg: ExampleConfig): + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + cfg.isaacgym.dt=0.05 + + sim = IsaacGymWrapper( + cfg.isaacgym, + cfg.urdf_file, + cfg.fix_base, + cfg.flip_visual, + num_envs=1, + ee_link=cfg.ee_link, + disable_gravity=cfg.disable_gravity, + viewer=True, + ) + + # Manually add table + block and restart isaacgym + additions = [ + { + "type": "box", + "name": "table", + "size": [0.5, 1.0, 0.112], + "init_pos": [0.5, 0, 0.112 / 2], + "fixed": True, + "handle": None, + }, + { + "type": "box", + "name": "block", + "size": [0.105, 0.063, 0.063], + "init_pos": [0.55, 0.2, 0.3], + "mass": 0.250, + "fixed": False, + "handle": None, + "color": [0.2, 0.2, 1.0] + } + ] + for a in additions: + sim.env_cfg.append(a) + sim.stop_sim() + sim.start_sim() + + sim.gym.viewer_camera_look_at( + sim.viewer, None, gymapi.Vec3(1.5, 2, 3), gymapi.Vec3(1.5, 0, 0) + ) + + planner = zerorpc.Client() + planner.connect("tcp://127.0.0.1:4242") + print("Mppi server found!") + + planner.add_to_env(additions) + + pi = 3.14 + sim.set_dof_state_tensor(torch.tensor([0, 0, 0, 0, 0, 0, -pi/2, 0, 0, 0, pi/2, 0, pi/4, 0], device="cuda:0")) + + for _ in range(cfg.n_steps): + t = time.time() + # Reset state + planner.reset_rollout_sim( + torch_to_bytes(sim.dof_state[0]), + torch_to_bytes(sim.root_state[0]), + torch_to_bytes(sim.rigid_body_state[0]), + ) + + # Compute action + action = bytes_to_torch(planner.command()) + if torch.any(torch.isnan(action)): + action = torch.zeros_like(action) + + # Apply action + sim.set_dof_velocity_target_tensor(action) + + # Step simulator + sim.step() + + # Print error of block + pos = sim.root_state[0, -1][:2].cpu().numpy() + goal = np.array([0.5, 0]) + print(f"L2: {np.linalg.norm(pos - goal)} FPS: {1/(time.time() - t)}") + return {} + + +if __name__ == "__main__": + res = run_panda_robot() diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 0bbd2e5..735b266 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -50,7 +50,8 @@ def __init__( flip_visual: bool, num_envs: int = 0, ee_link: str = None, - disable_gravity: bool = False + disable_gravity: bool = False, + viewer: bool = False ): self.gym = gymapi.acquire_gym() @@ -61,6 +62,7 @@ def __init__( {"type": "robot", "name": "main_robot", "handle": None}, ] self.cfg = cfg + if viewer: self.cfg.viewer = viewer self.num_envs = num_envs self._urdf_file = urdf_file self._fix_base = fix_base @@ -92,7 +94,7 @@ def start_sim(self): asset_root=f"{file_path}/../../assets", fix_base_link=self._fix_base, flip_visual_attachments=self._flip_visual, - disable_gravity=self._disable_gravity + disable_gravity=self._disable_gravity, ) self.envs = [self.create_env(i) for i in range(self.num_envs)] @@ -182,6 +184,11 @@ def create_env(self, env_idx): self.gym.set_actor_dof_properties(env, robot_handle, props) for obst_cfg in self.env_cfg[3:]: + if "init_pos" in obst_cfg.keys(): + init_pos = gymapi.Vec3(*obst_cfg["init_pos"]) + else: + init_pos=gymapi.Vec3(0, 0, -20) + if obst_cfg["type"] == "sphere": # add spheres handle = self.add_sphere( @@ -189,19 +196,28 @@ def create_env(self, env_idx): env_idx=env_idx, name=obst_cfg["name"], radius=obst_cfg["size"][0], - pos=gymapi.Vec3(0, 0, -20), + pos=init_pos, color=gymapi.Vec3(1.0, 1.0, 1.0), ) elif obst_cfg["type"] == "box": # add spheres + if "mass" in obst_cfg.keys(): + mass = obst_cfg['mass'] + else: + mass = 1.0 + if "mass" in obst_cfg.keys(): + color = gymapi.Vec3(*obst_cfg['color']) + else: + color = gymapi.Vec3(1.0, 1.0, 1.0) handle = self.add_box( env=env, env_idx=env_idx, name=obst_cfg["name"], whd=obst_cfg["size"], - pos=gymapi.Vec3(0, 0, -20), - color=gymapi.Vec3(1.0, 1.0, 1.0), + pos=init_pos, + color=color, fixed=obst_cfg["fixed"], + mass=mass ) else: raise NotImplementedError( @@ -403,6 +419,7 @@ def update_root_state_tensor_by_obstacles(self, obstacles): def update_root_state_tensor_by_obstacles_tensor(self, obst_tensor): for i, o_tensor in enumerate(obst_tensor): + if self.env_cfg[i + 3]['fixed']: continue self.root_state[:, i + 3] = o_tensor.repeat(self.num_envs, 1) self.gym.set_actor_root_state_tensor( diff --git a/mppiisaac/planner/mppi_isaac.py b/mppiisaac/planner/mppi_isaac.py index 8ec2ced..c138604 100644 --- a/mppiisaac/planner/mppi_isaac.py +++ b/mppiisaac/planner/mppi_isaac.py @@ -1,12 +1,26 @@ from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper from mppiisaac.planner.mppi import MPPIPlanner from typing import Callable, Optional +import io +from isaacgym import gymtorch import torch torch.set_printoptions(precision=2, sci_mode=False) +def torch_to_bytes(t: torch.Tensor) -> bytes: + buff = io.BytesIO() + torch.save(t, buff) + buff.seek(0) + return buff.read() + + +def bytes_to_torch(b: bytes) -> torch.Tensor: + buff = io.BytesIO(b) + return torch.load(buff) + + class MPPIisaacPlanner(object): """ Wrapper class that inherits from the MPPIPlanner and implements the required functions: @@ -24,11 +38,11 @@ def __init__(self, cfg, objective: Callable, prior: Optional[Callable] = None): cfg.flip_visual, num_envs=cfg.mppi.num_samples, ee_link=cfg.ee_link, - disable_gravity=cfg.disable_gravity + disable_gravity=cfg.disable_gravity, ) if prior: - self.prior = lambda state, t : prior.compute_command(self.sim) + self.prior = lambda state, t: prior.compute_command(self.sim) else: self.prior = None @@ -40,7 +54,6 @@ def __init__(self, cfg, objective: Callable, prior: Optional[Callable] = None): prior=self.prior, ) - # Note: place_holder variable to pass to mppi so it doesn't complain, while the real state is actually the isaacgym simulator itself. self.state_place_holder = torch.zeros((self.cfg.mppi.num_samples, self.cfg.nx)) @@ -131,3 +144,24 @@ def compute_action(self, q, qdot, obst=None, obst_tensor=None): self.sim.save_root_state() actions = self.mppi.command(self.state_place_holder).cpu() return actions + + def reset_rollout_sim( + self, dof_state_tensor, root_state_tensor, rigid_body_state_tensor + ): + self.sim.dof_state[:] = bytes_to_torch(dof_state_tensor) + self.sim.root_state[:] = bytes_to_torch(root_state_tensor) + self.sim.rigid_body_state[:] = bytes_to_torch(rigid_body_state_tensor) + + self.sim.gym.set_dof_state_tensor(self.sim.sim, gymtorch.unwrap_tensor(self.sim.dof_state)) + self.sim.gym.set_actor_root_state_tensor(self.sim.sim, gymtorch.unwrap_tensor(self.sim.root_state)) + + def command(self): + return torch_to_bytes(self.mppi.command(self.state_place_holder)) + + def add_to_env(self, env_cfg_additions): + for addition in env_cfg_additions: + self.sim.env_cfg.append(addition) + + self.sim.stop_sim() + self.sim.start_sim() + diff --git a/mppiisaac/utils/config_store.py b/mppiisaac/utils/config_store.py index ca38e37..3c2e3c5 100644 --- a/mppiisaac/utils/config_store.py +++ b/mppiisaac/utils/config_store.py @@ -31,6 +31,7 @@ class ExampleConfig: cs.store(name="config_boxer_robot", node=ExampleConfig) cs.store(name="config_jackal_robot", node=ExampleConfig) cs.store(name="config_panda", node=ExampleConfig) +cs.store(name="config_panda_push", node=ExampleConfig) cs.store(name="config_panda_c_space_goal", node=ExampleConfig) cs.store(group="mppi", name="base_mppi", node=MPPIConfig) cs.store(group="isaacgym", name="base_isaacgym", node=IsaacGymConfig) From 569149be74783cef69ddf1cd0793a5fa82e43c6f Mon Sep 17 00:00:00 2001 From: cpezzato Date: Tue, 28 Mar 2023 10:36:29 +0200 Subject: [PATCH 03/26] Adds missing dependency, tested performance against old implementation, the new one runs 4-5 fps faster :rocket: --- conf/isaacgym/slow.yaml | 1 + conf/mppi/panda.yaml | 2 +- poetry.lock | 442 +++++++++++++++++++++++++++++++++++++++- 3 files changed, 443 insertions(+), 2 deletions(-) diff --git a/conf/isaacgym/slow.yaml b/conf/isaacgym/slow.yaml index 1235e30..485eea8 100644 --- a/conf/isaacgym/slow.yaml +++ b/conf/isaacgym/slow.yaml @@ -2,3 +2,4 @@ defaults: - base_isaacgym dt: 0.01 +substeps: 1 \ No newline at end of file diff --git a/conf/mppi/panda.yaml b/conf/mppi/panda.yaml index cf2101b..85d59bb 100644 --- a/conf/mppi/panda.yaml +++ b/conf/mppi/panda.yaml @@ -3,7 +3,7 @@ defaults: mppi_mode: "halton-spline" # halton-spline, simple sampling_method: "halton" # halton, random -num_samples: 300 +num_samples: 200 horizon: 12 # At least 12 for Halton Sampling device: "cuda:0" u_min: [-0.5] diff --git a/poetry.lock b/poetry.lock index d8274c1..09dbef2 100644 --- a/poetry.lock +++ b/poetry.lock @@ -157,6 +157,83 @@ files = [ {file = "certifi-2022.12.7.tar.gz", hash = "sha256:35824b4c3a97115964b408844d64aa14db1cc518f6562e8d7261699d1350a9e3"}, ] +[[package]] +name = "cffi" +version = "1.15.1" +description = "Foreign Function Interface for Python calling C code." +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "cffi-1.15.1-cp27-cp27m-macosx_10_9_x86_64.whl", hash = "sha256:a66d3508133af6e8548451b25058d5812812ec3798c886bf38ed24a98216fab2"}, + {file = "cffi-1.15.1-cp27-cp27m-manylinux1_i686.whl", hash = "sha256:470c103ae716238bbe698d67ad020e1db9d9dba34fa5a899b5e21577e6d52ed2"}, + {file = "cffi-1.15.1-cp27-cp27m-manylinux1_x86_64.whl", hash = "sha256:9ad5db27f9cabae298d151c85cf2bad1d359a1b9c686a275df03385758e2f914"}, + {file = "cffi-1.15.1-cp27-cp27m-win32.whl", hash = "sha256:b3bbeb01c2b273cca1e1e0c5df57f12dce9a4dd331b4fa1635b8bec26350bde3"}, + {file = "cffi-1.15.1-cp27-cp27m-win_amd64.whl", hash = "sha256:e00b098126fd45523dd056d2efba6c5a63b71ffe9f2bbe1a4fe1716e1d0c331e"}, + {file = "cffi-1.15.1-cp27-cp27mu-manylinux1_i686.whl", hash = "sha256:d61f4695e6c866a23a21acab0509af1cdfd2c013cf256bbf5b6b5e2695827162"}, + {file = "cffi-1.15.1-cp27-cp27mu-manylinux1_x86_64.whl", hash = "sha256:ed9cb427ba5504c1dc15ede7d516b84757c3e3d7868ccc85121d9310d27eed0b"}, + {file = "cffi-1.15.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:39d39875251ca8f612b6f33e6b1195af86d1b3e60086068be9cc053aa4376e21"}, + {file = "cffi-1.15.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:285d29981935eb726a4399badae8f0ffdff4f5050eaa6d0cfc3f64b857b77185"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3eb6971dcff08619f8d91607cfc726518b6fa2a9eba42856be181c6d0d9515fd"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:21157295583fe8943475029ed5abdcf71eb3911894724e360acff1d61c1d54bc"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5635bd9cb9731e6d4a1132a498dd34f764034a8ce60cef4f5319c0541159392f"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2012c72d854c2d03e45d06ae57f40d78e5770d252f195b93f581acf3ba44496e"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd86c085fae2efd48ac91dd7ccffcfc0571387fe1193d33b6394db7ef31fe2a4"}, + {file = "cffi-1.15.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:fa6693661a4c91757f4412306191b6dc88c1703f780c8234035eac011922bc01"}, + {file = "cffi-1.15.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:59c0b02d0a6c384d453fece7566d1c7e6b7bae4fc5874ef2ef46d56776d61c9e"}, + {file = "cffi-1.15.1-cp310-cp310-win32.whl", hash = "sha256:cba9d6b9a7d64d4bd46167096fc9d2f835e25d7e4c121fb2ddfc6528fb0413b2"}, + {file = "cffi-1.15.1-cp310-cp310-win_amd64.whl", hash = "sha256:ce4bcc037df4fc5e3d184794f27bdaab018943698f4ca31630bc7f84a7b69c6d"}, + {file = "cffi-1.15.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3d08afd128ddaa624a48cf2b859afef385b720bb4b43df214f85616922e6a5ac"}, + {file = "cffi-1.15.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:3799aecf2e17cf585d977b780ce79ff0dc9b78d799fc694221ce814c2c19db83"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a591fe9e525846e4d154205572a029f653ada1a78b93697f3b5a8f1f2bc055b9"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3548db281cd7d2561c9ad9984681c95f7b0e38881201e157833a2342c30d5e8c"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:91fc98adde3d7881af9b59ed0294046f3806221863722ba7d8d120c575314325"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:94411f22c3985acaec6f83c6df553f2dbe17b698cc7f8ae751ff2237d96b9e3c"}, + {file = "cffi-1.15.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:03425bdae262c76aad70202debd780501fabeaca237cdfddc008987c0e0f59ef"}, + {file = "cffi-1.15.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:cc4d65aeeaa04136a12677d3dd0b1c0c94dc43abac5860ab33cceb42b801c1e8"}, + {file = "cffi-1.15.1-cp311-cp311-win32.whl", hash = "sha256:a0f100c8912c114ff53e1202d0078b425bee3649ae34d7b070e9697f93c5d52d"}, + {file = "cffi-1.15.1-cp311-cp311-win_amd64.whl", hash = "sha256:04ed324bda3cda42b9b695d51bb7d54b680b9719cfab04227cdd1e04e5de3104"}, + {file = "cffi-1.15.1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:50a74364d85fd319352182ef59c5c790484a336f6db772c1a9231f1c3ed0cbd7"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e263d77ee3dd201c3a142934a086a4450861778baaeeb45db4591ef65550b0a6"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:cec7d9412a9102bdc577382c3929b337320c4c4c4849f2c5cdd14d7368c5562d"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4289fc34b2f5316fbb762d75362931e351941fa95fa18789191b33fc4cf9504a"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:173379135477dc8cac4bc58f45db08ab45d228b3363adb7af79436135d028405"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:6975a3fac6bc83c4a65c9f9fcab9e47019a11d3d2cf7f3c0d03431bf145a941e"}, + {file = "cffi-1.15.1-cp36-cp36m-win32.whl", hash = "sha256:2470043b93ff09bf8fb1d46d1cb756ce6132c54826661a32d4e4d132e1977adf"}, + {file = "cffi-1.15.1-cp36-cp36m-win_amd64.whl", hash = "sha256:30d78fbc8ebf9c92c9b7823ee18eb92f2e6ef79b45ac84db507f52fbe3ec4497"}, + {file = "cffi-1.15.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:198caafb44239b60e252492445da556afafc7d1e3ab7a1fb3f0584ef6d742375"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5ef34d190326c3b1f822a5b7a45f6c4535e2f47ed06fec77d3d799c450b2651e"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8102eaf27e1e448db915d08afa8b41d6c7ca7a04b7d73af6514df10a3e74bd82"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5df2768244d19ab7f60546d0c7c63ce1581f7af8b5de3eb3004b9b6fc8a9f84b"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a8c4917bd7ad33e8eb21e9a5bbba979b49d9a97acb3a803092cbc1133e20343c"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0e2642fe3142e4cc4af0799748233ad6da94c62a8bec3a6648bf8ee68b1c7426"}, + {file = "cffi-1.15.1-cp37-cp37m-win32.whl", hash = "sha256:e229a521186c75c8ad9490854fd8bbdd9a0c9aa3a524326b55be83b54d4e0ad9"}, + {file = "cffi-1.15.1-cp37-cp37m-win_amd64.whl", hash = "sha256:a0b71b1b8fbf2b96e41c4d990244165e2c9be83d54962a9a1d118fd8657d2045"}, + {file = "cffi-1.15.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:320dab6e7cb2eacdf0e658569d2575c4dad258c0fcc794f46215e1e39f90f2c3"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1e74c6b51a9ed6589199c787bf5f9875612ca4a8a0785fb2d4a84429badaf22a"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a5c84c68147988265e60416b57fc83425a78058853509c1b0629c180094904a5"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3b926aa83d1edb5aa5b427b4053dc420ec295a08e40911296b9eb1b6170f6cca"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:87c450779d0914f2861b8526e035c5e6da0a3199d8f1add1a665e1cbc6fc6d02"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4f2c9f67e9821cad2e5f480bc8d83b8742896f1242dba247911072d4fa94c192"}, + {file = "cffi-1.15.1-cp38-cp38-win32.whl", hash = "sha256:8b7ee99e510d7b66cdb6c593f21c043c248537a32e0bedf02e01e9553a172314"}, + {file = "cffi-1.15.1-cp38-cp38-win_amd64.whl", hash = "sha256:00a9ed42e88df81ffae7a8ab6d9356b371399b91dbdf0c3cb1e84c03a13aceb5"}, + {file = "cffi-1.15.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:54a2db7b78338edd780e7ef7f9f6c442500fb0d41a5a4ea24fff1c929d5af585"}, + {file = "cffi-1.15.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:fcd131dd944808b5bdb38e6f5b53013c5aa4f334c5cad0c72742f6eba4b73db0"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7473e861101c9e72452f9bf8acb984947aa1661a7704553a9f6e4baa5ba64415"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6c9a799e985904922a4d207a94eae35c78ebae90e128f0c4e521ce339396be9d"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3bcde07039e586f91b45c88f8583ea7cf7a0770df3a1649627bf598332cb6984"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:33ab79603146aace82c2427da5ca6e58f2b3f2fb5da893ceac0c42218a40be35"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5d598b938678ebf3c67377cdd45e09d431369c3b1a5b331058c338e201f12b27"}, + {file = "cffi-1.15.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:db0fbb9c62743ce59a9ff687eb5f4afbe77e5e8403d6697f7446e5f609976f76"}, + {file = "cffi-1.15.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:98d85c6a2bef81588d9227dde12db8a7f47f639f4a17c9ae08e773aa9c697bf3"}, + {file = "cffi-1.15.1-cp39-cp39-win32.whl", hash = "sha256:40f4774f5a9d4f5e344f31a32b5096977b5d48560c5592e2f3d2c4374bd543ee"}, + {file = "cffi-1.15.1-cp39-cp39-win_amd64.whl", hash = "sha256:70df4e3b545a17496c9b3f41f5115e69a4f2e77e94e1d2a8e1070bc0c38c8a3c"}, + {file = "cffi-1.15.1.tar.gz", hash = "sha256:d400bfb9a37b1351253cb402671cea7e89bdecc294e8016a707f6d1d8ac934f9"}, +] + +[package.dependencies] +pycparser = "*" + [[package]] name = "chardet" version = "5.1.0" @@ -408,6 +485,17 @@ casadi = ">=3.5.4,<3.5.5.post1 || >3.5.5.post1,<3.5.5.post2 || >3.5.5.post2,<4.0 numpy = ">=1.15.3,<2.0.0" urdf_parser_py = ">=0.0.3" +[[package]] +name = "future" +version = "0.18.3" +description = "Clean single-source support for Python 3 and 2" +category = "main" +optional = false +python-versions = ">=2.6, !=3.0.*, !=3.1.*, !=3.2.*" +files = [ + {file = "future-0.18.3.tar.gz", hash = "sha256:34a17436ed1e96697a86f9de3d15a3b0be01d8bc8de9c1dffd59fb8234ed5307"}, +] + [[package]] name = "geomdl" version = "5.3.1" @@ -420,6 +508,82 @@ files = [ {file = "geomdl-5.3.1.tar.gz", hash = "sha256:e81a31b4d5f111267b16045ba1d9539235a98b2cff5e4bad18f7ddcd4cb804c8"}, ] +[[package]] +name = "gevent" +version = "22.10.2" +description = "Coroutine-based network library" +category = "main" +optional = false +python-versions = ">=2.7,!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5" +files = [ + {file = "gevent-22.10.2-cp27-cp27m-macosx_10_14_x86_64.whl", hash = "sha256:97cd42382421779f5d82ec5007199e8a84aa288114975429e4fd0a98f2290f10"}, + {file = "gevent-22.10.2-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:1e1286a76f15b5e15f1e898731d50529e249529095a032453f2c101af3fde71c"}, + {file = "gevent-22.10.2-cp27-cp27m-win32.whl", hash = "sha256:59b47e81b399d49a5622f0f503c59f1ce57b7705306ea0196818951dfc2f36c8"}, + {file = "gevent-22.10.2-cp27-cp27m-win_amd64.whl", hash = "sha256:1d543c9407a1e4bca11a8932916988cfb16de00366de5bf7bc9e7a3f61e60b18"}, + {file = "gevent-22.10.2-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:4e2f008c82dc54ec94f4de12ca6feea60e419babb48ec145456907ae61625aa4"}, + {file = "gevent-22.10.2-cp310-cp310-macosx_10_15_x86_64.whl", hash = "sha256:990d7069f14dc40674e0d5cb43c68fd3bad8337048613b9bb94a0c4180ffc176"}, + {file = "gevent-22.10.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f23d0997149a816a2a9045af29c66f67f405a221745b34cefeac5769ed451db8"}, + {file = "gevent-22.10.2-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b43d500d7d3c0e03070dee813335bb5315215aa1cf6a04c61093dfdd718640b3"}, + {file = "gevent-22.10.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:17b68f4c9e20e47ad49fe797f37f91d5bbeace8765ce2707f979a8d4ec197e4d"}, + {file = "gevent-22.10.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:1f001cac0ba8da76abfeb392a3057f81fab3d67cc916c7df8ea977a44a2cc989"}, + {file = "gevent-22.10.2-cp310-cp310-win_amd64.whl", hash = "sha256:3b7eae8a0653ba95a224faaddf629a913ace408edb67384d3117acf42d7dcf89"}, + {file = "gevent-22.10.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8f2477e7b0a903a01485c55bacf2089110e5f767014967ba4b287ff390ae2638"}, + {file = "gevent-22.10.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ddaa3e310a8f1a45b5c42cf50b54c31003a3028e7d4e085059090ea0e7a5fddd"}, + {file = "gevent-22.10.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:98bc510e80f45486ef5b806a1c305e0e89f0430688c14984b0dbdec03331f48b"}, + {file = "gevent-22.10.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:877abdb3a669576b1d51ce6a49b7260b2a96f6b2424eb93287e779a3219d20ba"}, + {file = "gevent-22.10.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:d21ad79cca234cdbfa249e727500b0ddcbc7adfff6614a96e6eaa49faca3e4f2"}, + {file = "gevent-22.10.2-cp311-cp311-win_amd64.whl", hash = "sha256:1e955238f59b2947631c9782a713280dd75884e40e455313b5b6bbc20b92ff73"}, + {file = "gevent-22.10.2-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:5aa99e4882a9e909b4756ee799c6fa0f79eb0542779fad4cc60efa23ec1b2aa8"}, + {file = "gevent-22.10.2-cp36-cp36m-manylinux2010_x86_64.whl", hash = "sha256:d82081656a5b9a94d37c718c8646c757e1617e389cdc533ea5e6a6f0b8b78545"}, + {file = "gevent-22.10.2-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:54f4bfd74c178351a4a05c5c7df6f8a0a279ff6f392b57608ce0e83c768207f9"}, + {file = "gevent-22.10.2-cp36-cp36m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1ff3796692dff50fec2f381b9152438b221335f557c4f9b811f7ded51b7a25a1"}, + {file = "gevent-22.10.2-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f01c9adbcb605364694b11dcd0542ec468a29ac7aba2fb5665dc6caf17ba4d7e"}, + {file = "gevent-22.10.2-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:9d85574eb729f981fea9a78998725a06292d90a3ed50ddca74530c3148c0be41"}, + {file = "gevent-22.10.2-cp36-cp36m-win32.whl", hash = "sha256:8c192d2073e558e241f0b592c1e2b34127a4481a5be240cad4796533b88b1a98"}, + {file = "gevent-22.10.2-cp36-cp36m-win_amd64.whl", hash = "sha256:a2237451c721a0f874ef89dbb4af4fdc172b76a964befaa69deb15b8fff10f49"}, + {file = "gevent-22.10.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:53ee7f170ed42c7561fe8aff5d381dc9a4124694e70580d0c02fba6aafc0ea37"}, + {file = "gevent-22.10.2-cp37-cp37m-manylinux2010_x86_64.whl", hash = "sha256:96c56c280e3c43cfd075efd10b250350ed5ffd3c1514ec99a080b1b92d7c8374"}, + {file = "gevent-22.10.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b6c144e08dfad4106effc043a026e5d0c0eff6ad031904c70bf5090c63f3a6a7"}, + {file = "gevent-22.10.2-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:018f93de7d5318d2fb440f846839a4464738468c3476d5c9cf7da45bb71c18bd"}, + {file = "gevent-22.10.2-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f7ed2346eb9dc4344f9cb0d7963ce5b74fe16fdd031a2809bb6c2b6eba7ebcd5"}, + {file = "gevent-22.10.2-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:84c517e33ed604fa06b7d756dc0171169cc12f7fdd68eb7b17708a62eebf4516"}, + {file = "gevent-22.10.2-cp37-cp37m-win32.whl", hash = "sha256:4114f0f439f0b547bb6f1d474fee99ddb46736944ad2207cef3771828f6aa358"}, + {file = "gevent-22.10.2-cp37-cp37m-win_amd64.whl", hash = "sha256:0d581f22a5be6281b11ad6309b38b18f0638cf896931223cbaa5adb904826ef6"}, + {file = "gevent-22.10.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:2929377c8ebfb6f4d868d161cd8de2ea6b9f6c7a5fcd4f78bcd537319c16190b"}, + {file = "gevent-22.10.2-cp38-cp38-manylinux2010_x86_64.whl", hash = "sha256:efc003b6c1481165af61f0aeac248e0a9ac8d880bb3acbe469b448674b2d5281"}, + {file = "gevent-22.10.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:db562a8519838bddad0c439a2b12246bab539dd50e299ea7ff3644274a33b6a5"}, + {file = "gevent-22.10.2-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1472012493ca1fac103f700d309cb6ef7964dcdb9c788d1768266e77712f5e49"}, + {file = "gevent-22.10.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6c04ee32c11e9fcee47c1b431834878dc987a7a2cc4fe126ddcae3bad723ce89"}, + {file = "gevent-22.10.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:8729129edef2637a8084258cb9ec4e4d5ca45d97ac77aa7a6ff19ccb530ab731"}, + {file = "gevent-22.10.2-cp38-cp38-win32.whl", hash = "sha256:ae90226074a6089371a95f20288431cd4b3f6b0b096856afd862e4ac9510cddd"}, + {file = "gevent-22.10.2-cp38-cp38-win_amd64.whl", hash = "sha256:494c7f29e94df9a1c3157d67bb7edfa32a46eed786e04d9ee68d39f375e30001"}, + {file = "gevent-22.10.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:58898dbabb5b11e4d0192aae165ad286dc6742c543e1be9d30dc82753547c508"}, + {file = "gevent-22.10.2-cp39-cp39-manylinux2010_x86_64.whl", hash = "sha256:4197d423e198265eef39a0dea286ef389da9148e070310f34455ecee8172c391"}, + {file = "gevent-22.10.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da4183f0b9d9a1e25e1758099220d32c51cc2c6340ee0dea3fd236b2b37598e4"}, + {file = "gevent-22.10.2-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a5488eba6a568b4d23c072113da4fc0feb1b5f5ede7381656dc913e0d82204e2"}, + {file = "gevent-22.10.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:319d8b1699b7b8134de66d656cd739b308ab9c45ace14d60ae44de7775b456c9"}, + {file = "gevent-22.10.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:f3329bedbba4d3146ae58c667e0f9ac1e6f1e1e6340c7593976cdc60aa7d1a47"}, + {file = "gevent-22.10.2-cp39-cp39-win32.whl", hash = "sha256:172caa66273315f283e90a315921902cb6549762bdcb0587fd60cb712a9d6263"}, + {file = "gevent-22.10.2-cp39-cp39-win_amd64.whl", hash = "sha256:323b207b281ba0405fea042067fa1a61662e5ac0d574ede4ebbda03efd20c350"}, + {file = "gevent-22.10.2-pp27-pypy_73-win_amd64.whl", hash = "sha256:ed7f16613eebf892a6a744d7a4a8f345bc6f066a0ff3b413e2479f9c0a180193"}, + {file = "gevent-22.10.2-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:a47a4e77e2bc668856aad92a0b8de7ee10768258d93cd03968e6c7ba2e832f76"}, + {file = "gevent-22.10.2.tar.gz", hash = "sha256:1ca01da176ee37b3527a2702f7d40dbc9ffb8cfc7be5a03bfa4f9eec45e55c46"}, +] + +[package.dependencies] +cffi = {version = ">=1.12.2", markers = "platform_python_implementation == \"CPython\" and sys_platform == \"win32\""} +greenlet = {version = ">=2.0.0", markers = "platform_python_implementation == \"CPython\""} +setuptools = "*" +"zope.event" = "*" +"zope.interface" = "*" + +[package.extras] +dnspython = ["dnspython (>=1.16.0,<2.0)", "idna"] +docs = ["repoze.sphinx.autointerface", "sphinxcontrib-programoutput", "zope.schema"] +monitor = ["psutil (>=5.7.0)"] +recommended = ["backports.socketpair", "cffi (>=1.12.2)", "dnspython (>=1.16.0,<2.0)", "idna", "psutil (>=5.7.0)", "selectors2"] +test = ["backports.socketpair", "cffi (>=1.12.2)", "contextvars (==2.4)", "coverage (>=5.0)", "coveralls (>=1.7.0)", "dnspython (>=1.16.0,<2.0)", "futures", "idna", "mock", "objgraph", "psutil (>=5.7.0)", "requests", "selectors2"] + [[package]] name = "ghalton" version = "0.6.2" @@ -452,6 +616,80 @@ files = [ {file = "ghalton-0.6.2.tar.gz", hash = "sha256:fcff3f528ead5f77a60ecc774a666c3b24747d05af1c693909bd824049eb30d2"}, ] +[[package]] +name = "greenlet" +version = "2.0.2" +description = "Lightweight in-process concurrent programming" +category = "main" +optional = false +python-versions = ">=2.7,!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*" +files = [ + {file = "greenlet-2.0.2-cp27-cp27m-macosx_10_14_x86_64.whl", hash = "sha256:bdfea8c661e80d3c1c99ad7c3ff74e6e87184895bbaca6ee8cc61209f8b9b85d"}, + {file = "greenlet-2.0.2-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:9d14b83fab60d5e8abe587d51c75b252bcc21683f24699ada8fb275d7712f5a9"}, + {file = "greenlet-2.0.2-cp27-cp27m-win32.whl", hash = "sha256:6c3acb79b0bfd4fe733dff8bc62695283b57949ebcca05ae5c129eb606ff2d74"}, + {file = "greenlet-2.0.2-cp27-cp27m-win_amd64.whl", hash = "sha256:283737e0da3f08bd637b5ad058507e578dd462db259f7f6e4c5c365ba4ee9343"}, + {file = "greenlet-2.0.2-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:d27ec7509b9c18b6d73f2f5ede2622441de812e7b1a80bbd446cb0633bd3d5ae"}, + {file = "greenlet-2.0.2-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:30bcf80dda7f15ac77ba5af2b961bdd9dbc77fd4ac6105cee85b0d0a5fcf74df"}, + {file = "greenlet-2.0.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:26fbfce90728d82bc9e6c38ea4d038cba20b7faf8a0ca53a9c07b67318d46088"}, + {file = "greenlet-2.0.2-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9190f09060ea4debddd24665d6804b995a9c122ef5917ab26e1566dcc712ceeb"}, + {file = "greenlet-2.0.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d75209eed723105f9596807495d58d10b3470fa6732dd6756595e89925ce2470"}, + {file = "greenlet-2.0.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:3a51c9751078733d88e013587b108f1b7a1fb106d402fb390740f002b6f6551a"}, + {file = "greenlet-2.0.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:76ae285c8104046b3a7f06b42f29c7b73f77683df18c49ab5af7983994c2dd91"}, + {file = "greenlet-2.0.2-cp310-cp310-win_amd64.whl", hash = "sha256:2d4686f195e32d36b4d7cf2d166857dbd0ee9f3d20ae349b6bf8afc8485b3645"}, + {file = "greenlet-2.0.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c4302695ad8027363e96311df24ee28978162cdcdd2006476c43970b384a244c"}, + {file = "greenlet-2.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c48f54ef8e05f04d6eff74b8233f6063cb1ed960243eacc474ee73a2ea8573ca"}, + {file = "greenlet-2.0.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a1846f1b999e78e13837c93c778dcfc3365902cfb8d1bdb7dd73ead37059f0d0"}, + {file = "greenlet-2.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a06ad5312349fec0ab944664b01d26f8d1f05009566339ac6f63f56589bc1a2"}, + {file = "greenlet-2.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:eff4eb9b7eb3e4d0cae3d28c283dc16d9bed6b193c2e1ace3ed86ce48ea8df19"}, + {file = "greenlet-2.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:5454276c07d27a740c5892f4907c86327b632127dd9abec42ee62e12427ff7e3"}, + {file = "greenlet-2.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:7cafd1208fdbe93b67c7086876f061f660cfddc44f404279c1585bbf3cdc64c5"}, + {file = "greenlet-2.0.2-cp35-cp35m-macosx_10_14_x86_64.whl", hash = "sha256:910841381caba4f744a44bf81bfd573c94e10b3045ee00de0cbf436fe50673a6"}, + {file = "greenlet-2.0.2-cp35-cp35m-manylinux2010_x86_64.whl", hash = "sha256:18a7f18b82b52ee85322d7a7874e676f34ab319b9f8cce5de06067384aa8ff43"}, + {file = "greenlet-2.0.2-cp35-cp35m-win32.whl", hash = "sha256:03a8f4f3430c3b3ff8d10a2a86028c660355ab637cee9333d63d66b56f09d52a"}, + {file = "greenlet-2.0.2-cp35-cp35m-win_amd64.whl", hash = "sha256:4b58adb399c4d61d912c4c331984d60eb66565175cdf4a34792cd9600f21b394"}, + {file = "greenlet-2.0.2-cp36-cp36m-macosx_10_14_x86_64.whl", hash = "sha256:703f18f3fda276b9a916f0934d2fb6d989bf0b4fb5a64825260eb9bfd52d78f0"}, + {file = "greenlet-2.0.2-cp36-cp36m-manylinux2010_x86_64.whl", hash = "sha256:32e5b64b148966d9cccc2c8d35a671409e45f195864560829f395a54226408d3"}, + {file = "greenlet-2.0.2-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2dd11f291565a81d71dab10b7033395b7a3a5456e637cf997a6f33ebdf06f8db"}, + {file = "greenlet-2.0.2-cp36-cp36m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e0f72c9ddb8cd28532185f54cc1453f2c16fb417a08b53a855c4e6a418edd099"}, + {file = "greenlet-2.0.2-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cd021c754b162c0fb55ad5d6b9d960db667faad0fa2ff25bb6e1301b0b6e6a75"}, + {file = "greenlet-2.0.2-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:3c9b12575734155d0c09d6c3e10dbd81665d5c18e1a7c6597df72fd05990c8cf"}, + {file = "greenlet-2.0.2-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:b9ec052b06a0524f0e35bd8790686a1da006bd911dd1ef7d50b77bfbad74e292"}, + {file = "greenlet-2.0.2-cp36-cp36m-win32.whl", hash = "sha256:dbfcfc0218093a19c252ca8eb9aee3d29cfdcb586df21049b9d777fd32c14fd9"}, + {file = "greenlet-2.0.2-cp36-cp36m-win_amd64.whl", hash = "sha256:9f35ec95538f50292f6d8f2c9c9f8a3c6540bbfec21c9e5b4b751e0a7c20864f"}, + {file = "greenlet-2.0.2-cp37-cp37m-macosx_10_15_x86_64.whl", hash = "sha256:d5508f0b173e6aa47273bdc0a0b5ba055b59662ba7c7ee5119528f466585526b"}, + {file = "greenlet-2.0.2-cp37-cp37m-manylinux2010_x86_64.whl", hash = "sha256:f82d4d717d8ef19188687aa32b8363e96062911e63ba22a0cff7802a8e58e5f1"}, + {file = "greenlet-2.0.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c9c59a2120b55788e800d82dfa99b9e156ff8f2227f07c5e3012a45a399620b7"}, + {file = "greenlet-2.0.2-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:2780572ec463d44c1d3ae850239508dbeb9fed38e294c68d19a24d925d9223ca"}, + {file = "greenlet-2.0.2-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:937e9020b514ceedb9c830c55d5c9872abc90f4b5862f89c0887033ae33c6f73"}, + {file = "greenlet-2.0.2-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:36abbf031e1c0f79dd5d596bfaf8e921c41df2bdf54ee1eed921ce1f52999a86"}, + {file = "greenlet-2.0.2-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:18e98fb3de7dba1c0a852731c3070cf022d14f0d68b4c87a19cc1016f3bb8b33"}, + {file = "greenlet-2.0.2-cp37-cp37m-win32.whl", hash = "sha256:3f6ea9bd35eb450837a3d80e77b517ea5bc56b4647f5502cd28de13675ee12f7"}, + {file = "greenlet-2.0.2-cp37-cp37m-win_amd64.whl", hash = "sha256:7492e2b7bd7c9b9916388d9df23fa49d9b88ac0640db0a5b4ecc2b653bf451e3"}, + {file = "greenlet-2.0.2-cp38-cp38-macosx_10_15_x86_64.whl", hash = "sha256:b864ba53912b6c3ab6bcb2beb19f19edd01a6bfcbdfe1f37ddd1778abfe75a30"}, + {file = "greenlet-2.0.2-cp38-cp38-manylinux2010_x86_64.whl", hash = "sha256:ba2956617f1c42598a308a84c6cf021a90ff3862eddafd20c3333d50f0edb45b"}, + {file = "greenlet-2.0.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fc3a569657468b6f3fb60587e48356fe512c1754ca05a564f11366ac9e306526"}, + {file = "greenlet-2.0.2-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8eab883b3b2a38cc1e050819ef06a7e6344d4a990d24d45bc6f2cf959045a45b"}, + {file = "greenlet-2.0.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:acd2162a36d3de67ee896c43effcd5ee3de247eb00354db411feb025aa319857"}, + {file = "greenlet-2.0.2-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:0bf60faf0bc2468089bdc5edd10555bab6e85152191df713e2ab1fcc86382b5a"}, + {file = "greenlet-2.0.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:b0ef99cdbe2b682b9ccbb964743a6aca37905fda5e0452e5ee239b1654d37f2a"}, + {file = "greenlet-2.0.2-cp38-cp38-win32.whl", hash = "sha256:b80f600eddddce72320dbbc8e3784d16bd3fb7b517e82476d8da921f27d4b249"}, + {file = "greenlet-2.0.2-cp38-cp38-win_amd64.whl", hash = "sha256:4d2e11331fc0c02b6e84b0d28ece3a36e0548ee1a1ce9ddde03752d9b79bba40"}, + {file = "greenlet-2.0.2-cp39-cp39-macosx_11_0_x86_64.whl", hash = "sha256:88d9ab96491d38a5ab7c56dd7a3cc37d83336ecc564e4e8816dbed12e5aaefc8"}, + {file = "greenlet-2.0.2-cp39-cp39-manylinux2010_x86_64.whl", hash = "sha256:561091a7be172ab497a3527602d467e2b3fbe75f9e783d8b8ce403fa414f71a6"}, + {file = "greenlet-2.0.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:971ce5e14dc5e73715755d0ca2975ac88cfdaefcaab078a284fea6cfabf866df"}, + {file = "greenlet-2.0.2-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:be4ed120b52ae4d974aa40215fcdfde9194d63541c7ded40ee12eb4dda57b76b"}, + {file = "greenlet-2.0.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:94c817e84245513926588caf1152e3b559ff794d505555211ca041f032abbb6b"}, + {file = "greenlet-2.0.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:1a819eef4b0e0b96bb0d98d797bef17dc1b4a10e8d7446be32d1da33e095dbb8"}, + {file = "greenlet-2.0.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:7efde645ca1cc441d6dc4b48c0f7101e8d86b54c8530141b09fd31cef5149ec9"}, + {file = "greenlet-2.0.2-cp39-cp39-win32.whl", hash = "sha256:ea9872c80c132f4663822dd2a08d404073a5a9b5ba6155bea72fb2a79d1093b5"}, + {file = "greenlet-2.0.2-cp39-cp39-win_amd64.whl", hash = "sha256:db1a39669102a1d8d12b57de2bb7e2ec9066a6f2b3da35ae511ff93b01b5d564"}, + {file = "greenlet-2.0.2.tar.gz", hash = "sha256:e7c8dc13af7db097bed64a051d2dd49e9f0af495c26995c00a9ee842690d34c0"}, +] + +[package.extras] +docs = ["Sphinx", "docutils (<0.18)"] +test = ["objgraph", "psutil"] + [[package]] name = "gym" version = "0.22.0" @@ -1089,6 +1327,7 @@ files = [ {file = "ninja-1.11.1-py2.py3-none-musllinux_1_1_x86_64.whl", hash = "sha256:3b28b595ed580752240ade7821b6cb7a5a4c6a604c865dc474bd38f06e2eb7f5"}, {file = "ninja-1.11.1-py2.py3-none-win32.whl", hash = "sha256:3329b4b7c1694730772522a3ba0ba40fd15c012476ed3e1c9f0fd9e76190394e"}, {file = "ninja-1.11.1-py2.py3-none-win_amd64.whl", hash = "sha256:4e547bc759c570773d83d110c41fd5ca9a94c0a9a8388f5a3ea37bdf97d002b0"}, + {file = "ninja-1.11.1-py2.py3-none-win_arm64.whl", hash = "sha256:8cf96f92ccc851c600cb3e1251c34db06f1dd682de79188ad490c33cddc66981"}, {file = "ninja-1.11.1.tar.gz", hash = "sha256:c833a47d39b2d1eee3f9ca886fa1581efd5be6068b82734ac229961ee8748f90"}, ] @@ -1301,6 +1540,20 @@ category = "main" optional = false python-versions = ">=3.7" files = [ + {file = "Pillow-9.4.0-1-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:1b4b4e9dda4f4e4c4e6896f93e84a8f0bcca3b059de9ddf67dac3c334b1195e1"}, + {file = "Pillow-9.4.0-1-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:fb5c1ad6bad98c57482236a21bf985ab0ef42bd51f7ad4e4538e89a997624e12"}, + {file = "Pillow-9.4.0-1-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:f0caf4a5dcf610d96c3bd32932bfac8aee61c96e60481c2a0ea58da435e25acd"}, + {file = "Pillow-9.4.0-1-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:3f4cc516e0b264c8d4ccd6b6cbc69a07c6d582d8337df79be1e15a5056b258c9"}, + {file = "Pillow-9.4.0-1-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:b8c2f6eb0df979ee99433d8b3f6d193d9590f735cf12274c108bd954e30ca858"}, + {file = "Pillow-9.4.0-1-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:b70756ec9417c34e097f987b4d8c510975216ad26ba6e57ccb53bc758f490dab"}, + {file = "Pillow-9.4.0-1-pp39-pypy39_pp73-macosx_10_10_x86_64.whl", hash = "sha256:43521ce2c4b865d385e78579a082b6ad1166ebed2b1a2293c3be1d68dd7ca3b9"}, + {file = "Pillow-9.4.0-2-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:9d9a62576b68cd90f7075876f4e8444487db5eeea0e4df3ba298ee38a8d067b0"}, + {file = "Pillow-9.4.0-2-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:87708d78a14d56a990fbf4f9cb350b7d89ee8988705e58e39bdf4d82c149210f"}, + {file = "Pillow-9.4.0-2-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:8a2b5874d17e72dfb80d917213abd55d7e1ed2479f38f001f264f7ce7bae757c"}, + {file = "Pillow-9.4.0-2-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:83125753a60cfc8c412de5896d10a0a405e0bd88d0470ad82e0869ddf0cb3848"}, + {file = "Pillow-9.4.0-2-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:9e5f94742033898bfe84c93c831a6f552bb629448d4072dd312306bab3bd96f1"}, + {file = "Pillow-9.4.0-2-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:013016af6b3a12a2f40b704677f8b51f72cb007dac785a9933d5c86a72a7fe33"}, + {file = "Pillow-9.4.0-2-pp39-pypy39_pp73-macosx_10_10_x86_64.whl", hash = "sha256:99d92d148dd03fd19d16175b6d355cc1b01faf80dae93c6c3eb4163709edc0a9"}, {file = "Pillow-9.4.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:2968c58feca624bb6c8502f9564dd187d0e1389964898f5e9e1fbc8533169157"}, {file = "Pillow-9.4.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c5c1362c14aee73f50143d74389b2c158707b4abce2cb055b7ad37ce60738d47"}, {file = "Pillow-9.4.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bd752c5ff1b4a870b7661234694f24b1d2b9076b8bf337321a814c612665f343"}, @@ -1450,6 +1703,18 @@ python-dateutil = ">=2.2" prettyprint = ["lxml"] validation = ["lxml"] +[[package]] +name = "pycparser" +version = "2.21" +description = "C parser in Python" +category = "main" +optional = false +python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" +files = [ + {file = "pycparser-2.21-py2.py3-none-any.whl", hash = "sha256:8ee45429555515e1f6b185e78100aea234072576aa43ab53aefcae078162fca9"}, + {file = "pycparser-2.21.tar.gz", hash = "sha256:e644fdec12f7872f86c58ff790da456218b10f863970249516d60a5eaca77206"}, +] + [[package]] name = "pylint" version = "2.16.1" @@ -1623,6 +1888,96 @@ files = [ {file = "PyYAML-6.0.tar.gz", hash = "sha256:68fb519c14306fec9720a2a5b45bc9f0c8d1b9c72adf45c37baedfcd949c35a2"}, ] +[[package]] +name = "pyzmq" +version = "25.0.2" +description = "Python bindings for 0MQ" +category = "main" +optional = false +python-versions = ">=3.6" +files = [ + {file = "pyzmq-25.0.2-cp310-cp310-macosx_10_15_universal2.whl", hash = "sha256:ac178e666c097c8d3deb5097b58cd1316092fc43e8ef5b5fdb259b51da7e7315"}, + {file = "pyzmq-25.0.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:659e62e1cbb063151c52f5b01a38e1df6b54feccfa3e2509d44c35ca6d7962ee"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8280ada89010735a12b968ec3ea9a468ac2e04fddcc1cede59cb7f5178783b9c"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a9b5eeb5278a8a636bb0abdd9ff5076bcbb836cd2302565df53ff1fa7d106d54"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9a2e5fe42dfe6b73ca120b97ac9f34bfa8414feb15e00e37415dbd51cf227ef6"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:827bf60e749e78acb408a6c5af6688efbc9993e44ecc792b036ec2f4b4acf485"}, + {file = "pyzmq-25.0.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:7b504ae43d37e282301da586529e2ded8b36d4ee2cd5e6db4386724ddeaa6bbc"}, + {file = "pyzmq-25.0.2-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:cb1f69a0a2a2b1aae8412979dd6293cc6bcddd4439bf07e4758d864ddb112354"}, + {file = "pyzmq-25.0.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:2b9c9cc965cdf28381e36da525dcb89fc1571d9c54800fdcd73e3f73a2fc29bd"}, + {file = "pyzmq-25.0.2-cp310-cp310-win32.whl", hash = "sha256:24abbfdbb75ac5039205e72d6c75f10fc39d925f2df8ff21ebc74179488ebfca"}, + {file = "pyzmq-25.0.2-cp310-cp310-win_amd64.whl", hash = "sha256:6a821a506822fac55d2df2085a52530f68ab15ceed12d63539adc32bd4410f6e"}, + {file = "pyzmq-25.0.2-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:9af0bb0277e92f41af35e991c242c9c71920169d6aa53ade7e444f338f4c8128"}, + {file = "pyzmq-25.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:54a96cf77684a3a537b76acfa7237b1e79a8f8d14e7f00e0171a94b346c5293e"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88649b19ede1cab03b96b66c364cbbf17c953615cdbc844f7f6e5f14c5e5261c"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:715cff7644a80a7795953c11b067a75f16eb9fc695a5a53316891ebee7f3c9d5"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:312b3f0f066b4f1d17383aae509bacf833ccaf591184a1f3c7a1661c085063ae"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:d488c5c8630f7e782e800869f82744c3aca4aca62c63232e5d8c490d3d66956a"}, + {file = "pyzmq-25.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:38d9f78d69bcdeec0c11e0feb3bc70f36f9b8c44fc06e5d06d91dc0a21b453c7"}, + {file = "pyzmq-25.0.2-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:3059a6a534c910e1d5d068df42f60d434f79e6cc6285aa469b384fa921f78cf8"}, + {file = "pyzmq-25.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:6526d097b75192f228c09d48420854d53dfbc7abbb41b0e26f363ccb26fbc177"}, + {file = "pyzmq-25.0.2-cp311-cp311-win32.whl", hash = "sha256:5c5fbb229e40a89a2fe73d0c1181916f31e30f253cb2d6d91bea7927c2e18413"}, + {file = "pyzmq-25.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:ed15e3a2c3c2398e6ae5ce86d6a31b452dfd6ad4cd5d312596b30929c4b6e182"}, + {file = "pyzmq-25.0.2-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:032f5c8483c85bf9c9ca0593a11c7c749d734ce68d435e38c3f72e759b98b3c9"}, + {file = "pyzmq-25.0.2-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:374b55516393bfd4d7a7daa6c3b36d6dd6a31ff9d2adad0838cd6a203125e714"}, + {file = "pyzmq-25.0.2-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:08bfcc21b5997a9be4fefa405341320d8e7f19b4d684fb9c0580255c5bd6d695"}, + {file = "pyzmq-25.0.2-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:1a843d26a8da1b752c74bc019c7b20e6791ee813cd6877449e6a1415589d22ff"}, + {file = "pyzmq-25.0.2-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:b48616a09d7df9dbae2f45a0256eee7b794b903ddc6d8657a9948669b345f220"}, + {file = "pyzmq-25.0.2-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:d4427b4a136e3b7f85516c76dd2e0756c22eec4026afb76ca1397152b0ca8145"}, + {file = "pyzmq-25.0.2-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:26b0358e8933990502f4513c991c9935b6c06af01787a36d133b7c39b1df37fa"}, + {file = "pyzmq-25.0.2-cp36-cp36m-win32.whl", hash = "sha256:c8fedc3ccd62c6b77dfe6f43802057a803a411ee96f14e946f4a76ec4ed0e117"}, + {file = "pyzmq-25.0.2-cp36-cp36m-win_amd64.whl", hash = "sha256:2da6813b7995b6b1d1307329c73d3e3be2fd2d78e19acfc4eff2e27262732388"}, + {file = "pyzmq-25.0.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:a35960c8b2f63e4ef67fd6731851030df68e4b617a6715dd11b4b10312d19fef"}, + {file = "pyzmq-25.0.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:eef2a0b880ab40aca5a878933376cb6c1ec483fba72f7f34e015c0f675c90b20"}, + {file = "pyzmq-25.0.2-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:85762712b74c7bd18e340c3639d1bf2f23735a998d63f46bb6584d904b5e401d"}, + {file = "pyzmq-25.0.2-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:64812f29d6eee565e129ca14b0c785744bfff679a4727137484101b34602d1a7"}, + {file = "pyzmq-25.0.2-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:510d8e55b3a7cd13f8d3e9121edf0a8730b87d925d25298bace29a7e7bc82810"}, + {file = "pyzmq-25.0.2-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:b164cc3c8acb3d102e311f2eb6f3c305865ecb377e56adc015cb51f721f1dda6"}, + {file = "pyzmq-25.0.2-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:28fdb9224a258134784a9cf009b59265a9dde79582fb750d4e88a6bcbc6fa3dc"}, + {file = "pyzmq-25.0.2-cp37-cp37m-win32.whl", hash = "sha256:dd771a440effa1c36d3523bc6ba4e54ff5d2e54b4adcc1e060d8f3ca3721d228"}, + {file = "pyzmq-25.0.2-cp37-cp37m-win_amd64.whl", hash = "sha256:9bdc40efb679b9dcc39c06d25629e55581e4c4f7870a5e88db4f1c51ce25e20d"}, + {file = "pyzmq-25.0.2-cp38-cp38-macosx_10_15_universal2.whl", hash = "sha256:1f82906a2d8e4ee310f30487b165e7cc8ed09c009e4502da67178b03083c4ce0"}, + {file = "pyzmq-25.0.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:21ec0bf4831988af43c8d66ba3ccd81af2c5e793e1bf6790eb2d50e27b3c570a"}, + {file = "pyzmq-25.0.2-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:abbce982a17c88d2312ec2cf7673985d444f1beaac6e8189424e0a0e0448dbb3"}, + {file = "pyzmq-25.0.2-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:9e1d2f2d86fc75ed7f8845a992c5f6f1ab5db99747fb0d78b5e4046d041164d2"}, + {file = "pyzmq-25.0.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a2e92ff20ad5d13266bc999a29ed29a3b5b101c21fdf4b2cf420c09db9fb690e"}, + {file = "pyzmq-25.0.2-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:edbbf06cc2719889470a8d2bf5072bb00f423e12de0eb9ffec946c2c9748e149"}, + {file = "pyzmq-25.0.2-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:77942243ff4d14d90c11b2afd8ee6c039b45a0be4e53fb6fa7f5e4fd0b59da39"}, + {file = "pyzmq-25.0.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:ab046e9cb902d1f62c9cc0eca055b1d11108bdc271caf7c2171487298f229b56"}, + {file = "pyzmq-25.0.2-cp38-cp38-win32.whl", hash = "sha256:ad761cfbe477236802a7ab2c080d268c95e784fe30cafa7e055aacd1ca877eb0"}, + {file = "pyzmq-25.0.2-cp38-cp38-win_amd64.whl", hash = "sha256:8560756318ec7c4c49d2c341012167e704b5a46d9034905853c3d1ade4f55bee"}, + {file = "pyzmq-25.0.2-cp39-cp39-macosx_10_15_universal2.whl", hash = "sha256:ab2c056ac503f25a63f6c8c6771373e2a711b98b304614151dfb552d3d6c81f6"}, + {file = "pyzmq-25.0.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:cca8524b61c0eaaa3505382dc9b9a3bc8165f1d6c010fdd1452c224225a26689"}, + {file = "pyzmq-25.0.2-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:cfb9f7eae02d3ac42fbedad30006b7407c984a0eb4189a1322241a20944d61e5"}, + {file = "pyzmq-25.0.2-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:5eaeae038c68748082137d6896d5c4db7927e9349237ded08ee1bbd94f7361c9"}, + {file = "pyzmq-25.0.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4a31992a8f8d51663ebf79df0df6a04ffb905063083d682d4380ab8d2c67257c"}, + {file = "pyzmq-25.0.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:6a979e59d2184a0c8f2ede4b0810cbdd86b64d99d9cc8a023929e40dce7c86cc"}, + {file = "pyzmq-25.0.2-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:1f124cb73f1aa6654d31b183810febc8505fd0c597afa127c4f40076be4574e0"}, + {file = "pyzmq-25.0.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:65c19a63b4a83ae45d62178b70223adeee5f12f3032726b897431b6553aa25af"}, + {file = "pyzmq-25.0.2-cp39-cp39-win32.whl", hash = "sha256:83d822e8687621bed87404afc1c03d83fa2ce39733d54c2fd52d8829edb8a7ff"}, + {file = "pyzmq-25.0.2-cp39-cp39-win_amd64.whl", hash = "sha256:24683285cc6b7bf18ad37d75b9db0e0fefe58404e7001f1d82bf9e721806daa7"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:4a4b4261eb8f9ed71f63b9eb0198dd7c934aa3b3972dac586d0ef502ba9ab08b"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:62ec8d979f56c0053a92b2b6a10ff54b9ec8a4f187db2b6ec31ee3dd6d3ca6e2"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:affec1470351178e892121b3414c8ef7803269f207bf9bef85f9a6dd11cde264"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ffc71111433bd6ec8607a37b9211f4ef42e3d3b271c6d76c813669834764b248"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:6fadc60970714d86eff27821f8fb01f8328dd36bebd496b0564a500fe4a9e354"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:269968f2a76c0513490aeb3ba0dc3c77b7c7a11daa894f9d1da88d4a0db09835"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:f7c8b8368e84381ae7c57f1f5283b029c888504aaf4949c32e6e6fb256ec9bf0"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:25e6873a70ad5aa31e4a7c41e5e8c709296edef4a92313e1cd5fc87bbd1874e2"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b733076ff46e7db5504c5e7284f04a9852c63214c74688bdb6135808531755a3"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:a6f6ae12478fdc26a6d5fdb21f806b08fa5403cd02fd312e4cb5f72df078f96f"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:67da1c213fbd208906ab3470cfff1ee0048838365135a9bddc7b40b11e6d6c89"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:531e36d9fcd66f18de27434a25b51d137eb546931033f392e85674c7a7cea853"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:34a6fddd159ff38aa9497b2e342a559f142ab365576284bc8f77cb3ead1f79c5"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b491998ef886662c1f3d49ea2198055a9a536ddf7430b051b21054f2a5831800"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:5d496815074e3e3d183fe2c7fcea2109ad67b74084c254481f87b64e04e9a471"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:56a94ab1d12af982b55ca96c6853db6ac85505e820d9458ac76364c1998972f4"}, + {file = "pyzmq-25.0.2.tar.gz", hash = "sha256:6b8c1bbb70e868dc88801aa532cae6bd4e3b5233784692b786f17ad2962e5149"}, +] + +[package.dependencies] +cffi = {version = "*", markers = "implementation_name == \"pypy\""} + [[package]] name = "quaternionic" version = "1.0.6" @@ -2298,6 +2653,24 @@ trimesh = {version = ">=3.11.2", extras = ["easy"]} [package.extras] testing = ["pytest", "pytest-cov", "setuptools"] +[[package]] +name = "zerorpc" +version = "0.6.3" +description = "zerorpc is a flexible RPC based on zeromq." +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "zerorpc-0.6.3-py3-none-any.whl", hash = "sha256:0a91ab78db756aec25d5c7c326f8d0dcdf852144acba2cced2cfb2e736c51628"}, + {file = "zerorpc-0.6.3.tar.gz", hash = "sha256:d2ee247a566fc703f29c277d767f6f61f1e12f76d0402faea4bd815f32cbf37f"}, +] + +[package.dependencies] +future = "*" +gevent = ">=1.1" +msgpack = ">=0.5.2" +pyzmq = ">=13.1.0" + [[package]] name = "zipp" version = "3.12.0" @@ -2314,7 +2687,74 @@ files = [ docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] testing = ["flake8 (<5)", "func-timeout", "jaraco.functools", "jaraco.itertools", "more-itertools", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=1.3)", "pytest-flake8", "pytest-mypy (>=0.9.1)"] +[[package]] +name = "zope-event" +version = "4.6" +description = "Very basic event publishing system" +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "zope.event-4.6-py2.py3-none-any.whl", hash = "sha256:73d9e3ef750cca14816a9c322c7250b0d7c9dbc337df5d1b807ff8d3d0b9e97c"}, + {file = "zope.event-4.6.tar.gz", hash = "sha256:81d98813046fc86cc4136e3698fee628a3282f9c320db18658c21749235fce80"}, +] + +[package.dependencies] +setuptools = "*" + +[package.extras] +docs = ["Sphinx"] +test = ["zope.testrunner"] + +[[package]] +name = "zope-interface" +version = "6.0" +description = "Interfaces for Python" +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "zope.interface-6.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:f299c020c6679cb389814a3b81200fe55d428012c5e76da7e722491f5d205990"}, + {file = "zope.interface-6.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ee4b43f35f5dc15e1fec55ccb53c130adb1d11e8ad8263d68b1284b66a04190d"}, + {file = "zope.interface-6.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5a158846d0fca0a908c1afb281ddba88744d403f2550dc34405c3691769cdd85"}, + {file = "zope.interface-6.0-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f72f23bab1848edb7472309e9898603141644faec9fd57a823ea6b4d1c4c8995"}, + {file = "zope.interface-6.0-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:48f4d38cf4b462e75fac78b6f11ad47b06b1c568eb59896db5b6ec1094eb467f"}, + {file = "zope.interface-6.0-cp310-cp310-win_amd64.whl", hash = "sha256:87b690bbee9876163210fd3f500ee59f5803e4a6607d1b1238833b8885ebd410"}, + {file = "zope.interface-6.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:f2363e5fd81afb650085c6686f2ee3706975c54f331b426800b53531191fdf28"}, + {file = "zope.interface-6.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:af169ba897692e9cd984a81cb0f02e46dacdc07d6cf9fd5c91e81f8efaf93d52"}, + {file = "zope.interface-6.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fa90bac61c9dc3e1a563e5babb3fd2c0c1c80567e815442ddbe561eadc803b30"}, + {file = "zope.interface-6.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:89086c9d3490a0f265a3c4b794037a84541ff5ffa28bb9c24cc9f66566968464"}, + {file = "zope.interface-6.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:809fe3bf1a91393abc7e92d607976bbb8586512913a79f2bf7d7ec15bd8ea518"}, + {file = "zope.interface-6.0-cp311-cp311-win_amd64.whl", hash = "sha256:0ec9653825f837fbddc4e4b603d90269b501486c11800d7c761eee7ce46d1bbb"}, + {file = "zope.interface-6.0-cp37-cp37m-macosx_10_15_x86_64.whl", hash = "sha256:790c1d9d8f9c92819c31ea660cd43c3d5451df1df61e2e814a6f99cebb292788"}, + {file = "zope.interface-6.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b39b8711578dcfd45fc0140993403b8a81e879ec25d53189f3faa1f006087dca"}, + {file = "zope.interface-6.0-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:eba51599370c87088d8882ab74f637de0c4f04a6d08a312dce49368ba9ed5c2a"}, + {file = "zope.interface-6.0-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6ee934f023f875ec2cfd2b05a937bd817efcc6c4c3f55c5778cbf78e58362ddc"}, + {file = "zope.interface-6.0-cp37-cp37m-win_amd64.whl", hash = "sha256:042f2381118b093714081fd82c98e3b189b68db38ee7d35b63c327c470ef8373"}, + {file = "zope.interface-6.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:dfbbbf0809a3606046a41f8561c3eada9db811be94138f42d9135a5c47e75f6f"}, + {file = "zope.interface-6.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:424d23b97fa1542d7be882eae0c0fc3d6827784105264a8169a26ce16db260d8"}, + {file = "zope.interface-6.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e538f2d4a6ffb6edfb303ce70ae7e88629ac6e5581870e66c306d9ad7b564a58"}, + {file = "zope.interface-6.0-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:12175ca6b4db7621aedd7c30aa7cfa0a2d65ea3a0105393e05482d7a2d367446"}, + {file = "zope.interface-6.0-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4c3d7dfd897a588ec27e391edbe3dd320a03684457470415870254e714126b1f"}, + {file = "zope.interface-6.0-cp38-cp38-win_amd64.whl", hash = "sha256:b3f543ae9d3408549a9900720f18c0194ac0fe810cecda2a584fd4dca2eb3bb8"}, + {file = "zope.interface-6.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:d0583b75f2e70ec93f100931660328965bb9ff65ae54695fb3fa0a1255daa6f2"}, + {file = "zope.interface-6.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:23ac41d52fd15dd8be77e3257bc51bbb82469cf7f5e9a30b75e903e21439d16c"}, + {file = "zope.interface-6.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:99856d6c98a326abbcc2363827e16bd6044f70f2ef42f453c0bd5440c4ce24e5"}, + {file = "zope.interface-6.0-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1592f68ae11e557b9ff2bc96ac8fc30b187e77c45a3c9cd876e3368c53dc5ba8"}, + {file = "zope.interface-6.0-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4407b1435572e3e1610797c9203ad2753666c62883b921318c5403fb7139dec2"}, + {file = "zope.interface-6.0-cp39-cp39-win_amd64.whl", hash = "sha256:5171eb073474a5038321409a630904fd61f12dd1856dd7e9d19cd6fe092cbbc5"}, + {file = "zope.interface-6.0.tar.gz", hash = "sha256:aab584725afd10c710b8f1e6e208dbee2d0ad009f57d674cb9d1b3964037275d"}, +] + +[package.dependencies] +setuptools = "*" + +[package.extras] +docs = ["Sphinx", "repoze.sphinx.autointerface"] +test = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] +testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] + [metadata] lock-version = "2.0" python-versions = "^3.8,<3.9" -content-hash = "002bd23f1420edeeef967f1ec6346b723a8def79dd0313eabf97287f542fd02e" +content-hash = "ed443ff98b3f0dbbeef543e2fa74358d4b27a91cb03d31c8c4b3b67b073605af" From dadd04a90ecf61eef2c75a2e8a7653b12206cd72 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 3 Apr 2023 09:41:50 +0200 Subject: [PATCH 04/26] Structural improvements in IsaacgymWrapper, now using actor dataclass. Also includes drawing of rollouts. --- conf/config_panda_push.yaml | 4 +- examples/panda_push_server.py | 20 +- mppiisaac/planner/isaacgym_wrapper.py | 343 ++++++++++++-------------- mppiisaac/planner/mppi_isaac.py | 8 +- 4 files changed, 170 insertions(+), 205 deletions(-) diff --git a/conf/config_panda_push.yaml b/conf/config_panda_push.yaml index f921701..493364e 100644 --- a/conf/config_panda_push.yaml +++ b/conf/config_panda_push.yaml @@ -1,12 +1,12 @@ defaults: - mppi: panda_push - - isaacgym: slow + - isaacgym: normal goal: [0.5, 0.4, 0.7] render: true n_steps: 10000 urdf_file: "panda_isaac/robots/franka_panda_stick.urdf" -ee_link: "panda_link7" +ee_link: "panda_ee_tip" fix_base: true flip_visual: true disable_gravity: true diff --git a/examples/panda_push_server.py b/examples/panda_push_server.py index 09df603..2d2770b 100644 --- a/examples/panda_push_server.py +++ b/examples/panda_push_server.py @@ -31,7 +31,6 @@ def bytes_to_torch(b: bytes) -> torch.Tensor: def run_panda_robot(cfg: ExampleConfig): # Note: Workaround to trigger the dataclasses __post_init__ method cfg = OmegaConf.to_object(cfg) - cfg.isaacgym.dt=0.05 sim = IsaacGymWrapper( cfg.isaacgym, @@ -62,13 +61,12 @@ def run_panda_robot(cfg: ExampleConfig): "mass": 0.250, "fixed": False, "handle": None, - "color": [0.2, 0.2, 1.0] + "color": [0.2, 0.2, 1.0], + "friction": 0.2 } ] - for a in additions: - sim.env_cfg.append(a) - sim.stop_sim() - sim.start_sim() + + sim.add_to_envs(additions) sim.gym.viewer_camera_look_at( sim.viewer, None, gymapi.Vec3(1.5, 2, 3), gymapi.Vec3(1.5, 0, 0) @@ -81,7 +79,7 @@ def run_panda_robot(cfg: ExampleConfig): planner.add_to_env(additions) pi = 3.14 - sim.set_dof_state_tensor(torch.tensor([0, 0, 0, 0, 0, 0, -pi/2, 0, 0, 0, pi/2, 0, pi/4, 0], device="cuda:0")) + sim.set_dof_state_tensor(torch.tensor([0, 0, 0, 0, 0, 0, -pi * 0.65, 0, 0, 0, pi/2, 0, 0, 0], device="cuda:0")) for _ in range(cfg.n_steps): t = time.time() @@ -91,22 +89,28 @@ def run_panda_robot(cfg: ExampleConfig): torch_to_bytes(sim.root_state[0]), torch_to_bytes(sim.rigid_body_state[0]), ) + sim.gym.clear_lines(sim.viewer) # Compute action action = bytes_to_torch(planner.command()) if torch.any(torch.isnan(action)): + print("nan action") action = torch.zeros_like(action) # Apply action sim.set_dof_velocity_target_tensor(action) + # Visualize samples + rollouts = bytes_to_torch(planner.get_rollouts()) + sim.draw_lines(rollouts) + # Step simulator sim.step() # Print error of block pos = sim.root_state[0, -1][:2].cpu().numpy() goal = np.array([0.5, 0]) - print(f"L2: {np.linalg.norm(pos - goal)} FPS: {1/(time.time() - t)}") + print(f"L2: {np.linalg.norm(pos - goal)} FPS: {1/(time.time() - t)} RT-factor: {cfg.isaacgym.dt/(time.time() - t)}") return {} diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 735b266..0c9cc96 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -1,8 +1,11 @@ from isaacgym import gymapi from isaacgym import gymtorch -from dataclasses import dataclass +from dataclasses import dataclass, field import torch import numpy as np +from enum import Enum +from typing import List, Optional + import pathlib @@ -41,6 +44,28 @@ def parse_isaacgym_config(cfg: IsaacGymConfig) -> gymapi.SimParams: return sim_params +class SupportedActorTypes(Enum): + Axis = 1 + Robot = 2 + Sphere = 3 + Box = 4 + + +@dataclass +class ActorWrapper: + type: SupportedActorTypes + name: str + init_pos: List[float] = field(default_factory=lambda: [0, 0, 0]) + init_ori: List[float] = field(default_factory=lambda: [0, 0, 0, 1]) + size: List[float] = field(default_factory=lambda: [0.1, 0.1, 0.1]) + mass: float = 1.0 # kg + color: List[float] = field(default_factory=lambda: [1.0, 1.0, 1.0]) + fixed: bool = False + collision: bool = True + friction: float = 0.8 + handle: Optional[int] = None + + class IsaacGymWrapper: def __init__( self, @@ -51,18 +76,38 @@ def __init__( num_envs: int = 0, ee_link: str = None, disable_gravity: bool = False, - viewer: bool = False + viewer: bool = False, ): self.gym = gymapi.acquire_gym() - # Keep track of env idxs. Everytime an actor get added append with a tuple of (idx, type, name) self.env_cfg = [ - {"type": "axis", "name": "x", "handle": None, "fixed": True}, - {"type": "axis", "name": "y", "handle": None, "fixed": True}, - {"type": "robot", "name": "main_robot", "handle": None}, + { + "type": "box", + "name": "x", + "handle": None, + "fixed": True, + "size": [0.5, 0.05, 0.01], + "init_pos": [0, 0.25, 0.01], + "color": [1, 0.0, 0.2], + "collision": False + }, + { + "type": "box", + "name": "y", + "handle": None, + "fixed": True, + "size": [0.05, 0.5, 0.01], + "init_pos": [0.25, 0, 0.01], + "color": [0.0, 1, 0.2], + "collision": False + }, + {"type": "robot", "name": "main_robot", "handle": None, "fixed": True}, ] + self.env_cfg = [ActorWrapper(**a) for a in self.env_cfg] + self.cfg = cfg - if viewer: self.cfg.viewer = viewer + if viewer: + self.cfg.viewer = viewer self.num_envs = num_envs self._urdf_file = urdf_file self._fix_base = fix_base @@ -87,17 +132,52 @@ def start_sim(self): self.add_ground_plane() - asset_file = "urdf/" + self._urdf_file - print(asset_file) - self._robot_asset = self.load_robot_asset_from_urdf( - asset_file=asset_file, - asset_root=f"{file_path}/../../assets", - fix_base_link=self._fix_base, - flip_visual_attachments=self._flip_visual, - disable_gravity=self._disable_gravity, - ) + # Load / create assets for all actors in the envs + self.env_actor_assets = [] + for actor_cfg in self.env_cfg: + asset_options = gymapi.AssetOptions() + asset_options.fix_base_link = actor_cfg.fixed + if actor_cfg.type == "robot": + asset_file = "urdf/" + self._urdf_file + asset_options.flip_visual_attachments = self._flip_visual + asset_options.disable_gravity = self._disable_gravity + actor_asset = self.gym.load_asset( + sim=self.sim, + rootpath=f"{file_path}/../../assets", + filename=asset_file, + options=asset_options, + ) + elif actor_cfg.type == "box": + actor_asset = self.gym.create_box( + sim=self.sim, + width=actor_cfg.size[0], + height=actor_cfg.size[1], + depth=actor_cfg.size[2], + options=asset_options, + ) + elif actor_cfg.type == "sphere": + actor_asset = self.gym.create_sphere( + sim=self.sim, + radius=actor_cfg.size[0], + options=asset_options, + ) + else: + raise NotImplementedError(f"actor asset of type {actor_cfg.type} is not yet implemented!") + self.env_actor_assets.append(actor_asset) + + # Create envs and fill with assets + self.envs = [] + for env_idx in range(self.num_envs): + env = self.gym.create_env( + self.sim, + gymapi.Vec3(-self.cfg.spacing, 0.0, -self.cfg.spacing), + gymapi.Vec3(self.cfg.spacing, self.cfg.spacing, self.cfg.spacing), + int(self.num_envs**0.5), + ) - self.envs = [self.create_env(i) for i in range(self.num_envs)] + for actor_asset, actor_cfg in zip(self.env_actor_assets, self.env_cfg): + self.create_actor(env, env_idx, actor_asset, actor_cfg) + self.envs.append(env) self.gym.prepare_sim(self.sim) @@ -116,10 +196,16 @@ def start_sim(self): self.gym.acquire_net_contact_force_tensor(self.sim) ) + # save buffer of ee states + if self._ee_link: + self.ee_positions_buffer = [] + # helpfull slices self.robot_positions = self.root_state[:, 2, 0:3] # [x, y, z] self.robot_velocities = self.root_state[:, 2, 7:10] # [x, y, z] self.obstacle_positions = self.root_state[:, 3:, 0:3] # [x, y, z] + if self._ee_link: + self.ee_positions = self.rigid_body_state[:, self.robot_rigid_body_ee_idx, 0:3] # [x, y, z] self.gym.refresh_actor_root_state_tensor(self.sim) self.gym.refresh_dof_state_tensor(self.sim) @@ -130,170 +216,48 @@ def stop_sim(self): if self.viewer: self.gym.destroy_viewer(self.viewer) self.gym.destroy_sim(self.sim) + + def add_to_envs(self, additions): + for a in additions: + self.env_cfg.append(ActorWrapper(**a)) + self.stop_sim() + self.start_sim() - def create_env(self, env_idx): - env = self.gym.create_env( - self.sim, - gymapi.Vec3(-self.cfg.spacing, 0.0, -self.cfg.spacing), - gymapi.Vec3(self.cfg.spacing, self.cfg.spacing, self.cfg.spacing), - int(self.num_envs**0.5), - ) - - x_axis = self.add_box( - env, - env_idx=-2, - name=self.env_cfg[0]["name"], - whd=(0.5, 0.05, 0.01), - pos=gymapi.Vec3(0.25, 0, 0.01), - color=gymapi.Vec3(1, 0.0, 0.2), - ) - self.env_cfg[0]["handle"] = x_axis - - y_axis = self.add_box( - env=env, - env_idx=-2, - name=self.env_cfg[1]["name"], - whd=(0.05, 0.5, 0.01), - pos=gymapi.Vec3(0, 0.25, 0.01), - color=gymapi.Vec3(0.0, 1, 0.2), - ) - self.env_cfg[1]["handle"] = y_axis - - robot_init_pose = gymapi.Transform() - robot_init_pose.p = gymapi.Vec3(0.0, 0.0, 0.05) - - robot_handle = self.gym.create_actor( - env=env, - asset=self._robot_asset, - pose=robot_init_pose, - name=self.env_cfg[2]["name"], - group=env_idx, - ) - self.env_cfg[2]["handle"] = robot_handle - - if self._ee_link: - self.robot_rigid_body_ee_idx = self.gym.find_actor_rigid_body_index( - env, robot_handle, self._ee_link, gymapi.IndexDomain.DOMAIN_ENV - ) - - # Update point bot dynamics / control mode - props = self.gym.get_asset_dof_properties(self._robot_asset) - props["driveMode"].fill(gymapi.DOF_MODE_VEL) - props["stiffness"].fill(0.0) - props["damping"].fill(1e7) - self.gym.set_actor_dof_properties(env, robot_handle, props) - - for obst_cfg in self.env_cfg[3:]: - if "init_pos" in obst_cfg.keys(): - init_pos = gymapi.Vec3(*obst_cfg["init_pos"]) - else: - init_pos=gymapi.Vec3(0, 0, -20) - - if obst_cfg["type"] == "sphere": - # add spheres - handle = self.add_sphere( - env=env, - env_idx=env_idx, - name=obst_cfg["name"], - radius=obst_cfg["size"][0], - pos=init_pos, - color=gymapi.Vec3(1.0, 1.0, 1.0), - ) - elif obst_cfg["type"] == "box": - # add spheres - if "mass" in obst_cfg.keys(): - mass = obst_cfg['mass'] - else: - mass = 1.0 - if "mass" in obst_cfg.keys(): - color = gymapi.Vec3(*obst_cfg['color']) - else: - color = gymapi.Vec3(1.0, 1.0, 1.0) - handle = self.add_box( - env=env, - env_idx=env_idx, - name=obst_cfg["name"], - whd=obst_cfg["size"], - pos=init_pos, - color=color, - fixed=obst_cfg["fixed"], - mass=mass - ) - else: - raise NotImplementedError( - f"obstacles of type {obst_cfg['type']} are not supported!" - ) - obst_cfg["handle"] = handle - return env - - def add_box( - self, - env, - env_idx: int, - name: str, - whd: list, - pos: gymapi.Vec3, - color: gymapi.Vec3, - fixed: bool = True, - mass: float = 1.0, - ) -> int: - asset_options_objects = gymapi.AssetOptions() - asset_options_objects.fix_base_link = fixed - object_asset = self.gym.create_box( - sim=self.sim, - width=whd[0], - height=whd[1], - depth=whd[2], - options=asset_options_objects, - ) - + def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: pose = gymapi.Transform() - pose.p = pos + pose.p = gymapi.Vec3(*actor.init_pos) + pose.r = gymapi.Quat(*actor.init_ori) handle = self.gym.create_actor( env=env, - asset=object_asset, + asset=asset, pose=pose, - name=name, - group=env_idx, + name=actor.name, + group=env_idx if actor.collision else -1, ) self.gym.set_rigid_body_color( - env, handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, color + env, handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, gymapi.Vec3(*actor.color) ) props = self.gym.get_actor_rigid_body_properties(env, handle) - props[0].mass = mass + props[0].mass = actor.mass self.gym.set_actor_rigid_body_properties(env, handle, props) - return handle + props = self.gym.get_actor_rigid_shape_properties(env, handle) + props[0].friction = actor.friction + props[0].torsion_friction = actor.friction + props[0].rolling_friction = actor.friction + self.gym.set_actor_rigid_shape_properties(env, handle, props) + + if actor.type == "robot": + if self._ee_link: + self.robot_rigid_body_ee_idx = self.gym.find_actor_rigid_body_index( + env, handle, self._ee_link, gymapi.IndexDomain.DOMAIN_ENV + ) - def add_sphere( - self, - env, - env_idx: int, - name: str, - radius: float, - pos: gymapi.Vec3, - color: gymapi.Vec3, - fixed: bool = True, - ) -> int: - asset_options_objects = gymapi.AssetOptions() - asset_options_objects.fix_base_link = fixed - object_asset = self.gym.create_sphere( - sim=self.sim, - radius=radius, - options=asset_options_objects, - ) + props = self.gym.get_asset_dof_properties(asset) + props["driveMode"].fill(gymapi.DOF_MODE_VEL) + props["stiffness"].fill(0.0) + props["damping"].fill(1e7) + self.gym.set_actor_dof_properties(env, handle, props) - pose = gymapi.Transform() - pose.p = pos - handle = self.gym.create_actor( - env=env, - asset=object_asset, - pose=pose, - name=name, - group=env_idx, - ) - self.gym.set_rigid_body_color( - env, handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, color - ) return handle def add_ground_plane(self): @@ -305,21 +269,6 @@ def add_ground_plane(self): plane_params.restitution = 0 self.gym.add_ground(self.sim, plane_params) - def load_robot_asset_from_urdf( - self, - asset_file, - asset_root=f"{file_path}/../../assets", - fix_base_link=False, - flip_visual_attachments=False, - disable_gravity=False, - ): - asset_options = gymapi.AssetOptions() - asset_options.fix_base_link = fix_base_link - asset_options.armature = 0.01 - asset_options.flip_visual_attachments = flip_visual_attachments - asset_options.disable_gravity = disable_gravity - return self.gym.load_asset(self.sim, asset_root, asset_file, asset_options) - def set_dof_state_tensor(self, state): self.gym.set_dof_state_tensor(self.sim, gymtorch.unwrap_tensor(state)) @@ -336,7 +285,10 @@ def step(self): if self.viewer is not None: self.gym.step_graphics(self.sim) self.gym.draw_viewer(self.viewer, self.sim, False) - self.gym.sync_frame_time(self.sim) + # self.gym.sync_frame_time(self.sim) + + if self._ee_link: + self.ee_positions_buffer.append(self.ee_positions.clone()) def set_root_state_tensor_by_actor_idx(self, state_tensor, idx): for i in range(self.num_envs): @@ -380,16 +332,16 @@ def update_root_state_tensor_by_obstacles(self, obstacles): pos, vel, o_type, o_size = obst name = f"{o_type}{i}" try: - obst_idx = [actor["name"] for actor in self.env_cfg].index(name) + obst_idx = [idx for idx, actor in enumerate(self.env_cfg) if actor.name == name] except: self.env_cfg.append( - { + ActorWrapper({ "type": o_type, "name": name, "handle": None, "size": o_size, "fixed": True, - } + }) ) env_cfg_changed = True continue @@ -400,10 +352,10 @@ def update_root_state_tensor_by_obstacles(self, obstacles): # Note: reset simulator if size changed, because this cannot be done at runtime. if not all( - [a == b for a, b in zip(o_size, self.env_cfg[obst_idx]["size"])] + [a == b for a, b in zip(o_size, self.env_cfg[obst_idx].size)] ): env_cfg_changed = True - self.env_cfg[obst_idx]["size"] = o_size + self.env_cfg[obst_idx].size = o_size for j, env in enumerate(self.envs): self.root_state[j, obst_idx] = obst_state @@ -419,9 +371,18 @@ def update_root_state_tensor_by_obstacles(self, obstacles): def update_root_state_tensor_by_obstacles_tensor(self, obst_tensor): for i, o_tensor in enumerate(obst_tensor): - if self.env_cfg[i + 3]['fixed']: continue + if self.env_cfg[i + 3].fixed: + continue self.root_state[:, i + 3] = o_tensor.repeat(self.num_envs, 1) self.gym.set_actor_root_state_tensor( self.sim, gymtorch.unwrap_tensor(self.root_state) ) + + def draw_lines(self, lines, env_idx=0): + # convert list of vertices into line segments + line_segments = torch.concat((lines[:-1], lines[1:]), axis=-1).flatten(end_dim=-2).cpu().numpy().astype(np.float32) + num_lines = line_segments.shape[0] + colors = np.zeros((num_lines,3), dtype=np.float32) + colors[:, 1] = 255 + self.gym.add_lines(self.viewer, self.envs[env_idx], num_lines, line_segments, colors) \ No newline at end of file diff --git a/mppiisaac/planner/mppi_isaac.py b/mppiisaac/planner/mppi_isaac.py index c138604..2c8fae8 100644 --- a/mppiisaac/planner/mppi_isaac.py +++ b/mppiisaac/planner/mppi_isaac.py @@ -148,6 +148,7 @@ def compute_action(self, q, qdot, obst=None, obst_tensor=None): def reset_rollout_sim( self, dof_state_tensor, root_state_tensor, rigid_body_state_tensor ): + self.sim.ee_positions_buffer = [] self.sim.dof_state[:] = bytes_to_torch(dof_state_tensor) self.sim.root_state[:] = bytes_to_torch(root_state_tensor) self.sim.rigid_body_state[:] = bytes_to_torch(rigid_body_state_tensor) @@ -159,9 +160,8 @@ def command(self): return torch_to_bytes(self.mppi.command(self.state_place_holder)) def add_to_env(self, env_cfg_additions): - for addition in env_cfg_additions: - self.sim.env_cfg.append(addition) + self.sim.add_to_envs(env_cfg_additions) - self.sim.stop_sim() - self.sim.start_sim() + def get_rollouts(self): + return torch_to_bytes(torch.stack(self.sim.ee_positions_buffer)) From 296c6b1c8fa0e074d08965016f6a1ea64a075916 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 3 Apr 2023 11:37:40 +0200 Subject: [PATCH 05/26] Fixes init_pos examples by adding to conf. Tested all examples. --- conf/config_boxer_robot.yaml | 1 + conf/config_heijn_robot.yaml | 1 + conf/config_point_robot.yaml | 1 + conf/mppi/heijn.yaml | 4 ++-- conf/mppi/jackal.yaml | 8 ++++---- mppiisaac/planner/isaacgym_wrapper.py | 14 +++++++++----- mppiisaac/planner/mppi_isaac.py | 1 + mppiisaac/priors/fabrics_panda.py | 11 +++++++---- mppiisaac/priors/fabrics_point.py | 15 +++++++-------- mppiisaac/utils/config_store.py | 5 +++-- 10 files changed, 36 insertions(+), 25 deletions(-) diff --git a/conf/config_boxer_robot.yaml b/conf/config_boxer_robot.yaml index 9fe96d8..d918fe5 100644 --- a/conf/config_boxer_robot.yaml +++ b/conf/config_boxer_robot.yaml @@ -3,6 +3,7 @@ defaults: - isaacgym: normal goal: [2.0, 2.0] +initial_position: [0.0, 0.0, 0.05] render: true n_steps: 1000 urdf_file: "boxer/boxer.urdf" diff --git a/conf/config_heijn_robot.yaml b/conf/config_heijn_robot.yaml index 13445b9..8f451b5 100644 --- a/conf/config_heijn_robot.yaml +++ b/conf/config_heijn_robot.yaml @@ -3,6 +3,7 @@ defaults: - isaacgym: normal goal: [2.0, 2.0] +initial_position: [0.0, 0.0, 0.05] render: true n_steps: 1000 urdf_file: "heijn/heijn.urdf" diff --git a/conf/config_point_robot.yaml b/conf/config_point_robot.yaml index 64e1487..8fcaec8 100644 --- a/conf/config_point_robot.yaml +++ b/conf/config_point_robot.yaml @@ -3,6 +3,7 @@ defaults: - isaacgym: normal goal: [2.0, 2.0] +initial_position: [0.0, 0.0, 0.05] render: true n_steps: 1000 urdf_file: "point_robot.urdf" diff --git a/conf/mppi/heijn.yaml b/conf/mppi/heijn.yaml index 63f46e0..e703518 100644 --- a/conf/mppi/heijn.yaml +++ b/conf/mppi/heijn.yaml @@ -7,8 +7,8 @@ num_samples: 100 horizon: 20 # At least 12 for Halton Sampling device: "cuda:0" lambda_: 0.1 -u_min: -1.5 -u_max: 1.5 +u_min: [-1.5] +u_max: [1.5] noise_sigma: [[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]] update_cov: False rollout_var_discount: 0.95 diff --git a/conf/mppi/jackal.yaml b/conf/mppi/jackal.yaml index c94d5de..78f325a 100644 --- a/conf/mppi/jackal.yaml +++ b/conf/mppi/jackal.yaml @@ -6,10 +6,10 @@ sampling_method: "halton" # halton, random num_samples: 100 horizon: 20 # At least 12 for Halton Sampling device: "cuda:0" -lambda_: 0.01 -u_min: -1.5 -u_max: 1.5 -noise_sigma: [[1., 0.], [0., 1.]] +lambda_: 0.05 +u_min: [-1.5] +u_max: [1.5] +noise_sigma: [[10., 0.], [0., 10.]] update_cov: False rollout_var_discount: 0.95 sample_null_action: True diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 0c9cc96..c238582 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -75,6 +75,7 @@ def __init__( flip_visual: bool, num_envs: int = 0, ee_link: str = None, + robot_init_pos: List[float] = [0.0, 0.0, 0.0], disable_gravity: bool = False, viewer: bool = False, ): @@ -87,7 +88,7 @@ def __init__( "handle": None, "fixed": True, "size": [0.5, 0.05, 0.01], - "init_pos": [0, 0.25, 0.01], + "init_pos": [0.25, 0.0, 0.01], "color": [1, 0.0, 0.2], "collision": False }, @@ -97,11 +98,11 @@ def __init__( "handle": None, "fixed": True, "size": [0.05, 0.5, 0.01], - "init_pos": [0.25, 0, 0.01], + "init_pos": [0.0, 0.25, 0.01], "color": [0.0, 1, 0.2], "collision": False }, - {"type": "robot", "name": "main_robot", "handle": None, "fixed": True}, + {"type": "robot", "name": "main_robot", "handle": None, "fixed": fix_base, "init_pos": robot_init_pos}, ] self.env_cfg = [ActorWrapper(**a) for a in self.env_cfg] @@ -298,6 +299,9 @@ def save_root_state(self): self.saved_root_state = self.root_state.clone() def reset_root_state(self): + if self._ee_link: + self.ee_positions_buffer = [] + if self.saved_root_state is not None: self.gym.set_actor_root_state_tensor( self.sim, gymtorch.unwrap_tensor(self.saved_root_state) @@ -332,10 +336,10 @@ def update_root_state_tensor_by_obstacles(self, obstacles): pos, vel, o_type, o_size = obst name = f"{o_type}{i}" try: - obst_idx = [idx for idx, actor in enumerate(self.env_cfg) if actor.name == name] + obst_idx = [idx for idx, actor in enumerate(self.env_cfg) if actor.name == name][0] except: self.env_cfg.append( - ActorWrapper({ + ActorWrapper(**{ "type": o_type, "name": name, "handle": None, diff --git a/mppiisaac/planner/mppi_isaac.py b/mppiisaac/planner/mppi_isaac.py index 2c8fae8..a8fbb7f 100644 --- a/mppiisaac/planner/mppi_isaac.py +++ b/mppiisaac/planner/mppi_isaac.py @@ -36,6 +36,7 @@ def __init__(self, cfg, objective: Callable, prior: Optional[Callable] = None): cfg.urdf_file, cfg.fix_base, cfg.flip_visual, + robot_init_pos=cfg.initial_position, num_envs=cfg.mppi.num_samples, ee_link=cfg.ee_link, disable_gravity=cfg.disable_gravity, diff --git a/mppiisaac/priors/fabrics_panda.py b/mppiisaac/priors/fabrics_panda.py index 29bd9cc..d7ae849 100644 --- a/mppiisaac/priors/fabrics_panda.py +++ b/mppiisaac/priors/fabrics_panda.py @@ -54,8 +54,8 @@ def compute_command(self, sim): for i in range(self.max_num_obstacles): if i < len(obst_positions): x_obsts.append(obst_positions[i]) - if 'type' in sim.env_cfg[i + 3].keys() and sim.env_cfg[i+3]['type'] == 'sphere': - radius_obsts.append(sim.env_cfg[i + 3]["size"][0]) + if sim.env_cfg[i+3].type == 'sphere': + radius_obsts.append(sim.env_cfg[i + 3].size[0]) else: radius_obsts.append(0.2) else: @@ -143,9 +143,12 @@ def test(cfg: ExampleConfig): cfg.fix_base, cfg.flip_visual, num_envs=1, + robot_init_pos=cfg.initial_position, + ee_link=cfg.ee_link, + disable_gravity=cfg.disable_gravity, ) - sim.env_cfg.append( + sim.add_to_envs([ { "type": "sphere", "name": "sphere0", @@ -153,7 +156,7 @@ def test(cfg: ExampleConfig): "size": [0.1], "fixed": True, } - ) + ]) sim.stop_sim() sim.start_sim() diff --git a/mppiisaac/priors/fabrics_point.py b/mppiisaac/priors/fabrics_point.py index 779888e..35c30dc 100644 --- a/mppiisaac/priors/fabrics_point.py +++ b/mppiisaac/priors/fabrics_point.py @@ -35,8 +35,8 @@ def compute_command(self, sim): for i in range(self.max_num_obstacles): if i < len(obst_positions): x_obsts.append(obst_positions[i][:2]) - if 'type' in sim.env_cfg[i + 3].keys() and sim.env_cfg[i+3]['type'] == 'sphere': - radius_obsts.append(sim.env_cfg[i + 3]["size"][0]) + if sim.env_cfg[i+3].type == 'sphere': + radius_obsts.append(sim.env_cfg[i + 3].size[0]) else: radius_obsts.append(0.2) else: @@ -123,24 +123,23 @@ def test(cfg: ExampleConfig): cfg.fix_base, cfg.flip_visual, num_envs=1, + robot_init_pos=cfg.initial_position, + disable_gravity=cfg.disable_gravity, ) - sim.env_cfg.append( + sim.add_to_envs([ { "type": "sphere", "name": "sphere0", "handle": None, "size": [0.2], "fixed": True, - } + "init_pos": [1.0, 1.0, 0.0] + }] ) sim.stop_sim() sim.start_sim() - sim.update_root_state_tensor_by_obstacles_tensor( - torch.tensor([[1.0, 1.0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0]], device="cuda:0") - ) - sim.gym.viewer_camera_look_at( sim.viewer, None, gymapi.Vec3(1.5, 6, 8), gymapi.Vec3(1.5, 0, 0) ) diff --git a/mppiisaac/utils/config_store.py b/mppiisaac/utils/config_store.py index 3c2e3c5..44c858f 100644 --- a/mppiisaac/utils/config_store.py +++ b/mppiisaac/utils/config_store.py @@ -1,6 +1,6 @@ -from dataclasses import dataclass +from dataclasses import dataclass, field from mppiisaac.planner.mppi import MPPIConfig -from mppiisaac.planner.isaacgym_wrapper import IsaacGymConfig +from mppiisaac.planner.isaacgym_wrapper import IsaacGymConfig, ActorWrapper from hydra.core.config_store import ConfigStore from typing import List, Optional @@ -17,6 +17,7 @@ class ExampleConfig: urdf_file: str fix_base: bool flip_visual: bool + initial_position: List[float] = field(default_factory=lambda: [0, 0, 0]) disable_gravity: bool = False differential_drive: bool = False wheel_base: float = 0 From ee16de9f20af3584494f389c8ac4f04a470c8529 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Fri, 14 Apr 2023 13:53:52 +0200 Subject: [PATCH 06/26] Supporting multiple robot, including differential drive ones --- conf/actors/jackal.yaml | 12 ++ conf/actors/panda.yaml | 8 ++ conf/actors/xaxis.yaml | 8 ++ conf/actors/yaxis.yaml | 8 ++ conf/config_jackal_robot.yaml | 10 +- conf/config_multi_jackal.yaml | 11 ++ conf/config_panda.yaml | 10 +- conf/mppi/multi-jackal.yaml | 17 +++ examples/jackal_robot.py | 6 +- examples/multi_jackal.py | 128 ++++++++++++++++++ examples/panda_robot.py | 1 + mppiisaac/planner/isaacgym_wrapper.py | 187 ++++++++++++++++++-------- mppiisaac/planner/mppi_isaac.py | 82 +++-------- mppiisaac/utils/config_store.py | 13 +- 14 files changed, 353 insertions(+), 148 deletions(-) create mode 100644 conf/actors/jackal.yaml create mode 100644 conf/actors/panda.yaml create mode 100644 conf/actors/xaxis.yaml create mode 100644 conf/actors/yaxis.yaml create mode 100644 conf/config_multi_jackal.yaml create mode 100644 conf/mppi/multi-jackal.yaml create mode 100644 examples/multi_jackal.py diff --git a/conf/actors/jackal.yaml b/conf/actors/jackal.yaml new file mode 100644 index 0000000..ee26558 --- /dev/null +++ b/conf/actors/jackal.yaml @@ -0,0 +1,12 @@ +type: robot +name: jackal +urdf_file: "jackal/jackal.urdf" +fixed: False +flip_visual: false +gravity: true +differential_drive: true +mass: 40 +wheel_radius: 0.14 +wheel_base: 0.400 +wheel_count: 4 +collision: False diff --git a/conf/actors/panda.yaml b/conf/actors/panda.yaml new file mode 100644 index 0000000..7c685f0 --- /dev/null +++ b/conf/actors/panda.yaml @@ -0,0 +1,8 @@ +type: robot +name: panda +fixed: True +init_pos: [0.0, 0.0, 0.0] +urdf_file: "panda_isaac/robots/franka_panda.urdf" +ee_link: "panda_link7" +flip_visual: true +gravity: false diff --git a/conf/actors/xaxis.yaml b/conf/actors/xaxis.yaml new file mode 100644 index 0000000..19741b2 --- /dev/null +++ b/conf/actors/xaxis.yaml @@ -0,0 +1,8 @@ +type: box +name: x +handle: None +fixed: True +size: [0.5, 0.05, 0.01] +init_pos: [0.25, 0.0, 0.01] +color: [1, 0.0, 0.2] +collision: False diff --git a/conf/actors/yaxis.yaml b/conf/actors/yaxis.yaml new file mode 100644 index 0000000..9f04171 --- /dev/null +++ b/conf/actors/yaxis.yaml @@ -0,0 +1,8 @@ +type: box +name: y +handle: None +fixed: True +size: [0.05, 0.5, 0.01] +init_pos: [0.0, 0.25, 0.01] +color: [0.0, 1, 0.2] +collision: False diff --git a/conf/config_jackal_robot.yaml b/conf/config_jackal_robot.yaml index 36c61c6..94e052b 100644 --- a/conf/config_jackal_robot.yaml +++ b/conf/config_jackal_robot.yaml @@ -5,11 +5,7 @@ defaults: goal: [2.0, 2.0] render: true n_steps: 1000 -urdf_file: "jackal/jackal.urdf" -fix_base: false -flip_visual: false nx: 4 -differential_drive: true -wheel_radius: 0.14 -wheel_base: 0.400 -wheel_count: 4 + +actors: ['jackal', 'xaxis', 'yaxis'] +initial_actor_positions: [[0.0, 0.0, 0.05]] diff --git a/conf/config_multi_jackal.yaml b/conf/config_multi_jackal.yaml new file mode 100644 index 0000000..37044cb --- /dev/null +++ b/conf/config_multi_jackal.yaml @@ -0,0 +1,11 @@ +defaults: + - mppi: multi-jackal + - isaacgym: normal + +goal: [2.0, 0.0, -2.0, 0.0] +render: true +n_steps: 1000 +nx: 8 + +actors: ['jackal', 'jackal', 'xaxis', 'yaxis'] +initial_actor_positions: [[-2.0, 0.0, 0.05], [2.0, 0.0, 0.05]] diff --git a/conf/config_panda.yaml b/conf/config_panda.yaml index e91f7ef..7947cfc 100644 --- a/conf/config_panda.yaml +++ b/conf/config_panda.yaml @@ -1,13 +1,11 @@ defaults: - mppi: panda - - isaacgym: slow + - isaacgym: normal goal: [0.5, 0.4, 0.7] render: true n_steps: 1000 -urdf_file: "panda_isaac/robots/franka_panda.urdf" -ee_link: "panda_link7" -fix_base: true -flip_visual: true -disable_gravity: true +actors: ['panda', 'xaxis', 'yaxis'] +initial_actor_positions: [[0.0, 0.0, 0.0]] + nx: 14 diff --git a/conf/mppi/multi-jackal.yaml b/conf/mppi/multi-jackal.yaml new file mode 100644 index 0000000..13891a9 --- /dev/null +++ b/conf/mppi/multi-jackal.yaml @@ -0,0 +1,17 @@ +defaults: + - base_mppi + +mppi_mode: "halton-spline" # halton-spline, simple +sampling_method: "halton" # halton, random +num_samples: 100 +horizon: 20 # At least 12 for Halton Sampling +device: "cuda:0" +lambda_: 0.01 +u_min: [-1.5] +u_max: [1.5] +noise_sigma: [[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]] +update_cov: False +rollout_var_discount: 0.95 +sample_null_action: True +noise_abs_cost: False +filter_u: True diff --git a/examples/jackal_robot.py b/examples/jackal_robot.py index 42b45df..2a57bcb 100644 --- a/examples/jackal_robot.py +++ b/examples/jackal_robot.py @@ -20,9 +20,10 @@ def __init__(self, cfg, device): def compute_cost(self, sim): pos = sim.robot_positions[:, :2] - return torch.clamp( + cost = torch.clamp( torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 ) + return cost * 1.5 def initalize_environment(cfg) -> UrdfEnv: @@ -95,7 +96,7 @@ def run_jackal_robot(cfg: ExampleConfig): env = initalize_environment(cfg) planner = set_planner(cfg) - action = np.zeros(int(cfg.nx/2)) + action = np.zeros(4) ob, *_ = env.step(action) @@ -113,7 +114,6 @@ def run_jackal_robot(cfg: ExampleConfig): ob, *_, ) = env.step(action) - print(action) return {} diff --git a/examples/multi_jackal.py b/examples/multi_jackal.py new file mode 100644 index 0000000..549e83b --- /dev/null +++ b/examples/multi_jackal.py @@ -0,0 +1,128 @@ +import gym +import numpy as np +from urdfenvs.robots.jackal import JackalRobot +from urdfenvs.urdf_common.urdf_env import UrdfEnv +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import hydra +from omegaconf import OmegaConf +import os +import torch +from mpscenes.goals.static_sub_goal import StaticSubGoal + +from mppiisaac.utils.config_store import ExampleConfig + +# MPPI to navigate a simple robot to a goal position + +class Objective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + + def compute_cost(self, sim): + pos = torch.cat((sim.root_state[:, 0, 0:2], sim.root_state[:, 1, 0:2]), axis=1) + print(pos[0]) + print(self.nav_goal) + + + cost = torch.clamp( + torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 + ) + cost += -0.2*torch.linalg.norm(pos[:, :2] - pos[:, 2:], axis=1) + return cost * 1.5 + + +def initalize_environment(cfg) -> UrdfEnv: + """ + Initializes the simulation environment. + + Adds an obstacle and goal visualizaion to the environment and + steps the simulation once. + + Params + ---------- + render + Boolean toggle to set rendering on (True) or off (False). + """ + # urdf_file = os.path.dirname(os.path.abspath(__file__)) + "/../assets/urdf/" + cfg.urdf_file + robots = [ + JackalRobot(mode="vel"), + JackalRobot(mode="vel"), + ] + env: UrdfEnv = gym.make("urdf-env-v0", dt=0.02, robots=robots, render=cfg.render) + # Set the initial position and velocity of the jackal robot + print(cfg.initial_actor_positions) + env.reset(pos=np.array(cfg.initial_actor_positions)) + #goal_dict = { + # "weight": 1.0, + # "is_primary_goal": True, + # "indices": [0, 1], + # "parent_link": 0, + # "child_link": 1, + # "desired_position": cfg.goal, + # "epsilon": 0.05, + # "type": "staticSubGoal", + #} + #goal = StaticSubGoal(name="simpleGoal", content_dict=goal_dict) + # env.add_goal(goal) + return env + + +def set_planner(cfg): + """ + Initializes the mppi planner for jackal robot. + + Params + ---------- + goal_position: np.ndarray + The goal to the motion planning problem. + """ + objective = Objective(cfg, cfg.mppi.device) + planner = MPPIisaacPlanner(cfg, objective) + + return planner + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_multi_jackal") +def run_jackal_robot(cfg: ExampleConfig): + """ + Set the gym environment, the planner and run jackal robot example. + The initial zero action step is needed to initialize the sensor in the + urdf environment. + + Params + ---------- + n_steps + Total number of simulation steps. + render + Boolean toggle to set rendering on (True) or off (False). + """ + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + + env = initalize_environment(cfg) + planner = set_planner(cfg) + + action = np.zeros(8) + ob, *_ = env.step(action) + + + for _ in range(cfg.n_steps): + #Calculate action with the fabric planner, slice the states to drop Z-axis [3] information. + + #Todo fix joint with zero friction + + ob_robot0 = ob["robot_0"] + ob_robot1 = ob["robot_1"] + action = planner.compute_action( + q=list(ob_robot0["joint_state"]["position"]) + list(ob_robot1["joint_state"]["position"]), + qdot=list(ob_robot0["joint_state"]["velocity"]) + list(ob_robot1["joint_state"]["velocity"]), + ) + ( + ob, + *_, + ) = env.step(action) + return {} + + +if __name__ == "__main__": + res = run_jackal_robot() diff --git a/examples/panda_robot.py b/examples/panda_robot.py index b814ee8..3909af4 100644 --- a/examples/panda_robot.py +++ b/examples/panda_robot.py @@ -7,6 +7,7 @@ from omegaconf import OmegaConf import os import torch +import mppiisaac from mppiisaac.priors.fabrics_panda import FabricsPandaPrior from mppiisaac.utils.config_store import ExampleConfig diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index c238582..f53ebc0 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -4,7 +4,7 @@ import torch import numpy as np from enum import Enum -from typing import List, Optional +from typing import List, Optional, Any import pathlib @@ -64,57 +64,39 @@ class ActorWrapper: collision: bool = True friction: float = 0.8 handle: Optional[int] = None + flip_visual: bool = False + urdf_file: str = None + ee_link: str = None + gravity: bool = True + differential_drive: bool = False + wheel_radius: Optional[float] = None + wheel_base: Optional[float] = None + wheel_count: Optional[float] = None + left_wheel_joints: Optional[List[int]] = None + right_wheel_joints: Optional[List[int]] = None class IsaacGymWrapper: def __init__( self, cfg: IsaacGymConfig, - urdf_file: str, - fix_base: bool, - flip_visual: bool, - num_envs: int = 0, - ee_link: str = None, - robot_init_pos: List[float] = [0.0, 0.0, 0.0], - disable_gravity: bool = False, - viewer: bool = False, + actors: List[ActorWrapper], + init_positions: List[List[float]], + num_envs: int, + viewer: bool = False ): self.gym = gymapi.acquire_gym() + self.env_cfg = actors - self.env_cfg = [ - { - "type": "box", - "name": "x", - "handle": None, - "fixed": True, - "size": [0.5, 0.05, 0.01], - "init_pos": [0.25, 0.0, 0.01], - "color": [1, 0.0, 0.2], - "collision": False - }, - { - "type": "box", - "name": "y", - "handle": None, - "fixed": True, - "size": [0.05, 0.5, 0.01], - "init_pos": [0.0, 0.25, 0.01], - "color": [0.0, 1, 0.2], - "collision": False - }, - {"type": "robot", "name": "main_robot", "handle": None, "fixed": fix_base, "init_pos": robot_init_pos}, - ] - self.env_cfg = [ActorWrapper(**a) for a in self.env_cfg] + assert len([a for a in self.env_cfg if a.type == 'robot']) == len(init_positions) + + for init_pos, actor_cfg in zip(init_positions, self.env_cfg): + actor_cfg.init_pos = init_pos self.cfg = cfg if viewer: self.cfg.viewer = viewer self.num_envs = num_envs - self._urdf_file = urdf_file - self._fix_base = fix_base - self._flip_visual = flip_visual - self._ee_link = ee_link - self._disable_gravity = disable_gravity self.start_sim() @@ -139,9 +121,9 @@ def start_sim(self): asset_options = gymapi.AssetOptions() asset_options.fix_base_link = actor_cfg.fixed if actor_cfg.type == "robot": - asset_file = "urdf/" + self._urdf_file - asset_options.flip_visual_attachments = self._flip_visual - asset_options.disable_gravity = self._disable_gravity + asset_file = "urdf/" + actor_cfg.urdf_file + asset_options.flip_visual_attachments = actor_cfg.flip_visual + asset_options.disable_gravity = not actor_cfg.gravity actor_asset = self.gym.load_asset( sim=self.sim, rootpath=f"{file_path}/../../assets", @@ -177,9 +159,11 @@ def start_sim(self): ) for actor_asset, actor_cfg in zip(self.env_actor_assets, self.env_cfg): - self.create_actor(env, env_idx, actor_asset, actor_cfg) + actor_cfg.handle = self.create_actor(env, env_idx, actor_asset, actor_cfg) self.envs.append(env) + self.ee_link_present = any([a.ee_link for a in self.env_cfg]) + self.gym.prepare_sim(self.sim) self.root_state = gymtorch.wrap_tensor( @@ -198,14 +182,14 @@ def start_sim(self): ) # save buffer of ee states - if self._ee_link: + if self.ee_link_present: self.ee_positions_buffer = [] # helpfull slices - self.robot_positions = self.root_state[:, 2, 0:3] # [x, y, z] - self.robot_velocities = self.root_state[:, 2, 7:10] # [x, y, z] + self.robot_positions = self.root_state[:, 0, 0:3] # [x, y, z] + self.robot_velocities = self.root_state[:, 0, 7:10] # [x, y, z] self.obstacle_positions = self.root_state[:, 3:, 0:3] # [x, y, z] - if self._ee_link: + if self.ee_link_present: self.ee_positions = self.rigid_body_state[:, self.robot_rigid_body_ee_idx, 0:3] # [x, y, z] self.gym.refresh_actor_root_state_tensor(self.sim) @@ -248,9 +232,10 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: self.gym.set_actor_rigid_shape_properties(env, handle, props) if actor.type == "robot": - if self._ee_link: + # TODO: Currently the robot_rigid_body_ee_idx is only supported for a single robot case. + if actor.ee_link: self.robot_rigid_body_ee_idx = self.gym.find_actor_rigid_body_index( - env, handle, self._ee_link, gymapi.IndexDomain.DOMAIN_ENV + env, handle, actor.ee_link, gymapi.IndexDomain.DOMAIN_ENV ) props = self.gym.get_asset_dof_properties(asset) @@ -276,6 +261,97 @@ def set_dof_state_tensor(self, state): def set_dof_velocity_target_tensor(self, u): self.gym.set_dof_velocity_target_tensor(self.sim, gymtorch.unwrap_tensor(u)) + def _ik(self, actor, u): + print(u.size()) + r = actor.wheel_radius + L = actor.wheel_base + wheel_sets = actor.wheel_count // 2 + + # Diff drive fk + u_ik = u.clone() + u_ik[:, 0] = (u[:, 0] / r) - ((L * u[:, 1]) / (2 * r)) + u_ik[:, 1] = (u[:, 0] / r) + ((L * u[:, 1]) / (2 * r)) + + + if wheel_sets > 1: + u_ik = u_ik.repeat(1, wheel_sets) + + return u_ik + + def apply_robot_cmd_velocity(self, u_desired): + test = list(self.dof_state.size()) + test[1] = test[1] // 2 + u = torch.zeros(test, device="cuda:0") + print(u_desired.size()) + + u_idx = 0 + for actor in self.env_cfg: + if actor.type != 'robot': continue + actor_dof_count = self.gym.get_actor_dof_count(self.envs[0], actor.handle) + dof_dict = self.gym.get_actor_dof_dict(self.envs[0], actor.handle) + for i in range(actor_dof_count): + print(i, u_idx) + if actor.differential_drive and i >= actor_dof_count - actor.wheel_count: + u_ik = self._ik(actor, u_desired[:, u_idx: u_idx+2]) + u[:, u_idx:u_idx + actor.wheel_count] = u_ik + u_idx += 2 + break + else: + u[:, u_idx] = u_desired[:, u_idx] + u_idx += 1 + + self.gym.set_dof_velocity_target_tensor(self.sim, gymtorch.unwrap_tensor(u)) + + def reset_robot_state(self, q, qdot): + ''' + This function is mainly used for compatibility with gym_urdf_envs pybullet sim. + ''' + + q_idx = 0 + + dof_state = [] + for actor in self.env_cfg: + if actor.type != 'robot': continue + + actor_dof_count = self.gym.get_actor_dof_count(self.envs[0], actor.handle) + + if actor.differential_drive: + actor_q_count = actor_dof_count - (actor.wheel_count - 3) + else: + actor_q_count = actor_dof_count + + actor_q = q[q_idx: q_idx + actor_q_count] + actor_qdot = qdot[q_idx: q_idx + actor_q_count] + + if actor.differential_drive: + pos = actor_q[:3] + vel = actor_qdot[:3] + + self.set_state_tensor_by_pos_vel(actor.handle, pos, vel) + + # assuming wheels at the back of the dof tensor + actor_q = list(actor_q[3:]) + [0] * actor.wheel_count + actor_qdot = list(actor_qdot[3:]) + [0] * actor.wheel_count + + for _q, _qdot in zip(actor_q, actor_qdot): + dof_state.append(_q) + dof_state.append(_qdot) + + q_idx += actor_q_count + + dof_state_tensor = ( + torch.tensor(dof_state) + .type(torch.float32) + .to("cuda:0") + ) + + dof_state_tensor = dof_state_tensor.repeat(self.num_envs, 1) + self.set_dof_state_tensor(dof_state_tensor) + + self.gym.set_actor_root_state_tensor( + self.sim, gymtorch.unwrap_tensor(self.root_state) + ) + def step(self): self.gym.simulate(self.sim) self.gym.fetch_results(self.sim, True) @@ -288,7 +364,7 @@ def step(self): self.gym.draw_viewer(self.viewer, self.sim, False) # self.gym.sync_frame_time(self.sim) - if self._ee_link: + if self.ee_link_present: self.ee_positions_buffer.append(self.ee_positions.clone()) def set_root_state_tensor_by_actor_idx(self, state_tensor, idx): @@ -299,7 +375,7 @@ def save_root_state(self): self.saved_root_state = self.root_state.clone() def reset_root_state(self): - if self._ee_link: + if self.ee_link_present: self.ee_positions_buffer = [] if self.saved_root_state is not None: @@ -307,7 +383,7 @@ def reset_root_state(self): self.sim, gymtorch.unwrap_tensor(self.saved_root_state) ) - def update_root_state_tensor_robot(self, pos, vel): + def set_state_tensor_by_pos_vel(self, handle, pos, vel): roll = 0 pitch = 0 yaw = pos[2] @@ -321,9 +397,10 @@ def update_root_state_tensor_robot(self, pos, vel): np.cos(roll / 2) * np.cos(pitch / 2) * np.cos(yaw / 2), ] - self.root_state[:, 2, :2] = torch.tensor(pos[:2], device="cuda:0") - self.root_state[:, 2, 3:7] = torch.tensor(orientation, device="cuda:0") - self.root_state[:, 2, 7:10] = torch.tensor(vel, device="cuda:0") + + self.root_state[:, handle, :2] = torch.tensor(pos[:2], device="cuda:0") + self.root_state[:, handle, 3:7] = torch.tensor(orientation, device="cuda:0") + self.root_state[:, handle, 7:10] = torch.tensor(vel, device="cuda:0") def update_root_state_tensor_by_obstacles(self, obstacles): """ @@ -389,4 +466,4 @@ def draw_lines(self, lines, env_idx=0): num_lines = line_segments.shape[0] colors = np.zeros((num_lines,3), dtype=np.float32) colors[:, 1] = 255 - self.gym.add_lines(self.viewer, self.envs[env_idx], num_lines, line_segments, colors) \ No newline at end of file + self.gym.add_lines(self.viewer, self.envs[env_idx], num_lines, line_segments, colors) diff --git a/mppiisaac/planner/mppi_isaac.py b/mppiisaac/planner/mppi_isaac.py index a8fbb7f..ab16124 100644 --- a/mppiisaac/planner/mppi_isaac.py +++ b/mppiisaac/planner/mppi_isaac.py @@ -1,7 +1,11 @@ -from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper +from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper, ActorWrapper from mppiisaac.planner.mppi import MPPIPlanner +import mppiisaac from typing import Callable, Optional import io +import os +import yaml +from yaml.loader import SafeLoader from isaacgym import gymtorch import torch @@ -31,15 +35,17 @@ def __init__(self, cfg, objective: Callable, prior: Optional[Callable] = None): self.cfg = cfg self.objective = objective + actors = [] + for actor_name in cfg.actors: + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/{actor_name}.yaml') as f: + actors.append(ActorWrapper(**yaml.load(f, Loader=SafeLoader))) + + print(actors) self.sim = IsaacGymWrapper( cfg.isaacgym, - cfg.urdf_file, - cfg.fix_base, - cfg.flip_visual, - robot_init_pos=cfg.initial_position, + actors=actors, + init_positions=cfg.initial_actor_positions, num_envs=cfg.mppi.num_samples, - ee_link=cfg.ee_link, - disable_gravity=cfg.disable_gravity, ) if prior: @@ -58,30 +64,11 @@ def __init__(self, cfg, objective: Callable, prior: Optional[Callable] = None): # Note: place_holder variable to pass to mppi so it doesn't complain, while the real state is actually the isaacgym simulator itself. self.state_place_holder = torch.zeros((self.cfg.mppi.num_samples, self.cfg.nx)) - def _ik(self, u): - r = self.cfg.wheel_radius - L = self.cfg.wheel_base - wheel_sets = self.cfg.wheel_count // 2 - - # Diff drive fk - u_ik = u.clone() - u_ik[:, 0] = (u[:, 0] / r) - ((L * u[:, 1]) / (2 * r)) - u_ik[:, 1] = (u[:, 0] / r) + ((L * u[:, 1]) / (2 * r)) - - if wheel_sets > 1: - u_ik = u_ik.repeat(1, wheel_sets) - - return u_ik - def dynamics(self, _, u, t=None): # Note: normally mppi passes the state as the first parameter in a dynamics call, but using isaacgym the state is already saved in the simulator itself, so we ignore it. # Note: t is an unused step dependent dynamics variable - if self.cfg.differential_drive: - u_ik = self._ik(u) - self.sim.set_dof_velocity_target_tensor(u_ik) - else: - self.sim.set_dof_velocity_target_tensor(u) + self.sim.apply_robot_cmd_velocity(u) self.sim.step() @@ -93,46 +80,7 @@ def running_cost(self, _): def compute_action(self, q, qdot, obst=None, obst_tensor=None): self.sim.reset_root_state() - - # Deal with non fixed base link robots, that we need to reset the root_state position / velocity of. - # Currently only differential drive bases are non fixed. We also have to deal with the kinematic transforms. - if self.cfg.differential_drive: - pos = q[:3] - vel = qdot[:3] - self.sim.update_root_state_tensor_robot(pos, vel) - - if len(q) > 3: - # Add the dof state of the wheels (assuming 2 wheel here) - q = [0] * self.cfg.wheel_count + q[3:] - # TODO: reset the dof_state velocity of the wheels based on the measured ground velocity - qdot = [0] * self.cfg.wheel_count + q[3:] - else: - q = [0] * self.cfg.wheel_count - qdot = [0] * self.cfg.wheel_count - - reordered_state = [] - for i in range(int(self.cfg.nx / 2) + (self.cfg.wheel_count - 2)): - reordered_state.append(q[i]) - reordered_state.append(qdot[i]) - state = ( - torch.tensor(reordered_state) - .type(torch.float32) - .to(self.cfg.mppi.device) - ) # [x, vx, y, vy] - - else: - reordered_state = [] - for i in range(int(self.cfg.nx / 2)): - reordered_state.append(q[i]) - reordered_state.append(qdot[i]) - state = ( - torch.tensor(reordered_state) - .type(torch.float32) - .to(self.cfg.mppi.device) - ) # [x, vx, y, vy] - - state = state.repeat(self.sim.num_envs, 1) - self.sim.set_dof_state_tensor(state) + self.sim.reset_robot_state(q, qdot) # NOTE: There are two different ways of updating obstacle root_states # Both update based on id in the list of obstacles diff --git a/mppiisaac/utils/config_store.py b/mppiisaac/utils/config_store.py index 44c858f..8fc2bff 100644 --- a/mppiisaac/utils/config_store.py +++ b/mppiisaac/utils/config_store.py @@ -14,16 +14,8 @@ class ExampleConfig: isaacgym: IsaacGymConfig goal: List[float] nx: int - urdf_file: str - fix_base: bool - flip_visual: bool - initial_position: List[float] = field(default_factory=lambda: [0, 0, 0]) - disable_gravity: bool = False - differential_drive: bool = False - wheel_base: float = 0 - wheel_radius: float = 0 - wheel_count: int = 0 - ee_link: Optional[str] = None + actors: List[str] + initial_actor_positions: List[List[float]] cs = ConfigStore.instance() @@ -31,6 +23,7 @@ class ExampleConfig: cs.store(name="config_heijn_robot", node=ExampleConfig) cs.store(name="config_boxer_robot", node=ExampleConfig) cs.store(name="config_jackal_robot", node=ExampleConfig) +cs.store(name="config_multi_jackal", node=ExampleConfig) cs.store(name="config_panda", node=ExampleConfig) cs.store(name="config_panda_push", node=ExampleConfig) cs.store(name="config_panda_c_space_goal", node=ExampleConfig) From 9398ba444d06c2f710cd0b295d7e2f8bea6a0e16 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 11:11:02 +0200 Subject: [PATCH 07/26] Adds jackal example with isaacgym as sim, and fixes bugs --- conf/actors/jackal.yaml | 5 +- conf/config_jackal_robot.yaml | 2 +- conf/mppi/jackal.yaml | 6 +- examples/jackal_client.py | 40 ++++++++++++ examples/jackal_key.py | 71 +++++++++++++++++++++ examples/jackal_robot.py | 2 +- examples/jackal_server.py | 89 +++++++++++++++++++++++++++ examples/multi_jackal.py | 20 +----- mppiisaac/planner/isaacgym_wrapper.py | 37 +++++------ 9 files changed, 228 insertions(+), 44 deletions(-) create mode 100644 examples/jackal_client.py create mode 100644 examples/jackal_key.py create mode 100644 examples/jackal_server.py diff --git a/conf/actors/jackal.yaml b/conf/actors/jackal.yaml index ee26558..f756f6c 100644 --- a/conf/actors/jackal.yaml +++ b/conf/actors/jackal.yaml @@ -5,8 +5,9 @@ fixed: False flip_visual: false gravity: true differential_drive: true -mass: 40 +mass: 40.00 wheel_radius: 0.14 wheel_base: 0.400 wheel_count: 4 -collision: False +friction: 0.8 +collision: True diff --git a/conf/config_jackal_robot.yaml b/conf/config_jackal_robot.yaml index 94e052b..e8c384f 100644 --- a/conf/config_jackal_robot.yaml +++ b/conf/config_jackal_robot.yaml @@ -7,5 +7,5 @@ render: true n_steps: 1000 nx: 4 -actors: ['jackal', 'xaxis', 'yaxis'] +actors: ['jackal'] initial_actor_positions: [[0.0, 0.0, 0.05]] diff --git a/conf/mppi/jackal.yaml b/conf/mppi/jackal.yaml index 78f325a..670e505 100644 --- a/conf/mppi/jackal.yaml +++ b/conf/mppi/jackal.yaml @@ -7,9 +7,9 @@ num_samples: 100 horizon: 20 # At least 12 for Halton Sampling device: "cuda:0" lambda_: 0.05 -u_min: [-1.5] -u_max: [1.5] -noise_sigma: [[10., 0.], [0., 10.]] +u_min: [-1.5, -10.5] +u_max: [1.5, 10.5] +noise_sigma: [[1., 0.], [0., 10.]] update_cov: False rollout_var_discount: 0.95 sample_null_action: True diff --git a/examples/jackal_client.py b/examples/jackal_client.py new file mode 100644 index 0000000..1ce01ad --- /dev/null +++ b/examples/jackal_client.py @@ -0,0 +1,40 @@ +import gym +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import hydra +from omegaconf import OmegaConf +import os +import torch +import zerorpc + +from mppiisaac.utils.config_store import ExampleConfig + + +class Objective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + + def compute_cost(self, sim): + pos = sim.robot_positions[:, :2] +# print(pos[0], self.nav_goal) + err = torch.linalg.norm(pos - self.nav_goal, axis=1) + cost = torch.clamp( + err - 0.05, min=0, max=1999 + ) + return err * 1.5 + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_jackal_robot") +def run_jackal_robot(cfg: ExampleConfig): + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + objective = Objective(cfg, cfg.mppi.device) + prior = None + planner = zerorpc.Server(MPPIisaacPlanner(cfg, objective, prior)) + planner.bind("tcp://0.0.0.0:4242") + planner.run() + + +if __name__ == "__main__": + run_jackal_robot() diff --git a/examples/jackal_key.py b/examples/jackal_key.py new file mode 100644 index 0000000..8f4a884 --- /dev/null +++ b/examples/jackal_key.py @@ -0,0 +1,71 @@ +import gym +from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper, ActorWrapper +import yaml +from yaml import SafeLoader +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import hydra +from omegaconf import OmegaConf +import os +import mppiisaac +import torch +import zerorpc +from mppiisaac.utils.config_store import ExampleConfig +from isaacgym import gymapi +import time + +import io + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_jackal_robot") +def run_jackal_robot(cfg: ExampleConfig): + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + actors=[] + for actor_name in cfg.actors: + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/{actor_name}.yaml') as f: + actors.append(ActorWrapper(**yaml.load(f, Loader=SafeLoader))) + + + sim = IsaacGymWrapper( + cfg.isaacgym, + init_positions=cfg.initial_actor_positions, + actors=actors, + num_envs=1, + viewer=True, + ) + + sim.gym.viewer_camera_look_at( + sim.viewer, None, gymapi.Vec3(1.5, 2, 3), gymapi.Vec3(1.5, 0, 0) + ) + + sim.gym.subscribe_viewer_keyboard_event(sim.viewer, gymapi.KEY_A, "left") + sim.gym.subscribe_viewer_keyboard_event(sim.viewer, gymapi.KEY_S, "down") + sim.gym.subscribe_viewer_keyboard_event(sim.viewer, gymapi.KEY_D, "right") + sim.gym.subscribe_viewer_keyboard_event(sim.viewer, gymapi.KEY_W, "up") + + action = torch.tensor([0., 0.], device="cuda:0") + for _ in range(cfg.n_steps): + for e in sim.gym.query_viewer_action_events(sim.viewer): + if e.action == "up": + action[0] = 0.5 + if e.action == "down": + action[0] = -0.2 + #action[1] = 0. + if e.action == "left": + action[1] = 5.8 + if e.action == "right": + action[1] = -5.8 + + # Apply action + sim.apply_robot_cmd_velocity(torch.unsqueeze(action, axis=0)) + + # Step simulator + sim.step() + sim.gym.sync_frame_time(sim.sim) + return {} + + +if __name__ == "__main__": + res = run_jackal_robot() diff --git a/examples/jackal_robot.py b/examples/jackal_robot.py index 2a57bcb..13632bb 100644 --- a/examples/jackal_robot.py +++ b/examples/jackal_robot.py @@ -19,7 +19,7 @@ def __init__(self, cfg, device): def compute_cost(self, sim): pos = sim.robot_positions[:, :2] - + err = torch.linalg.norm(pos - self.nav_goal, axis=1) cost = torch.clamp( torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 ) diff --git a/examples/jackal_server.py b/examples/jackal_server.py new file mode 100644 index 0000000..047f7fb --- /dev/null +++ b/examples/jackal_server.py @@ -0,0 +1,89 @@ +import gym +from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper, ActorWrapper +import yaml +from yaml import SafeLoader +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import hydra +from omegaconf import OmegaConf +import os +import mppiisaac +import torch +import zerorpc +from mppiisaac.utils.config_store import ExampleConfig +from isaacgym import gymapi +import time + +import io + + +def torch_to_bytes(t: torch.Tensor) -> bytes: + buff = io.BytesIO() + torch.save(t, buff) + buff.seek(0) + return buff.read() + + +def bytes_to_torch(b: bytes) -> torch.Tensor: + buff = io.BytesIO(b) + return torch.load(buff) + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_jackal_robot") +def run_jackal_robot(cfg: ExampleConfig): + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + actors=[] + for actor_name in cfg.actors: + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/{actor_name}.yaml') as f: + actors.append(ActorWrapper(**yaml.load(f, Loader=SafeLoader))) + + + sim = IsaacGymWrapper( + cfg.isaacgym, + init_positions=cfg.initial_actor_positions, + actors=actors, + num_envs=1, + viewer=True, + ) + + sim.gym.viewer_camera_look_at( + sim.viewer, None, gymapi.Vec3(1.5, 2, 3), gymapi.Vec3(1.5, 0, 0) + ) + + planner = zerorpc.Client() + planner.connect("tcp://127.0.0.1:4242") + print("Mppi server found!") + + for _ in range(cfg.n_steps): + t = time.time() + # Reset state + planner.reset_rollout_sim( + torch_to_bytes(sim.dof_state[0]), + torch_to_bytes(sim.root_state[0]), + torch_to_bytes(sim.rigid_body_state[0]), + ) + + # Compute action + action = bytes_to_torch(planner.command()) + #print(action) + if torch.any(torch.isnan(action)): + print("nan action") + action = torch.zeros_like(action) + + # Apply action + sim.apply_robot_cmd_velocity(torch.unsqueeze(action, axis=0)) + #sim.set_dof_velocity_target_tensor(action) + + # Step simulator + sim.step() + + # Print error + pos = sim.robot_positions[:, :2] + print(torch.linalg.norm(pos - torch.tensor(cfg.goal, device="cuda:0"), axis=1)) + return {} + + +if __name__ == "__main__": + res = run_jackal_robot() diff --git a/examples/multi_jackal.py b/examples/multi_jackal.py index 549e83b..985ed49 100644 --- a/examples/multi_jackal.py +++ b/examples/multi_jackal.py @@ -19,15 +19,10 @@ def __init__(self, cfg, device): def compute_cost(self, sim): pos = torch.cat((sim.root_state[:, 0, 0:2], sim.root_state[:, 1, 0:2]), axis=1) - print(pos[0]) - print(self.nav_goal) - - cost = torch.clamp( torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 ) - cost += -0.2*torch.linalg.norm(pos[:, :2] - pos[:, 2:], axis=1) - return cost * 1.5 + return cost def initalize_environment(cfg) -> UrdfEnv: @@ -49,20 +44,7 @@ def initalize_environment(cfg) -> UrdfEnv: ] env: UrdfEnv = gym.make("urdf-env-v0", dt=0.02, robots=robots, render=cfg.render) # Set the initial position and velocity of the jackal robot - print(cfg.initial_actor_positions) env.reset(pos=np.array(cfg.initial_actor_positions)) - #goal_dict = { - # "weight": 1.0, - # "is_primary_goal": True, - # "indices": [0, 1], - # "parent_link": 0, - # "child_link": 1, - # "desired_position": cfg.goal, - # "epsilon": 0.05, - # "type": "staticSubGoal", - #} - #goal = StaticSubGoal(name="simpleGoal", content_dict=goal_dict) - # env.add_goal(goal) return env diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index f53ebc0..ce6643a 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -226,9 +226,11 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: props[0].mass = actor.mass self.gym.set_actor_rigid_body_properties(env, handle, props) props = self.gym.get_actor_rigid_shape_properties(env, handle) - props[0].friction = actor.friction - props[0].torsion_friction = actor.friction - props[0].rolling_friction = actor.friction + for p in props: + p.friction = actor.friction + p.torsion_friction = actor.friction + p.rolling_friction = actor.friction + self.gym.set_actor_rigid_shape_properties(env, handle, props) if actor.type == "robot": @@ -262,16 +264,14 @@ def set_dof_velocity_target_tensor(self, u): self.gym.set_dof_velocity_target_tensor(self.sim, gymtorch.unwrap_tensor(u)) def _ik(self, actor, u): - print(u.size()) r = actor.wheel_radius L = actor.wheel_base wheel_sets = actor.wheel_count // 2 # Diff drive fk u_ik = u.clone() - u_ik[:, 0] = (u[:, 0] / r) - ((L * u[:, 1]) / (2 * r)) - u_ik[:, 1] = (u[:, 0] / r) + ((L * u[:, 1]) / (2 * r)) - + u_ik[:, 1] = (u[:, 0] / r) - ((L * u[:, 1]) / (2 * r)) + u_ik[:, 0] = (u[:, 0] / r) + ((L * u[:, 1]) / (2 * r)) if wheel_sets > 1: u_ik = u_ik.repeat(1, wheel_sets) @@ -279,26 +279,27 @@ def _ik(self, actor, u): return u_ik def apply_robot_cmd_velocity(self, u_desired): - test = list(self.dof_state.size()) - test[1] = test[1] // 2 - u = torch.zeros(test, device="cuda:0") - print(u_desired.size()) + vel_dof_shape = list(self.dof_state.size()) + vel_dof_shape[1] = vel_dof_shape[1] // 2 + u = torch.zeros(vel_dof_shape, device="cuda:0") - u_idx = 0 + u_desired_idx = 0 + u_dof_idx = 0 for actor in self.env_cfg: if actor.type != 'robot': continue actor_dof_count = self.gym.get_actor_dof_count(self.envs[0], actor.handle) dof_dict = self.gym.get_actor_dof_dict(self.envs[0], actor.handle) for i in range(actor_dof_count): - print(i, u_idx) if actor.differential_drive and i >= actor_dof_count - actor.wheel_count: - u_ik = self._ik(actor, u_desired[:, u_idx: u_idx+2]) - u[:, u_idx:u_idx + actor.wheel_count] = u_ik - u_idx += 2 + u_ik = self._ik(actor, u_desired[:, u_desired_idx: u_desired_idx+2]) + u[:, u_dof_idx:u_dof_idx + actor.wheel_count] = u_ik + u_desired_idx += 2 + u_dof_idx += actor.wheel_count break else: - u[:, u_idx] = u_desired[:, u_idx] - u_idx += 1 + u[:, u_dof_idx] = u_desired[:, u_desired_idx] + u_desired_idx += 1 + u_dof_idx += 1 self.gym.set_dof_velocity_target_tensor(self.sim, gymtorch.unwrap_tensor(u)) From eef1836089c180930f0975f50db3d49f9edef837 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 11:58:25 +0200 Subject: [PATCH 08/26] Set friction of caster links to zero automagically --- mppiisaac/planner/isaacgym_wrapper.py | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index ce6643a..3a35726 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -74,6 +74,7 @@ class ActorWrapper: wheel_count: Optional[float] = None left_wheel_joints: Optional[List[int]] = None right_wheel_joints: Optional[List[int]] = None + caster_links: Optional[List[str]] = None class IsaacGymWrapper: @@ -225,11 +226,25 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: props = self.gym.get_actor_rigid_body_properties(env, handle) props[0].mass = actor.mass self.gym.set_actor_rigid_body_properties(env, handle, props) + + body_names = self.gym.get_actor_rigid_body_names(env, handle) + body_to_shape = self.gym.get_actor_rigid_body_shape_indices(env, handle) + caster_shapes = [ + b.start + for body_idx, b in enumerate(body_to_shape) + if body_names[body_idx] in actor.caster_links + ] + props = self.gym.get_actor_rigid_shape_properties(env, handle) - for p in props: + for i, p in enumerate(props): p.friction = actor.friction p.torsion_friction = actor.friction p.rolling_friction = actor.friction + + if i in caster_shapes: + p.friction = 0 + p.torsion_friction = 0 + p.rolling_friction = 0 self.gym.set_actor_rigid_shape_properties(env, handle, props) From ba9de288aaefe58468104804105bab55ec6062ff Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 11:59:04 +0200 Subject: [PATCH 09/26] update styles using black --- mppiisaac/planner/isaacgym_wrapper.py | 96 ++++++++++++++++----------- 1 file changed, 58 insertions(+), 38 deletions(-) diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 3a35726..dcec93a 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -84,12 +84,14 @@ def __init__( actors: List[ActorWrapper], init_positions: List[List[float]], num_envs: int, - viewer: bool = False + viewer: bool = False, ): self.gym = gymapi.acquire_gym() self.env_cfg = actors - assert len([a for a in self.env_cfg if a.type == 'robot']) == len(init_positions) + assert len([a for a in self.env_cfg if a.type == "robot"]) == len( + init_positions + ) for init_pos, actor_cfg in zip(init_positions, self.env_cfg): actor_cfg.init_pos = init_pos @@ -146,7 +148,9 @@ def start_sim(self): options=asset_options, ) else: - raise NotImplementedError(f"actor asset of type {actor_cfg.type} is not yet implemented!") + raise NotImplementedError( + f"actor asset of type {actor_cfg.type} is not yet implemented!" + ) self.env_actor_assets.append(actor_asset) # Create envs and fill with assets @@ -160,7 +164,9 @@ def start_sim(self): ) for actor_asset, actor_cfg in zip(self.env_actor_assets, self.env_cfg): - actor_cfg.handle = self.create_actor(env, env_idx, actor_asset, actor_cfg) + actor_cfg.handle = self.create_actor( + env, env_idx, actor_asset, actor_cfg + ) self.envs.append(env) self.ee_link_present = any([a.ee_link for a in self.env_cfg]) @@ -191,7 +197,9 @@ def start_sim(self): self.robot_velocities = self.root_state[:, 0, 7:10] # [x, y, z] self.obstacle_positions = self.root_state[:, 3:, 0:3] # [x, y, z] if self.ee_link_present: - self.ee_positions = self.rigid_body_state[:, self.robot_rigid_body_ee_idx, 0:3] # [x, y, z] + self.ee_positions = self.rigid_body_state[ + :, self.robot_rigid_body_ee_idx, 0:3 + ] # [x, y, z] self.gym.refresh_actor_root_state_tensor(self.sim) self.gym.refresh_dof_state_tensor(self.sim) @@ -202,7 +210,7 @@ def stop_sim(self): if self.viewer: self.gym.destroy_viewer(self.viewer) self.gym.destroy_sim(self.sim) - + def add_to_envs(self, additions): for a in additions: self.env_cfg.append(ActorWrapper(**a)) @@ -301,43 +309,50 @@ def apply_robot_cmd_velocity(self, u_desired): u_desired_idx = 0 u_dof_idx = 0 for actor in self.env_cfg: - if actor.type != 'robot': continue + if actor.type != "robot": + continue actor_dof_count = self.gym.get_actor_dof_count(self.envs[0], actor.handle) dof_dict = self.gym.get_actor_dof_dict(self.envs[0], actor.handle) for i in range(actor_dof_count): - if actor.differential_drive and i >= actor_dof_count - actor.wheel_count: - u_ik = self._ik(actor, u_desired[:, u_desired_idx: u_desired_idx+2]) - u[:, u_dof_idx:u_dof_idx + actor.wheel_count] = u_ik + if ( + actor.differential_drive + and i >= actor_dof_count - actor.wheel_count + ): + u_ik = self._ik( + actor, u_desired[:, u_desired_idx : u_desired_idx + 2] + ) + u[:, u_dof_idx : u_dof_idx + actor.wheel_count] = u_ik u_desired_idx += 2 u_dof_idx += actor.wheel_count break else: - u[:, u_dof_idx] = u_desired[:, u_desired_idx] + u[:, u_dof_idx] = u_desired[:, u_desired_idx] u_desired_idx += 1 u_dof_idx += 1 - + self.gym.set_dof_velocity_target_tensor(self.sim, gymtorch.unwrap_tensor(u)) def reset_robot_state(self, q, qdot): - ''' + """ This function is mainly used for compatibility with gym_urdf_envs pybullet sim. - ''' + """ q_idx = 0 dof_state = [] for actor in self.env_cfg: - if actor.type != 'robot': continue + if actor.type != "robot": + continue actor_dof_count = self.gym.get_actor_dof_count(self.envs[0], actor.handle) if actor.differential_drive: - actor_q_count = actor_dof_count - (actor.wheel_count - 3) + actor_q_count = actor_dof_count - (actor.wheel_count - 3) else: actor_q_count = actor_dof_count - actor_q = q[q_idx: q_idx + actor_q_count] - actor_qdot = qdot[q_idx: q_idx + actor_q_count] + actor_q = q[q_idx : q_idx + actor_q_count] + actor_qdot = qdot[q_idx : q_idx + actor_q_count] if actor.differential_drive: pos = actor_q[:3] @@ -355,11 +370,7 @@ def reset_robot_state(self, q, qdot): q_idx += actor_q_count - dof_state_tensor = ( - torch.tensor(dof_state) - .type(torch.float32) - .to("cuda:0") - ) + dof_state_tensor = torch.tensor(dof_state).type(torch.float32).to("cuda:0") dof_state_tensor = dof_state_tensor.repeat(self.num_envs, 1) self.set_dof_state_tensor(dof_state_tensor) @@ -413,7 +424,6 @@ def set_state_tensor_by_pos_vel(self, handle, pos, vel): np.cos(roll / 2) * np.cos(pitch / 2) * np.cos(yaw / 2), ] - self.root_state[:, handle, :2] = torch.tensor(pos[:2], device="cuda:0") self.root_state[:, handle, 3:7] = torch.tensor(orientation, device="cuda:0") self.root_state[:, handle, 7:10] = torch.tensor(vel, device="cuda:0") @@ -429,16 +439,20 @@ def update_root_state_tensor_by_obstacles(self, obstacles): pos, vel, o_type, o_size = obst name = f"{o_type}{i}" try: - obst_idx = [idx for idx, actor in enumerate(self.env_cfg) if actor.name == name][0] + obst_idx = [ + idx for idx, actor in enumerate(self.env_cfg) if actor.name == name + ][0] except: self.env_cfg.append( - ActorWrapper(**{ - "type": o_type, - "name": name, - "handle": None, - "size": o_size, - "fixed": True, - }) + ActorWrapper( + **{ + "type": o_type, + "name": name, + "handle": None, + "size": o_size, + "fixed": True, + } + ) ) env_cfg_changed = True continue @@ -448,9 +462,7 @@ def update_root_state_tensor_by_obstacles(self, obstacles): ) # Note: reset simulator if size changed, because this cannot be done at runtime. - if not all( - [a == b for a, b in zip(o_size, self.env_cfg[obst_idx].size)] - ): + if not all([a == b for a, b in zip(o_size, self.env_cfg[obst_idx].size)]): env_cfg_changed = True self.env_cfg[obst_idx].size = o_size @@ -478,8 +490,16 @@ def update_root_state_tensor_by_obstacles_tensor(self, obst_tensor): def draw_lines(self, lines, env_idx=0): # convert list of vertices into line segments - line_segments = torch.concat((lines[:-1], lines[1:]), axis=-1).flatten(end_dim=-2).cpu().numpy().astype(np.float32) + line_segments = ( + torch.concat((lines[:-1], lines[1:]), axis=-1) + .flatten(end_dim=-2) + .cpu() + .numpy() + .astype(np.float32) + ) num_lines = line_segments.shape[0] - colors = np.zeros((num_lines,3), dtype=np.float32) + colors = np.zeros((num_lines, 3), dtype=np.float32) colors[:, 1] = 255 - self.gym.add_lines(self.viewer, self.envs[env_idx], num_lines, line_segments, colors) + self.gym.add_lines( + self.viewer, self.envs[env_idx], num_lines, line_segments, colors + ) From a383d2a2b62cc1860cce6c850393609bd0ea4d0d Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 11:59:25 +0200 Subject: [PATCH 10/26] update boxer example --- conf/actors/boxer.yaml | 14 ++++++++++++++ conf/config_boxer_robot.yaml | 12 ++++-------- 2 files changed, 18 insertions(+), 8 deletions(-) create mode 100644 conf/actors/boxer.yaml diff --git a/conf/actors/boxer.yaml b/conf/actors/boxer.yaml new file mode 100644 index 0000000..0e18cfe --- /dev/null +++ b/conf/actors/boxer.yaml @@ -0,0 +1,14 @@ +type: robot +name: boxer +urdf_file: "boxer/boxer.urdf" +gravity: true +mass: 100.00 +fixed: false +flip_visual: false +differential_drive: true +wheel_radius: 0.08 +wheel_base: 0.314 +wheel_count: 2 +friction: 1.0 +collision: True +caster_links: ['rotacastor_right_link', 'rotacastor_left_link'] diff --git a/conf/config_boxer_robot.yaml b/conf/config_boxer_robot.yaml index d918fe5..dce1769 100644 --- a/conf/config_boxer_robot.yaml +++ b/conf/config_boxer_robot.yaml @@ -3,14 +3,10 @@ defaults: - isaacgym: normal goal: [2.0, 2.0] -initial_position: [0.0, 0.0, 0.05] render: true n_steps: 1000 -urdf_file: "boxer/boxer.urdf" -fix_base: false -flip_visual: false nx: 4 -differential_drive: true -wheel_radius: 0.08 -wheel_base: 0.314 -wheel_count: 2 + +actors: ['boxer'] +initial_actor_positions: [[0.0, 0.0, 0.05]] + From 732fbf8ae380a5b5d75d7746211da1633b02b86f Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 12:09:32 +0200 Subject: [PATCH 11/26] update heijn example --- conf/actors/heijn.yaml | 8 ++++++++ conf/config_heijn_robot.yaml | 8 ++++---- examples/heijn_robot.py | 7 ++++++- mppiisaac/planner/isaacgym_wrapper.py | 5 +++-- 4 files changed, 21 insertions(+), 7 deletions(-) create mode 100644 conf/actors/heijn.yaml diff --git a/conf/actors/heijn.yaml b/conf/actors/heijn.yaml new file mode 100644 index 0000000..5beb311 --- /dev/null +++ b/conf/actors/heijn.yaml @@ -0,0 +1,8 @@ + +type: robot +name: heijn +urdf_file: "heijn/heijn.urdf" +gravity: true +fixed: true +flip_visual: true +collision: True diff --git a/conf/config_heijn_robot.yaml b/conf/config_heijn_robot.yaml index 8f451b5..0f0aab2 100644 --- a/conf/config_heijn_robot.yaml +++ b/conf/config_heijn_robot.yaml @@ -3,10 +3,10 @@ defaults: - isaacgym: normal goal: [2.0, 2.0] -initial_position: [0.0, 0.0, 0.05] render: true n_steps: 1000 -urdf_file: "heijn/heijn.urdf" -fix_base: true -flip_visual: true nx: 6 + +actors: ['heijn'] +initial_actor_positions: [[0.0, 0.0, 0.05]] + diff --git a/examples/heijn_robot.py b/examples/heijn_robot.py index a214615..92fad4b 100644 --- a/examples/heijn_robot.py +++ b/examples/heijn_robot.py @@ -3,7 +3,10 @@ from urdfenvs.robots.generic_urdf import GenericUrdfReacher from urdfenvs.urdf_common.urdf_env import UrdfEnv from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import mppiisaac import hydra +import yaml +from yaml import SafeLoader from omegaconf import OmegaConf import os import torch @@ -36,7 +39,9 @@ def initalize_environment(cfg) -> UrdfEnv: render Boolean toggle to set rendering on (True) or off (False). """ - urdf_file = os.path.dirname(os.path.abspath(__file__)) + "/../assets/urdf/" + cfg.urdf_file + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/heijn.yaml') as f: + heijn_cfg = yaml.load(f, Loader=SafeLoader) + urdf_file = f'{os.path.dirname(mppiisaac.__file__)}/../assets/urdf/' + heijn_cfg['urdf_file'] robots = [ GenericUrdfReacher(urdf=urdf_file, mode="vel"), ] diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index dcec93a..c2a6c7a 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -240,7 +240,8 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: caster_shapes = [ b.start for body_idx, b in enumerate(body_to_shape) - if body_names[body_idx] in actor.caster_links + if actor.caster_links is not None + and body_names[body_idx] in actor.caster_links ] props = self.gym.get_actor_rigid_shape_properties(env, handle) @@ -248,7 +249,7 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: p.friction = actor.friction p.torsion_friction = actor.friction p.rolling_friction = actor.friction - + if i in caster_shapes: p.friction = 0 p.torsion_friction = 0 From f361c708074b736cf3aa3ae4f7c6cd51f55146bd Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 13:18:49 +0200 Subject: [PATCH 12/26] update panda push example --- conf/actors/panda.yaml | 1 - conf/actors/panda_stick.yaml | 7 +++++++ conf/config_panda_push.yaml | 10 ++++------ examples/jackal_server.py | 2 +- examples/panda_isaacgym_server.py | 21 +++++++++++++-------- examples/panda_push_client.py | 4 ++-- examples/panda_push_server.py | 17 +++++++++++------ 7 files changed, 38 insertions(+), 24 deletions(-) create mode 100644 conf/actors/panda_stick.yaml diff --git a/conf/actors/panda.yaml b/conf/actors/panda.yaml index 7c685f0..98db344 100644 --- a/conf/actors/panda.yaml +++ b/conf/actors/panda.yaml @@ -1,7 +1,6 @@ type: robot name: panda fixed: True -init_pos: [0.0, 0.0, 0.0] urdf_file: "panda_isaac/robots/franka_panda.urdf" ee_link: "panda_link7" flip_visual: true diff --git a/conf/actors/panda_stick.yaml b/conf/actors/panda_stick.yaml new file mode 100644 index 0000000..d1ea8a3 --- /dev/null +++ b/conf/actors/panda_stick.yaml @@ -0,0 +1,7 @@ +type: robot +name: panda +urdf_file: "panda_isaac/robots/franka_panda_stick.urdf" +ee_link: "panda_ee_tip" +fixed: True +flip_visual: true +gravity: false diff --git a/conf/config_panda_push.yaml b/conf/config_panda_push.yaml index 493364e..91d369b 100644 --- a/conf/config_panda_push.yaml +++ b/conf/config_panda_push.yaml @@ -4,10 +4,8 @@ defaults: goal: [0.5, 0.4, 0.7] render: true -n_steps: 10000 -urdf_file: "panda_isaac/robots/franka_panda_stick.urdf" -ee_link: "panda_ee_tip" -fix_base: true -flip_visual: true -disable_gravity: true +n_steps: 1000 +actors: ['panda_stick'] +initial_actor_positions: [[0.0, 0.0, 0.0]] + nx: 14 diff --git a/examples/jackal_server.py b/examples/jackal_server.py index 047f7fb..2ea4de6 100644 --- a/examples/jackal_server.py +++ b/examples/jackal_server.py @@ -74,10 +74,10 @@ def run_jackal_robot(cfg: ExampleConfig): # Apply action sim.apply_robot_cmd_velocity(torch.unsqueeze(action, axis=0)) - #sim.set_dof_velocity_target_tensor(action) # Step simulator sim.step() + sim.gym.sync_frame_time(sim.sim) # Print error pos = sim.robot_positions[:, :2] diff --git a/examples/panda_isaacgym_server.py b/examples/panda_isaacgym_server.py index 45c3171..cca3178 100644 --- a/examples/panda_isaacgym_server.py +++ b/examples/panda_isaacgym_server.py @@ -1,9 +1,11 @@ import gym -from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper +from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper, ActorWrapper import numpy as np +import yaml +from yaml import SafeLoader from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner -from urdfenvs.robots.generic_urdf import GenericUrdfReacher import hydra +import mppiisaac from omegaconf import OmegaConf import os import torch @@ -31,14 +33,16 @@ def run_panda_robot(cfg: ExampleConfig): # Note: Workaround to trigger the dataclasses __post_init__ method cfg = OmegaConf.to_object(cfg) + actors=[] + for actor_name in cfg.actors: + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/{actor_name}.yaml') as f: + actors.append(ActorWrapper(**yaml.load(f, Loader=SafeLoader))) + sim = IsaacGymWrapper( cfg.isaacgym, - cfg.urdf_file, - cfg.fix_base, - cfg.flip_visual, + init_positions=cfg.initial_actor_positions, + actors=actors, num_envs=1, - ee_link=cfg.ee_link, - disable_gravity=cfg.disable_gravity, viewer=True, ) @@ -65,10 +69,11 @@ def run_panda_robot(cfg: ExampleConfig): action = bytes_to_torch(planner.command()) # Apply action - sim.set_dof_velocity_target_tensor(action) + sim.apply_robot_cmd_velocity(torch.unsqueeze(action, axis=0)) # Step simulator sim.step() + sim.gym.sync_frame_time(sim.sim) return {} diff --git a/examples/panda_push_client.py b/examples/panda_push_client.py index bf2984b..d228887 100644 --- a/examples/panda_push_client.py +++ b/examples/panda_push_client.py @@ -72,8 +72,8 @@ def orientation_error(self, q1, q2_batch): return error_batch def compute_cost(self, sim): - ee_index = 11 - block_index = 4 + ee_index = sim.robot_rigid_body_ee_idx + block_index = 2 r_pos = sim.rigid_body_state[:, ee_index, :3] r_ort = sim.rigid_body_state[:, ee_index, 3:7] ee_height = r_pos[:, 2] diff --git a/examples/panda_push_server.py b/examples/panda_push_server.py index 2d2770b..564868d 100644 --- a/examples/panda_push_server.py +++ b/examples/panda_push_server.py @@ -1,6 +1,9 @@ import gym -from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper +from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper, ActorWrapper import numpy as np +import yaml +import mppiisaac +from yaml import SafeLoader from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner from urdfenvs.robots.generic_urdf import GenericUrdfReacher import hydra @@ -32,14 +35,16 @@ def run_panda_robot(cfg: ExampleConfig): # Note: Workaround to trigger the dataclasses __post_init__ method cfg = OmegaConf.to_object(cfg) + actors=[] + for actor_name in cfg.actors: + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/{actor_name}.yaml') as f: + actors.append(ActorWrapper(**yaml.load(f, Loader=SafeLoader))) + sim = IsaacGymWrapper( cfg.isaacgym, - cfg.urdf_file, - cfg.fix_base, - cfg.flip_visual, + init_positions=cfg.initial_actor_positions, + actors=actors, num_envs=1, - ee_link=cfg.ee_link, - disable_gravity=cfg.disable_gravity, viewer=True, ) From db326dff76ce927683c7d171fc4fb785b5dc5eef Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 13:39:16 +0200 Subject: [PATCH 13/26] Fix robot and obstacle reference tensors --- examples/boxer_robot.py | 2 +- examples/jackal_client.py | 2 +- examples/jackal_robot.py | 2 +- examples/jackal_server.py | 2 +- mppiisaac/planner/isaacgym_wrapper.py | 13 ++++++++++--- 5 files changed, 14 insertions(+), 7 deletions(-) diff --git a/examples/boxer_robot.py b/examples/boxer_robot.py index 2b7099d..681336b 100644 --- a/examples/boxer_robot.py +++ b/examples/boxer_robot.py @@ -18,7 +18,7 @@ def __init__(self, cfg, device): self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) def compute_cost(self, sim): - pos = sim.robot_positions[:, :2] + pos = sim.robot_positions[:, 0, :2] return torch.clamp( torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 diff --git a/examples/jackal_client.py b/examples/jackal_client.py index 1ce01ad..c4d678f 100644 --- a/examples/jackal_client.py +++ b/examples/jackal_client.py @@ -15,7 +15,7 @@ def __init__(self, cfg, device): self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) def compute_cost(self, sim): - pos = sim.robot_positions[:, :2] + pos = sim.robot_positions[:, 0, :2] # print(pos[0], self.nav_goal) err = torch.linalg.norm(pos - self.nav_goal, axis=1) cost = torch.clamp( diff --git a/examples/jackal_robot.py b/examples/jackal_robot.py index 13632bb..ff93c29 100644 --- a/examples/jackal_robot.py +++ b/examples/jackal_robot.py @@ -18,7 +18,7 @@ def __init__(self, cfg, device): self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) def compute_cost(self, sim): - pos = sim.robot_positions[:, :2] + pos = sim.robot_positions[:, 0, :2] err = torch.linalg.norm(pos - self.nav_goal, axis=1) cost = torch.clamp( torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 diff --git a/examples/jackal_server.py b/examples/jackal_server.py index 2ea4de6..1000b34 100644 --- a/examples/jackal_server.py +++ b/examples/jackal_server.py @@ -80,7 +80,7 @@ def run_jackal_robot(cfg: ExampleConfig): sim.gym.sync_frame_time(sim.sim) # Print error - pos = sim.robot_positions[:, :2] + pos = sim.robot_positions[:, 0, :2] print(torch.linalg.norm(pos - torch.tensor(cfg.goal, device="cuda:0"), axis=1)) return {} diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index c2a6c7a..1c0ea51 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -193,9 +193,16 @@ def start_sim(self): self.ee_positions_buffer = [] # helpfull slices - self.robot_positions = self.root_state[:, 0, 0:3] # [x, y, z] - self.robot_velocities = self.root_state[:, 0, 7:10] # [x, y, z] - self.obstacle_positions = self.root_state[:, 3:, 0:3] # [x, y, z] + #self.robot_positions = self.root_state[:, 0, 0:3] # [x, y, z] + + indices = torch.tensor([i for i, a in enumerate(self.env_cfg) if a.type == "robot"], device="cuda:0") + self.robot_root_states = torch.index_select(self.root_state, 1, indices) + self.robot_positions = self.robot_root_states[:, :, 0:3] + self.robot_velocities = self.robot_root_states[:, :, 7:10] + + indices = torch.tensor([i for i, a in enumerate(self.env_cfg) if a.type in ["sphere", "box"]], device="cuda:0") + self.obstacle_root_states = torch.index_select(self.root_state, 1, indices) + self.obstacle_positions = self.obstacle_root_states[:, :, 0:3] # [x, y, z] if self.ee_link_present: self.ee_positions = self.rigid_body_state[ :, self.robot_rigid_body_ee_idx, 0:3 From c8c4671080122e1763df41f45f6198e21fb5c6b8 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 13:51:10 +0200 Subject: [PATCH 14/26] update point_robot example, and fix priors --- conf/actors/point_robot.yaml | 6 ++++++ conf/config_point_robot.yaml | 7 +++---- examples/point_robot.py | 9 ++++++--- examples/point_robot_with_obstacle.py | 9 ++++++--- mppiisaac/priors/fabrics_panda.py | 5 +++-- mppiisaac/priors/fabrics_point.py | 5 +++-- 6 files changed, 27 insertions(+), 14 deletions(-) create mode 100644 conf/actors/point_robot.yaml diff --git a/conf/actors/point_robot.yaml b/conf/actors/point_robot.yaml new file mode 100644 index 0000000..a774623 --- /dev/null +++ b/conf/actors/point_robot.yaml @@ -0,0 +1,6 @@ +type: robot +name: point_robot +urdf_file: "point_robot.urdf" +flip_visual: false +fixed: true +collision: True diff --git a/conf/config_point_robot.yaml b/conf/config_point_robot.yaml index 8fcaec8..8d85aa1 100644 --- a/conf/config_point_robot.yaml +++ b/conf/config_point_robot.yaml @@ -3,10 +3,9 @@ defaults: - isaacgym: normal goal: [2.0, 2.0] -initial_position: [0.0, 0.0, 0.05] render: true n_steps: 1000 -urdf_file: "point_robot.urdf" -fix_base: true -flip_visual: false nx: 6 + +actors: ['point_robot'] +initial_actor_positions: [[0.0, 0.0, 0.05]] diff --git a/examples/point_robot.py b/examples/point_robot.py index 6ad9e6e..064113b 100644 --- a/examples/point_robot.py +++ b/examples/point_robot.py @@ -3,7 +3,10 @@ from urdfenvs.robots.generic_urdf import GenericUrdfReacher from urdfenvs.urdf_common.urdf_env import UrdfEnv from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import mppiisaac import hydra +import yaml +from yaml import SafeLoader from omegaconf import OmegaConf import os import torch @@ -39,9 +42,9 @@ def initalize_environment(cfg) -> UrdfEnv: render Boolean toggle to set rendering on (True) or off (False). """ - urdf_file = ( - os.path.dirname(os.path.abspath(__file__)) + "/../assets/urdf/" + cfg.urdf_file - ) + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/point_robot.yaml') as f: + heijn_cfg = yaml.load(f, Loader=SafeLoader) + urdf_file = f'{os.path.dirname(mppiisaac.__file__)}/../assets/urdf/' + heijn_cfg['urdf_file'] robots = [ GenericUrdfReacher(urdf=urdf_file, mode="vel"), ] diff --git a/examples/point_robot_with_obstacle.py b/examples/point_robot_with_obstacle.py index e9666c4..2bb63b7 100644 --- a/examples/point_robot_with_obstacle.py +++ b/examples/point_robot_with_obstacle.py @@ -4,7 +4,10 @@ from urdfenvs.urdf_common.urdf_env import UrdfEnv from mppiisaac.planner.isaacgym_wrapper import IsaacGymWrapper from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import mppiisaac import hydra +import yaml +from yaml import SafeLoader from omegaconf import OmegaConf import os import torch @@ -59,9 +62,9 @@ def initalize_environment(cfg) -> UrdfEnv: render Boolean toggle to set rendering on (True) or off (False). """ - urdf_file = ( - os.path.dirname(os.path.abspath(__file__)) + "/../assets/urdf/" + cfg.urdf_file - ) + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/point_robot.yaml') as f: + heijn_cfg = yaml.load(f, Loader=SafeLoader) + urdf_file = f'{os.path.dirname(mppiisaac.__file__)}/../assets/urdf/' + heijn_cfg['urdf_file'] robots = [ GenericUrdfReacher(urdf=urdf_file, mode="vel"), ] diff --git a/mppiisaac/priors/fabrics_panda.py b/mppiisaac/priors/fabrics_panda.py index d7ae849..8dd8cc8 100644 --- a/mppiisaac/priors/fabrics_panda.py +++ b/mppiisaac/priors/fabrics_panda.py @@ -48,14 +48,15 @@ def compute_command(self, sim): vel = np.array(dofs[1::2]) obst_positions = np.array(sim.obstacle_positions[self.env_id].cpu()) + obst_indices = torch.tensor([i for i, a in enumerate(sim.env_cfg) if a.type in ["sphere", "box"]], device="cuda:0") x_obsts = [] radius_obsts = [] for i in range(self.max_num_obstacles): if i < len(obst_positions): x_obsts.append(obst_positions[i]) - if sim.env_cfg[i+3].type == 'sphere': - radius_obsts.append(sim.env_cfg[i + 3].size[0]) + if sim.env_cfg[obst_indices[i]].type == 'sphere': + radius_obsts.append(sim.env_cfg[obst_indices[i]].size[0]) else: radius_obsts.append(0.2) else: diff --git a/mppiisaac/priors/fabrics_point.py b/mppiisaac/priors/fabrics_point.py index 35c30dc..943d17c 100644 --- a/mppiisaac/priors/fabrics_point.py +++ b/mppiisaac/priors/fabrics_point.py @@ -29,14 +29,15 @@ def compute_command(self, sim): vel = np.array([dof_state[1], dof_state[3]]) obst_positions = np.array(sim.obstacle_positions[self.env_id].cpu()) + obst_indices = torch.tensor([i for i, a in enumerate(sim.env_cfg) if a.type in ["sphere", "box"]], device="cuda:0") x_obsts = [] radius_obsts = [] for i in range(self.max_num_obstacles): if i < len(obst_positions): x_obsts.append(obst_positions[i][:2]) - if sim.env_cfg[i+3].type == 'sphere': - radius_obsts.append(sim.env_cfg[i + 3].size[0]) + if sim.env_cfg[obst_indices[i]].type == 'sphere': + radius_obsts.append(sim.env_cfg[obst_indices[i]].size[0]) else: radius_obsts.append(0.2) else: From d1171dff4835b85bd8319a46feced633f91531dc Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 14:13:18 +0200 Subject: [PATCH 15/26] Add multi point robot example --- conf/config_multi_point_robot.yaml | 11 +++ conf/mppi/multi-pointbot.yaml | 25 ++++++ examples/multi_pointbot.py | 134 +++++++++++++++++++++++++++++ mppiisaac/utils/config_store.py | 1 + 4 files changed, 171 insertions(+) create mode 100644 conf/config_multi_point_robot.yaml create mode 100644 conf/mppi/multi-pointbot.yaml create mode 100644 examples/multi_pointbot.py diff --git a/conf/config_multi_point_robot.yaml b/conf/config_multi_point_robot.yaml new file mode 100644 index 0000000..a39f90d --- /dev/null +++ b/conf/config_multi_point_robot.yaml @@ -0,0 +1,11 @@ +defaults: + - mppi: multi-pointbot + - isaacgym: normal + +goal: [1.0, 0.0, -1.0, 0.0] +render: true +n_steps: 1000 +nx: 12 + +actors: ['point_robot', 'point_robot'] +initial_actor_positions: [[-1.0, 0.0, 0.05], [2.0, 0.0, 0.05]] diff --git a/conf/mppi/multi-pointbot.yaml b/conf/mppi/multi-pointbot.yaml new file mode 100644 index 0000000..c991de2 --- /dev/null +++ b/conf/mppi/multi-pointbot.yaml @@ -0,0 +1,25 @@ +defaults: + - base_mppi + +mppi_mode: "halton-spline" # halton-spline, simple +sampling_method: "halton" # halton, random +num_samples: 100 +horizon: 20 # At least 12 for Halton Sampling +device: "cuda:0" +lambda_: 0.1 +u_min: [-1.5] +u_max: [1.5] +noise_sigma: [ + [1., 0., 0., 0., 0., 0.], + [0., 1., 0., 0., 0., 0.], + [0., 0., 1., 0., 0., 0.], + [0., 0., 0., 1., 0., 0.], + [0., 0., 0., 0., 1., 0.], + [0., 0., 0., 0., 0., 1.]] +update_cov: False +rollout_var_discount: 0.95 +sample_null_action: True +noise_abs_cost: False +filter_u: True +use_priors: True + diff --git a/examples/multi_pointbot.py b/examples/multi_pointbot.py new file mode 100644 index 0000000..b2dedec --- /dev/null +++ b/examples/multi_pointbot.py @@ -0,0 +1,134 @@ +import gym +import numpy as np +from urdfenvs.robots.generic_urdf import GenericUrdfReacher +from urdfenvs.urdf_common.urdf_env import UrdfEnv +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +import mppiisaac +import hydra +import yaml +from yaml import SafeLoader +from omegaconf import OmegaConf +import os +import torch +from mpscenes.goals.static_sub_goal import StaticSubGoal +from mppiisaac.utils.config_store import ExampleConfig + +# MPPI to navigate a simple robot to a goal position + + +class Objective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + + def compute_cost(self, sim): + pos = torch.cat( + (sim.dof_state[:, 0].unsqueeze(1), sim.dof_state[:, 2].unsqueeze(1), sim.dof_state[:, 6].unsqueeze(1), sim.dof_state[:, 8].unsqueeze(1)), 1 + ) + + goal_cost = torch.clamp( + torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 + ) + + avoidance_cost = 1 / torch.clamp( + torch.linalg.norm(pos[:, :2] - pos[:, 2:], axis=1) - 0.05, min=0, max=1999 + ) + + return goal_cost #+ avoidance_cost + + + +def initalize_environment(cfg) -> UrdfEnv: + """ + Initializes the simulation environment. + + Adds an obstacle and goal visualizaion to the environment and + steps the simulation once. + + Params + ---------- + render + Boolean toggle to set rendering on (True) or off (False). + """ + with open(f'{os.path.dirname(mppiisaac.__file__)}/../conf/actors/point_robot.yaml') as f: + robot_cfg = yaml.load(f, Loader=SafeLoader) + urdf_file = f'{os.path.dirname(mppiisaac.__file__)}/../assets/urdf/' + robot_cfg['urdf_file'] + robots = [ + GenericUrdfReacher(urdf=urdf_file, mode="vel"), + GenericUrdfReacher(urdf=urdf_file, mode="vel"), + ] + env: UrdfEnv = gym.make("urdf-env-v0", dt=0.05, robots=robots, render=cfg.render) + + env.reset(pos=np.array(cfg.initial_actor_positions)) + # Set the initial position and velocity of the point mass. + #goal_dict = { + # "weight": 1.0, + # "is_primary_goal": True, + # "indices": [0, 1], + # "parent_link": 0, + # "child_link": 1, + # "desired_position": cfg.goal, + # "epsilon": 0.05, + # "type": "staticSubGoal", + #} + #goal = StaticSubGoal(name="simpleGoal", content_dict=goal_dict) + #env.add_goal(goal) + return env + + +def set_planner(cfg): + """ + Initializes the mppi planner for the point robot. + + Params + ---------- + goal_position: np.ndarray + The goal to the motion planning problem. + """ + # urdf = "../assets/point_robot.urdf" + objective = Objective(cfg, cfg.mppi.device) + prior = None + planner = MPPIisaacPlanner(cfg, objective, prior) + + return planner + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_multi_point_robot") +def run_point_robot(cfg: ExampleConfig): + """ + Set the gym environment, the planner and run point robot example. + The initial zero action step is needed to initialize the sensor in the + urdf environment. + + Params + ---------- + n_steps + Total number of simulation steps. + render + Boolean toggle to set rendering on (True) or off (False). + """ + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + env = initalize_environment(cfg) + planner = set_planner(cfg) + + action = np.zeros(int(cfg.nx / 2)) + ob, *_ = env.step(action) + + for _ in range(cfg.n_steps): + # Calculate action with the fabric planner, slice the states to drop Z-axis [3] information. + ob_robot0 = ob["robot_0"] + ob_robot1 = ob["robot_1"] + action = planner.compute_action( + q=list(ob_robot0["joint_state"]["position"]) + list(ob_robot1["joint_state"]["position"]), + qdot=list(ob_robot0["joint_state"]["velocity"]) + list(ob_robot1["joint_state"]["velocity"]), + ) + ( + ob, + *_, + ) = env.step(action) + return {} + + +if __name__ == "__main__": + res = run_point_robot() diff --git a/mppiisaac/utils/config_store.py b/mppiisaac/utils/config_store.py index 8fc2bff..1d49cf1 100644 --- a/mppiisaac/utils/config_store.py +++ b/mppiisaac/utils/config_store.py @@ -20,6 +20,7 @@ class ExampleConfig: cs = ConfigStore.instance() cs.store(name="config_point_robot", node=ExampleConfig) +cs.store(name="config_multi_point_robot", node=ExampleConfig) cs.store(name="config_heijn_robot", node=ExampleConfig) cs.store(name="config_boxer_robot", node=ExampleConfig) cs.store(name="config_jackal_robot", node=ExampleConfig) From 64977e92c3ec12123ec58506cc1891f9bf8f0f53 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 14:19:09 +0200 Subject: [PATCH 16/26] seperate panda c space example --- conf/config_panda_c_space_goal.yaml | 9 +- examples/panda_c_space_goal.py | 143 ++++++++++++++++++++++++++++ 2 files changed, 147 insertions(+), 5 deletions(-) create mode 100644 examples/panda_c_space_goal.py diff --git a/conf/config_panda_c_space_goal.yaml b/conf/config_panda_c_space_goal.yaml index f42e519..2eb0a9b 100644 --- a/conf/config_panda_c_space_goal.yaml +++ b/conf/config_panda_c_space_goal.yaml @@ -1,12 +1,11 @@ defaults: - mppi: panda - - isaacgym: slow + - isaacgym: normal goal: [0.6, 0.0, 0.0, -1.875, 0, 1.875, 0] render: true n_steps: 1000 -urdf_file: "panda_bullet/panda.urdf" -fix_base: true -flip_visual: false -disable_gravity: true +actors: ['panda', 'xaxis', 'yaxis'] +initial_actor_positions: [[0.0, 0.0, 0.0]] + nx: 14 diff --git a/examples/panda_c_space_goal.py b/examples/panda_c_space_goal.py new file mode 100644 index 0000000..d69e670 --- /dev/null +++ b/examples/panda_c_space_goal.py @@ -0,0 +1,143 @@ +import gym +from mpscenes.goals.static_sub_goal import StaticSubGoal +import numpy as np +from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner +from urdfenvs.robots.generic_urdf import GenericUrdfReacher +import hydra +from omegaconf import OmegaConf +import os +import torch +import mppiisaac +from mppiisaac.priors.fabrics_panda import FabricsPandaPrior + +from mppiisaac.utils.config_store import ExampleConfig + +# MPPI to navigate a simple robot to a goal position + +urdf_file = ( + os.path.dirname(os.path.abspath(__file__)) + + "/../assets/urdf/panda_bullet/panda.urdf" +) + + +class JointSpaceGoalObjective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + + def compute_cost(self, sim): + pos = torch.cat( + ( + sim.dof_state[:, 0].unsqueeze(1), + sim.dof_state[:, 2].unsqueeze(1), + sim.dof_state[:, 4].unsqueeze(1), + sim.dof_state[:, 6].unsqueeze(1), + sim.dof_state[:, 8].unsqueeze(1), + sim.dof_state[:, 10].unsqueeze(1), + sim.dof_state[:, 12].unsqueeze(1), + ), + 1, + ) + # dof_states = gym.acquire_dof_state_tensor(sim) + return torch.clamp( + torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 + ) + + +class EndEffectorGoalObjective(object): + def __init__(self, cfg, device): + self.nav_goal = torch.tensor(cfg.goal, device=cfg.mppi.device) + self.ort_goal = torch.tensor([1, 0, 0, 0], device=cfg.mppi.device) + + def compute_cost(self, sim): + pos = sim.rigid_body_state[:, sim.robot_rigid_body_ee_idx, :3] + ort = sim.rigid_body_state[:, sim.robot_rigid_body_ee_idx, 3:7] + # dof_states = gym.acquire_dof_state_tensor(sim) + + reach_cost = torch.linalg.norm(pos - self.nav_goal, axis=1) + align_cost = torch.linalg.norm(ort - self.ort_goal, axis=1) + return 10 * reach_cost + align_cost + # return torch.clamp( + # torch.linalg.norm(pos - self.nav_goal, axis=1) - 0.05, min=0, max=1999 + # ) + + +def initalize_environment(cfg): + """ + Initializes the simulation environment. + + Adds an obstacle and goal visualizaion to the environment and + steps the simulation once. + + Params + ---------- + render + Boolean toggle to set rendering on (True) or off (False). + """ + robots = [ + GenericUrdfReacher(urdf=urdf_file, mode="vel"), + ] + env: UrdfEnv = gym.make("urdf-env-v0", dt=0.01, robots=robots, render=cfg.render) + # Set the initial position and velocity of the panda arm. + env.reset() + return env + + +def set_planner(cfg): + """ + Initializes the mppi planner for the panda arm. + + Params + ---------- + goal_position: np.ndarray + The goal to the motion planning problem. + """ + #objective = EndEffectorGoalObjective(cfg, cfg.mppi.device) + objective = JointSpaceGoalObjective(cfg, cfg.mppi.device) + if cfg.mppi.use_priors == True: + prior = FabricsPandaPrior(cfg) + else: + prior = None + planner = MPPIisaacPlanner(cfg, objective, prior) + + return planner + + +@hydra.main(version_base=None, config_path="../conf", config_name="config_panda_c_space_goal") +def run_panda_robot(cfg: ExampleConfig): + """ + Set the gym environment, the planner and run panda robot example. + The initial zero action step is needed to initialize the sensor in the + urdf environment. + + Params + ---------- + n_steps + Total number of simulation steps. + render + Boolean toggle to set rendering on (True) or off (False). + """ + # Note: Workaround to trigger the dataclasses __post_init__ method + cfg = OmegaConf.to_object(cfg) + + env = initalize_environment(cfg) + planner = set_planner(cfg) + + action = np.zeros(7) + ob, *_ = env.step(action) + + for _ in range(cfg.n_steps): + # Calculate action with the fabric planner, slice the states to drop Z-axis [3] information. + ob_robot = ob["robot_0"] + action = planner.compute_action( + q=ob_robot["joint_state"]["position"], + qdot=ob_robot["joint_state"]["velocity"], + ) + ( + ob, + *_, + ) = env.step(action) + return {} + + +if __name__ == "__main__": + res = run_panda_robot() From 2b5e4fec24e18919344f3f1794bc143c2eda87a9 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Mon, 17 Apr 2023 14:43:45 +0200 Subject: [PATCH 17/26] update poetry stuff --- poetry.lock | 1358 +++++++++++++++++++++++++++++------------------- pyproject.toml | 1 + 2 files changed, 825 insertions(+), 534 deletions(-) diff --git a/poetry.lock b/poetry.lock index 09dbef2..1192a73 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry and should not be changed by hand. +# This file is automatically @generated by Poetry 1.4.2 and should not be changed by hand. [[package]] name = "antlr4-python3-runtime" @@ -13,14 +13,14 @@ files = [ [[package]] name = "astroid" -version = "2.14.1" +version = "2.15.3" description = "An abstract syntax tree for Python with inference support." category = "dev" optional = false python-versions = ">=3.7.2" files = [ - {file = "astroid-2.14.1-py3-none-any.whl", hash = "sha256:23c718921acab5f08cbbbe9293967f1f8fec40c336d19cd75dc12a9ea31d2eb2"}, - {file = "astroid-2.14.1.tar.gz", hash = "sha256:bd1aa4f9915c98e8aaebcd4e71930154d4e8c9aaf05d35ac0a63d1956091ae3f"}, + {file = "astroid-2.15.3-py3-none-any.whl", hash = "sha256:f11e74658da0f2a14a8d19776a8647900870a63de71db83713a8e77a6af52662"}, + {file = "astroid-2.15.3.tar.gz", hash = "sha256:44224ad27c54d770233751315fa7f74c46fa3ee0fab7beef1065f99f09897efe"}, ] [package.dependencies] @@ -30,56 +30,56 @@ wrapt = {version = ">=1.11,<2", markers = "python_version < \"3.11\""} [[package]] name = "attrs" -version = "22.2.0" +version = "23.1.0" description = "Classes Without Boilerplate" category = "main" optional = false -python-versions = ">=3.6" +python-versions = ">=3.7" files = [ - {file = "attrs-22.2.0-py3-none-any.whl", hash = "sha256:29e95c7f6778868dbd49170f98f8818f78f3dc5e0e37c0b1f474e3561b240836"}, - {file = "attrs-22.2.0.tar.gz", hash = "sha256:c9227bfc2f01993c03f68db37d1d15c9690188323c067c641f1a35ca58185f99"}, + {file = "attrs-23.1.0-py3-none-any.whl", hash = "sha256:1f28b4522cdc2fb4256ac1a020c78acf9cba2c6b461ccd2c126f3aa8e8335d04"}, + {file = "attrs-23.1.0.tar.gz", hash = "sha256:6279836d581513a26f1bf235f9acd333bc9115683f14f7e8fae46c98fc50e015"}, ] [package.extras] -cov = ["attrs[tests]", "coverage-enable-subprocess", "coverage[toml] (>=5.3)"] -dev = ["attrs[docs,tests]"] -docs = ["furo", "myst-parser", "sphinx", "sphinx-notfound-page", "sphinxcontrib-towncrier", "towncrier", "zope.interface"] -tests = ["attrs[tests-no-zope]", "zope.interface"] -tests-no-zope = ["cloudpickle", "cloudpickle", "hypothesis", "hypothesis", "mypy (>=0.971,<0.990)", "mypy (>=0.971,<0.990)", "pympler", "pympler", "pytest (>=4.3.0)", "pytest (>=4.3.0)", "pytest-mypy-plugins", "pytest-mypy-plugins", "pytest-xdist[psutil]", "pytest-xdist[psutil]"] +cov = ["attrs[tests]", "coverage[toml] (>=5.3)"] +dev = ["attrs[docs,tests]", "pre-commit"] +docs = ["furo", "myst-parser", "sphinx", "sphinx-notfound-page", "sphinxcontrib-towncrier", "towncrier", "zope-interface"] +tests = ["attrs[tests-no-zope]", "zope-interface"] +tests-no-zope = ["cloudpickle", "hypothesis", "mypy (>=1.1.1)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "pytest-xdist[psutil]"] [[package]] name = "black" -version = "23.1.0" +version = "23.3.0" description = "The uncompromising code formatter." category = "dev" optional = false python-versions = ">=3.7" files = [ - {file = "black-23.1.0-cp310-cp310-macosx_10_16_arm64.whl", hash = "sha256:b6a92a41ee34b883b359998f0c8e6eb8e99803aa8bf3123bf2b2e6fec505a221"}, - {file = "black-23.1.0-cp310-cp310-macosx_10_16_universal2.whl", hash = "sha256:57c18c5165c1dbe291d5306e53fb3988122890e57bd9b3dcb75f967f13411a26"}, - {file = "black-23.1.0-cp310-cp310-macosx_10_16_x86_64.whl", hash = "sha256:9880d7d419bb7e709b37e28deb5e68a49227713b623c72b2b931028ea65f619b"}, - {file = "black-23.1.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e6663f91b6feca5d06f2ccd49a10f254f9298cc1f7f49c46e498a0771b507104"}, - {file = "black-23.1.0-cp310-cp310-win_amd64.whl", hash = "sha256:9afd3f493666a0cd8f8df9a0200c6359ac53940cbde049dcb1a7eb6ee2dd7074"}, - {file = "black-23.1.0-cp311-cp311-macosx_10_16_arm64.whl", hash = "sha256:bfffba28dc52a58f04492181392ee380e95262af14ee01d4bc7bb1b1c6ca8d27"}, - {file = "black-23.1.0-cp311-cp311-macosx_10_16_universal2.whl", hash = "sha256:c1c476bc7b7d021321e7d93dc2cbd78ce103b84d5a4cf97ed535fbc0d6660648"}, - {file = "black-23.1.0-cp311-cp311-macosx_10_16_x86_64.whl", hash = "sha256:382998821f58e5c8238d3166c492139573325287820963d2f7de4d518bd76958"}, - {file = "black-23.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2bf649fda611c8550ca9d7592b69f0637218c2369b7744694c5e4902873b2f3a"}, - {file = "black-23.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:121ca7f10b4a01fd99951234abdbd97728e1240be89fde18480ffac16503d481"}, - {file = "black-23.1.0-cp37-cp37m-macosx_10_16_x86_64.whl", hash = "sha256:a8471939da5e824b891b25751955be52ee7f8a30a916d570a5ba8e0f2eb2ecad"}, - {file = "black-23.1.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8178318cb74f98bc571eef19068f6ab5613b3e59d4f47771582f04e175570ed8"}, - {file = "black-23.1.0-cp37-cp37m-win_amd64.whl", hash = "sha256:a436e7881d33acaf2536c46a454bb964a50eff59b21b51c6ccf5a40601fbef24"}, - {file = "black-23.1.0-cp38-cp38-macosx_10_16_arm64.whl", hash = "sha256:a59db0a2094d2259c554676403fa2fac3473ccf1354c1c63eccf7ae65aac8ab6"}, - {file = "black-23.1.0-cp38-cp38-macosx_10_16_universal2.whl", hash = "sha256:0052dba51dec07ed029ed61b18183942043e00008ec65d5028814afaab9a22fd"}, - {file = "black-23.1.0-cp38-cp38-macosx_10_16_x86_64.whl", hash = "sha256:49f7b39e30f326a34b5c9a4213213a6b221d7ae9d58ec70df1c4a307cf2a1580"}, - {file = "black-23.1.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:162e37d49e93bd6eb6f1afc3e17a3d23a823042530c37c3c42eeeaf026f38468"}, - {file = "black-23.1.0-cp38-cp38-win_amd64.whl", hash = "sha256:8b70eb40a78dfac24842458476135f9b99ab952dd3f2dab738c1881a9b38b753"}, - {file = "black-23.1.0-cp39-cp39-macosx_10_16_arm64.whl", hash = "sha256:a29650759a6a0944e7cca036674655c2f0f63806ddecc45ed40b7b8aa314b651"}, - {file = "black-23.1.0-cp39-cp39-macosx_10_16_universal2.whl", hash = "sha256:bb460c8561c8c1bec7824ecbc3ce085eb50005883a6203dcfb0122e95797ee06"}, - {file = "black-23.1.0-cp39-cp39-macosx_10_16_x86_64.whl", hash = "sha256:c91dfc2c2a4e50df0026f88d2215e166616e0c80e86004d0003ece0488db2739"}, - {file = "black-23.1.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2a951cc83ab535d248c89f300eccbd625e80ab880fbcfb5ac8afb5f01a258ac9"}, - {file = "black-23.1.0-cp39-cp39-win_amd64.whl", hash = "sha256:0680d4380db3719ebcfb2613f34e86c8e6d15ffeabcf8ec59355c5e7b85bb555"}, - {file = "black-23.1.0-py3-none-any.whl", hash = "sha256:7a0f701d314cfa0896b9001df70a530eb2472babb76086344e688829efd97d32"}, - {file = "black-23.1.0.tar.gz", hash = "sha256:b0bd97bea8903f5a2ba7219257a44e3f1f9d00073d6cc1add68f0beec69692ac"}, + {file = "black-23.3.0-cp310-cp310-macosx_10_16_arm64.whl", hash = "sha256:0945e13506be58bf7db93ee5853243eb368ace1c08a24c65ce108986eac65915"}, + {file = "black-23.3.0-cp310-cp310-macosx_10_16_universal2.whl", hash = "sha256:67de8d0c209eb5b330cce2469503de11bca4085880d62f1628bd9972cc3366b9"}, + {file = "black-23.3.0-cp310-cp310-macosx_10_16_x86_64.whl", hash = "sha256:7c3eb7cea23904399866c55826b31c1f55bbcd3890ce22ff70466b907b6775c2"}, + {file = "black-23.3.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:32daa9783106c28815d05b724238e30718f34155653d4d6e125dc7daec8e260c"}, + {file = "black-23.3.0-cp310-cp310-win_amd64.whl", hash = "sha256:35d1381d7a22cc5b2be2f72c7dfdae4072a3336060635718cc7e1ede24221d6c"}, + {file = "black-23.3.0-cp311-cp311-macosx_10_16_arm64.whl", hash = "sha256:a8a968125d0a6a404842fa1bf0b349a568634f856aa08ffaff40ae0dfa52e7c6"}, + {file = "black-23.3.0-cp311-cp311-macosx_10_16_universal2.whl", hash = "sha256:c7ab5790333c448903c4b721b59c0d80b11fe5e9803d8703e84dcb8da56fec1b"}, + {file = "black-23.3.0-cp311-cp311-macosx_10_16_x86_64.whl", hash = "sha256:a6f6886c9869d4daae2d1715ce34a19bbc4b95006d20ed785ca00fa03cba312d"}, + {file = "black-23.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6f3c333ea1dd6771b2d3777482429864f8e258899f6ff05826c3a4fcc5ce3f70"}, + {file = "black-23.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:11c410f71b876f961d1de77b9699ad19f939094c3a677323f43d7a29855fe326"}, + {file = "black-23.3.0-cp37-cp37m-macosx_10_16_x86_64.whl", hash = "sha256:1d06691f1eb8de91cd1b322f21e3bfc9efe0c7ca1f0e1eb1db44ea367dff656b"}, + {file = "black-23.3.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:50cb33cac881766a5cd9913e10ff75b1e8eb71babf4c7104f2e9c52da1fb7de2"}, + {file = "black-23.3.0-cp37-cp37m-win_amd64.whl", hash = "sha256:e114420bf26b90d4b9daa597351337762b63039752bdf72bf361364c1aa05925"}, + {file = "black-23.3.0-cp38-cp38-macosx_10_16_arm64.whl", hash = "sha256:48f9d345675bb7fbc3dd85821b12487e1b9a75242028adad0333ce36ed2a6d27"}, + {file = "black-23.3.0-cp38-cp38-macosx_10_16_universal2.whl", hash = "sha256:714290490c18fb0126baa0fca0a54ee795f7502b44177e1ce7624ba1c00f2331"}, + {file = "black-23.3.0-cp38-cp38-macosx_10_16_x86_64.whl", hash = "sha256:064101748afa12ad2291c2b91c960be28b817c0c7eaa35bec09cc63aa56493c5"}, + {file = "black-23.3.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:562bd3a70495facf56814293149e51aa1be9931567474993c7942ff7d3533961"}, + {file = "black-23.3.0-cp38-cp38-win_amd64.whl", hash = "sha256:e198cf27888ad6f4ff331ca1c48ffc038848ea9f031a3b40ba36aced7e22f2c8"}, + {file = "black-23.3.0-cp39-cp39-macosx_10_16_arm64.whl", hash = "sha256:3238f2aacf827d18d26db07524e44741233ae09a584273aa059066d644ca7b30"}, + {file = "black-23.3.0-cp39-cp39-macosx_10_16_universal2.whl", hash = "sha256:f0bd2f4a58d6666500542b26354978218a9babcdc972722f4bf90779524515f3"}, + {file = "black-23.3.0-cp39-cp39-macosx_10_16_x86_64.whl", hash = "sha256:92c543f6854c28a3c7f39f4d9b7694f9a6eb9d3c5e2ece488c327b6e7ea9b266"}, + {file = "black-23.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a150542a204124ed00683f0db1f5cf1c2aaaa9cc3495b7a3b5976fb136090ab"}, + {file = "black-23.3.0-cp39-cp39-win_amd64.whl", hash = "sha256:6b39abdfb402002b8a7d030ccc85cf5afff64ee90fa4c5aebc531e3ad0175ddb"}, + {file = "black-23.3.0-py3-none-any.whl", hash = "sha256:ec751418022185b0c1bb7d7736e6933d40bbb14c14a0abcf9123d1b159f98dd4"}, + {file = "black-23.3.0.tar.gz", hash = "sha256:1c7b8d606e728a41ea1ccbd7264677e494e87cf630e399262ced92d4a8dac940"}, ] [package.dependencies] @@ -99,52 +99,53 @@ uvloop = ["uvloop (>=0.15.2)"] [[package]] name = "casadi" -version = "3.5.5" +version = "3.6.0" description = "CasADi -- framework for algorithmic differentiation and numeric optimization" category = "main" optional = false python-versions = "*" files = [ - {file = "casadi-3.5.5-cp27-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:d4e49cb46404cef61f83b30bb20ec9597c50ae7f55cfd6b89c17facc74675437"}, - {file = "casadi-3.5.5-cp27-none-manylinux1_i686.whl", hash = "sha256:f08a99e98b0a15083f06b1e221f064a29b3ed9e20617dc55aa8e823f2f732ace"}, - {file = "casadi-3.5.5-cp27-none-manylinux1_x86_64.whl", hash = "sha256:09e103bb597d46aa338fc57bc49270068a1f07be35f9494c9f796dea4b801aeb"}, - {file = "casadi-3.5.5-cp27-none-win32.whl", hash = "sha256:a4ce51e988570160af9ccfbbb1b9679546cbb1865d3a74ef0276f37fd94d91d9"}, - {file = "casadi-3.5.5-cp27-none-win_amd64.whl", hash = "sha256:54d89442058271007ae8573dfa33360bea10e26603545481090b45e8b90c9d10"}, - {file = "casadi-3.5.5-cp34-none-manylinux1_x86_64.whl", hash = "sha256:4143803af909f284400c02f59de4d97e5ba9319de28366215ef55ef261914f9a"}, - {file = "casadi-3.5.5-cp34-none-win32.whl", hash = "sha256:7a624d40c7b5ded7916f6cc65998af4585b4557c9ea65dc1e3a6273ebb2313ec"}, - {file = "casadi-3.5.5-cp34-none-win_amd64.whl", hash = "sha256:3aec6737c282e7fb5be41f6c7d0649e52ce49efb3508f30bada707e809bbbb5f"}, - {file = "casadi-3.5.5-cp35-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:6192e2ed81c15a7dab2554f5f69b134df8d1a982f8d9f13e57bdef93364d2120"}, - {file = "casadi-3.5.5-cp35-none-manylinux1_i686.whl", hash = "sha256:49a8b713f0ff0bbc2f2af2e71c515cdced238786e25ef504f5982618c84c67a7"}, - {file = "casadi-3.5.5-cp35-none-manylinux1_x86_64.whl", hash = "sha256:13277151efc76b221de8ca6b5ab7b8bbdd2b0e139f282866840adf88dfe53bc9"}, - {file = "casadi-3.5.5-cp35-none-manylinux2014_aarch64.whl", hash = "sha256:253569c85f881a6a8fe5e1c0758858edb1ecb4c3d8bce4aee4b52e5dc59fc091"}, - {file = "casadi-3.5.5-cp35-none-win32.whl", hash = "sha256:5de5c3c1381ac303e71fdef75dace34af6e1d50b46ac081051cd209b8b933837"}, - {file = "casadi-3.5.5-cp35-none-win_amd64.whl", hash = "sha256:4932b2b5361013420189dbc8d30e970672d036b37cb382f1c09c3b6cfe651a37"}, - {file = "casadi-3.5.5-cp36-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:2322748a8d5e88750fd2fc0abcdc56cfbad1a8cd538fe0e7d7b6d8ce0cb3fa62"}, - {file = "casadi-3.5.5-cp36-none-manylinux1_i686.whl", hash = "sha256:ab6a600a9b2ea27453d56fd4464ad0db0ae69f5cea42595fcbdaabcd40396440"}, - {file = "casadi-3.5.5-cp36-none-manylinux1_x86_64.whl", hash = "sha256:5f6eb8de31735c14ecc777e3ad77b57767b5f2dbea29265909ef696f51e8be92"}, - {file = "casadi-3.5.5-cp36-none-manylinux2014_aarch64.whl", hash = "sha256:adf20c34ba2cec1840a026023d93cc6d9b3581dfda6a044f434fc75b50c9a2ce"}, - {file = "casadi-3.5.5-cp36-none-win32.whl", hash = "sha256:7309a75b27c57f09b00a61815fb38c40da8e62e3004598e55ea1b8f713d96221"}, - {file = "casadi-3.5.5-cp36-none-win_amd64.whl", hash = "sha256:ab85c7cf772ba54f2718ebe366b836fffff868443f7c0c02389ed0a288cbde1f"}, - {file = "casadi-3.5.5-cp37-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:ec26244f9d9047f1bb401f1b86ff4775e1ddf638f4b4992bbc362a27a6f56673"}, - {file = "casadi-3.5.5-cp37-none-manylinux1_i686.whl", hash = "sha256:1c451a07b2440c00d552e040b6285b6e79b677d2978212368b28b86f5d267669"}, - {file = "casadi-3.5.5-cp37-none-manylinux1_x86_64.whl", hash = "sha256:24fbac649ee26572884029dcd0e108b4a2412cad003a84ed915c4e44a94ecae7"}, - {file = "casadi-3.5.5-cp37-none-manylinux2014_aarch64.whl", hash = "sha256:a06c0b96eb9d3bc88c627eec6e465726934ca0394347dc33efc742b8c91db83d"}, - {file = "casadi-3.5.5-cp37-none-win32.whl", hash = "sha256:36db4c84d8f3aad328faaeaeaa454a633c95a854d78ea188791b147888379342"}, - {file = "casadi-3.5.5-cp37-none-win_amd64.whl", hash = "sha256:643e48f92eaf65eb82964816bb7e7064ddb8239959210fa6168e8bce6fe6ef94"}, - {file = "casadi-3.5.5-cp38-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:6ce7ac8a301a145f98d46db0bfd13bc8b3831a5bb92e8054d531a1f233bb4b93"}, - {file = "casadi-3.5.5-cp38-none-manylinux1_i686.whl", hash = "sha256:473bb86fa64ac9703d74a474514703b4665fa9a384221ced620b5025e64532a7"}, - {file = "casadi-3.5.5-cp38-none-manylinux1_x86_64.whl", hash = "sha256:292e2768280393bad406256e0ef9c30ddcd4867dbd42148b36f9d92a32d9e199"}, - {file = "casadi-3.5.5-cp38-none-manylinux2014_aarch64.whl", hash = "sha256:353a79e50aa84ac5e0d9f04bc3b2d78a2cc8edae3b842d757756449682778944"}, - {file = "casadi-3.5.5-cp38-none-win32.whl", hash = "sha256:77f33cb95be6a49b93d8d6b81f05193676ae09857699cedf8f1a14a4285d077e"}, - {file = "casadi-3.5.5-cp38-none-win_amd64.whl", hash = "sha256:fbf39dcd63f1d3b63c300fce59b7ea678bd5ea1d014e1e090a5226600a4132cb"}, - {file = "casadi-3.5.5-cp39-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:4086669280b2335d235c664373db46dcd7f6485dba4663ce1944ea01753c5e8b"}, - {file = "casadi-3.5.5-cp39-none-manylinux1_i686.whl", hash = "sha256:c3440c90c31b61ae1df82f6c784643393f723354dc08013f9d5cedf25507c67c"}, - {file = "casadi-3.5.5-cp39-none-manylinux1_x86_64.whl", hash = "sha256:bd94048388b602fc30fdac2fecb986c034110ed8d2d17af7fd13b0de45c58bd7"}, - {file = "casadi-3.5.5-cp39-none-manylinux2014_aarch64.whl", hash = "sha256:cd630a2e6ec6df6a4977af63080fa8d63a0053ff8c06ea0200959b47ae75201c"}, - {file = "casadi-3.5.5-cp39-none-win32.whl", hash = "sha256:ac45b91616e9b8afbe266ca08e80770b28e9e6d7a5852e3677fb37e42bde2047"}, - {file = "casadi-3.5.5-cp39-none-win_amd64.whl", hash = "sha256:55df534d003efdd120c4ebfeb6b252c443d273cdc4b97a394eb0268367477795"}, + {file = "casadi-3.6.0-cp27-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:3899643fead68face68b6c30a914eb40b2a2ab144bbda9633391363aa166c095"}, + {file = "casadi-3.6.0-cp27-none-manylinux1_i686.whl", hash = "sha256:68853772e53940ddd5c8e7f25580365ce576fdbf2089dafec730ae7bba50dd81"}, + {file = "casadi-3.6.0-cp27-none-manylinux2010_x86_64.whl", hash = "sha256:a33613b9ebc124bd92d68072e6a78fff1ee2baf18f28808e6bd6596e603122f2"}, + {file = "casadi-3.6.0-cp27-none-win_amd64.whl", hash = "sha256:7b3844bc5037f168304da25b2108e455c2b956caffff609e2119e533a1859a2c"}, + {file = "casadi-3.6.0-cp310-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:e952e28293fec517ca2ac5b06e74af48d6c36ce31d8263aeae4192e2f62748e4"}, + {file = "casadi-3.6.0-cp310-none-macosx_11_0_arm64.whl", hash = "sha256:8757a045c39c7a8a4274f87f5cd76c54f2c54c8dd7e477802dc825e522e7c470"}, + {file = "casadi-3.6.0-cp310-none-manylinux2014_i686.whl", hash = "sha256:5822c5331c604ab111834f5d85ad2d1c8d3f7d3bc7b2875c72449b184712cebe"}, + {file = "casadi-3.6.0-cp310-none-manylinux2014_x86_64.whl", hash = "sha256:86add80a229dc0a19cc96ec29ccd0a9079f19d1438afc3abb06d01528a5bad58"}, + {file = "casadi-3.6.0-cp310-none-win_amd64.whl", hash = "sha256:96d842af014ccd650f5a6803a459e478ed8246650e03f1a9270de56a90662c0e"}, + {file = "casadi-3.6.0-cp311-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:ef1950e22474b2c4020f1a87dc1936e11049ddf0da2eaeffbcbc412a1e776a07"}, + {file = "casadi-3.6.0-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:01e0b59e56303468478e516d76ecdada172b1698ffdfbf9255bdd404fbd74c9b"}, + {file = "casadi-3.6.0-cp311-none-manylinux2014_i686.whl", hash = "sha256:97eb9fd2ea835f6685fff2d5315a73ec8668ac49e0fbb0721c195ad071df1cf2"}, + {file = "casadi-3.6.0-cp311-none-manylinux2014_x86_64.whl", hash = "sha256:0ddff10a071b1d5db7cfc40ddf370062309141fefa5ae0789364dda36ecdcac8"}, + {file = "casadi-3.6.0-cp311-none-win_amd64.whl", hash = "sha256:c808ebbbfb779981f9a499b0296c462839a678182e2a5c4287a0fbf3756aae32"}, + {file = "casadi-3.6.0-cp35-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:6027a97848f98c08b2d4f291618c53cea0f83def47e24f02e9c2964c9252c014"}, + {file = "casadi-3.6.0-cp35-none-manylinux2010_x86_64.whl", hash = "sha256:8f2d2cf19dbbfad765be2fbb4c9281805cc9b99fd20b7b3171034965ef9afd77"}, + {file = "casadi-3.6.0-cp35-none-win_amd64.whl", hash = "sha256:488fb3bb8d0cc25c86fcdddf0d0765af53f55e8478e61badc9e5bd015f94ba14"}, + {file = "casadi-3.6.0-cp36-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:f5974c5f91297af836f263a5f7f35bc8faea1792c4b70de64914c56335568b3e"}, + {file = "casadi-3.6.0-cp36-none-manylinux2014_i686.whl", hash = "sha256:e7ceeb824fb9e5fa34f3145e9c27b9953773ca645e85f14a3673ba592f2d2b74"}, + {file = "casadi-3.6.0-cp36-none-manylinux2014_x86_64.whl", hash = "sha256:e3e464e518724db3a6c69bba821582fbe6a472f5040cddb39334c67364874433"}, + {file = "casadi-3.6.0-cp36-none-win_amd64.whl", hash = "sha256:47c383bc5f2371a49b2d81d2b964b90c05f88381323118c07a9ecff82c818c3e"}, + {file = "casadi-3.6.0-cp37-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:3a0902814666b5e7d6b4f744c670d80489bfae9a339ddeafcbedf3abc64f3e50"}, + {file = "casadi-3.6.0-cp37-none-manylinux2014_i686.whl", hash = "sha256:20e214b6d5b63d424f9f241680cb4ff39385856d8562329c4bd63a93bbb3405b"}, + {file = "casadi-3.6.0-cp37-none-manylinux2014_x86_64.whl", hash = "sha256:a2720dd43ffff78be9e32d9b84e8f9da75bbab99831dbff2b68c8716114119a2"}, + {file = "casadi-3.6.0-cp37-none-win_amd64.whl", hash = "sha256:e67b3c4b2303083c15c9745ad0c7691690a99400c24767a4e3ccd9f522c33755"}, + {file = "casadi-3.6.0-cp38-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:7e27c3009e0e2f56d405a510af20351bbfa32faa1132796230c8630f3b6942ea"}, + {file = "casadi-3.6.0-cp38-none-macosx_11_0_arm64.whl", hash = "sha256:3423bf2b9123f520278d795136b946f03690f53eecd58ee9497a8a851909d006"}, + {file = "casadi-3.6.0-cp38-none-manylinux2014_i686.whl", hash = "sha256:fe68be77b4fa2090586e8f43ce6ba5018c0467a669725967ef76ec64325f8fe3"}, + {file = "casadi-3.6.0-cp38-none-manylinux2014_x86_64.whl", hash = "sha256:e06c29bcbd6d7625cee4a68719bae4961b9e06f29568fcf7ad1beddb97ed5a0b"}, + {file = "casadi-3.6.0-cp38-none-win_amd64.whl", hash = "sha256:2f3d59988ddedb43b9f604a50d542e187f5e4dbe4b2fb4c6ec056d25924daa6b"}, + {file = "casadi-3.6.0-cp39-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:74967f40baf98ef6a00af27effaff27a1ffdf528eb47372f20f946e886d17572"}, + {file = "casadi-3.6.0-cp39-none-macosx_11_0_arm64.whl", hash = "sha256:3fd0024e6a25c86bfd5e01c4e6c4ebd4168f78073f9515224d0bab8db735672b"}, + {file = "casadi-3.6.0-cp39-none-manylinux2014_i686.whl", hash = "sha256:54d73033ac17249d4c2a95c1e8a06dfcbbcad1accadeaff5a4128d38e2b0dd0a"}, + {file = "casadi-3.6.0-cp39-none-manylinux2014_x86_64.whl", hash = "sha256:a02a9bf641ec8864b183c0bb4d1c179b6584c012e743fa2346d291a198239347"}, + {file = "casadi-3.6.0-cp39-none-win_amd64.whl", hash = "sha256:c1a7d253b12d103086a1d0f573fb6e860285909f71368be3d38b8651038cfd57"}, + {file = "casadi-3.6.0.tar.gz", hash = "sha256:d04151f64c6a9d0a973821ff484ed8bf2ec79ea3a629e6371b0d6957bda2f55f"}, ] +[package.dependencies] +numpy = "*" + [[package]] name = "certifi" version = "2022.12.7" @@ -161,7 +162,7 @@ files = [ name = "cffi" version = "1.15.1" description = "Foreign Function Interface for Python calling C code." -category = "main" +category = "dev" optional = false python-versions = "*" files = [ @@ -248,100 +249,87 @@ files = [ [[package]] name = "charset-normalizer" -version = "3.0.1" +version = "3.1.0" description = "The Real First Universal Charset Detector. Open, modern and actively maintained alternative to Chardet." category = "main" optional = false -python-versions = "*" +python-versions = ">=3.7.0" files = [ - {file = "charset-normalizer-3.0.1.tar.gz", hash = "sha256:ebea339af930f8ca5d7a699b921106c6e29c617fe9606fa7baa043c1cdae326f"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:88600c72ef7587fe1708fd242b385b6ed4b8904976d5da0893e31df8b3480cb6"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:c75ffc45f25324e68ab238cb4b5c0a38cd1c3d7f1fb1f72b5541de469e2247db"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:db72b07027db150f468fbada4d85b3b2729a3db39178abf5c543b784c1254539"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:62595ab75873d50d57323a91dd03e6966eb79c41fa834b7a1661ed043b2d404d"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ff6f3db31555657f3163b15a6b7c6938d08df7adbfc9dd13d9d19edad678f1e8"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:772b87914ff1152b92a197ef4ea40efe27a378606c39446ded52c8f80f79702e"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:70990b9c51340e4044cfc394a81f614f3f90d41397104d226f21e66de668730d"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:292d5e8ba896bbfd6334b096e34bffb56161c81408d6d036a7dfa6929cff8783"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:2edb64ee7bf1ed524a1da60cdcd2e1f6e2b4f66ef7c077680739f1641f62f555"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:31a9ddf4718d10ae04d9b18801bd776693487cbb57d74cc3458a7673f6f34639"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:44ba614de5361b3e5278e1241fda3dc1838deed864b50a10d7ce92983797fa76"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:12db3b2c533c23ab812c2b25934f60383361f8a376ae272665f8e48b88e8e1c6"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:c512accbd6ff0270939b9ac214b84fb5ada5f0409c44298361b2f5e13f9aed9e"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-win32.whl", hash = "sha256:502218f52498a36d6bf5ea77081844017bf7982cdbe521ad85e64cabee1b608b"}, - {file = "charset_normalizer-3.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:601f36512f9e28f029d9481bdaf8e89e5148ac5d89cffd3b05cd533eeb423b59"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:0298eafff88c99982a4cf66ba2efa1128e4ddaca0b05eec4c456bbc7db691d8d"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a8d0fc946c784ff7f7c3742310cc8a57c5c6dc31631269876a88b809dbeff3d3"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:87701167f2a5c930b403e9756fab1d31d4d4da52856143b609e30a1ce7160f3c"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:14e76c0f23218b8f46c4d87018ca2e441535aed3632ca134b10239dfb6dadd6b"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:0c0a590235ccd933d9892c627dec5bc7511ce6ad6c1011fdf5b11363022746c1"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8c7fe7afa480e3e82eed58e0ca89f751cd14d767638e2550c77a92a9e749c317"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:79909e27e8e4fcc9db4addea88aa63f6423ebb171db091fb4373e3312cb6d603"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8ac7b6a045b814cf0c47f3623d21ebd88b3e8cf216a14790b455ea7ff0135d18"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:72966d1b297c741541ca8cf1223ff262a6febe52481af742036a0b296e35fa5a"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:f9d0c5c045a3ca9bedfc35dca8526798eb91a07aa7a2c0fee134c6c6f321cbd7"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:5995f0164fa7df59db4746112fec3f49c461dd6b31b841873443bdb077c13cfc"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:4a8fcf28c05c1f6d7e177a9a46a1c52798bfe2ad80681d275b10dcf317deaf0b"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:761e8904c07ad053d285670f36dd94e1b6ab7f16ce62b9805c475b7aa1cffde6"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-win32.whl", hash = "sha256:71140351489970dfe5e60fc621ada3e0f41104a5eddaca47a7acb3c1b851d6d3"}, - {file = "charset_normalizer-3.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:9ab77acb98eba3fd2a85cd160851816bfce6871d944d885febf012713f06659c"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:84c3990934bae40ea69a82034912ffe5a62c60bbf6ec5bc9691419641d7d5c9a"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:74292fc76c905c0ef095fe11e188a32ebd03bc38f3f3e9bcb85e4e6db177b7ea"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c95a03c79bbe30eec3ec2b7f076074f4281526724c8685a42872974ef4d36b72"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f4c39b0e3eac288fedc2b43055cfc2ca7a60362d0e5e87a637beac5d801ef478"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:df2c707231459e8a4028eabcd3cfc827befd635b3ef72eada84ab13b52e1574d"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:93ad6d87ac18e2a90b0fe89df7c65263b9a99a0eb98f0a3d2e079f12a0735837"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:59e5686dd847347e55dffcc191a96622f016bc0ad89105e24c14e0d6305acbc6"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:cd6056167405314a4dc3c173943f11249fa0f1b204f8b51ed4bde1a9cd1834dc"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-musllinux_1_1_ppc64le.whl", hash = "sha256:083c8d17153ecb403e5e1eb76a7ef4babfc2c48d58899c98fcaa04833e7a2f9a"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-musllinux_1_1_s390x.whl", hash = "sha256:f5057856d21e7586765171eac8b9fc3f7d44ef39425f85dbcccb13b3ebea806c"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:7eb33a30d75562222b64f569c642ff3dc6689e09adda43a082208397f016c39a"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-win32.whl", hash = "sha256:95dea361dd73757c6f1c0a1480ac499952c16ac83f7f5f4f84f0658a01b8ef41"}, - {file = "charset_normalizer-3.0.1-cp36-cp36m-win_amd64.whl", hash = "sha256:eaa379fcd227ca235d04152ca6704c7cb55564116f8bc52545ff357628e10602"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:3e45867f1f2ab0711d60c6c71746ac53537f1684baa699f4f668d4c6f6ce8e14"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cadaeaba78750d58d3cc6ac4d1fd867da6fc73c88156b7a3212a3cd4819d679d"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:911d8a40b2bef5b8bbae2e36a0b103f142ac53557ab421dc16ac4aafee6f53dc"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:503e65837c71b875ecdd733877d852adbc465bd82c768a067badd953bf1bc5a3"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a60332922359f920193b1d4826953c507a877b523b2395ad7bc716ddd386d866"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:16a8663d6e281208d78806dbe14ee9903715361cf81f6d4309944e4d1e59ac5b"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:a16418ecf1329f71df119e8a65f3aa68004a3f9383821edcb20f0702934d8087"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:9d9153257a3f70d5f69edf2325357251ed20f772b12e593f3b3377b5f78e7ef8"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-musllinux_1_1_ppc64le.whl", hash = "sha256:02a51034802cbf38db3f89c66fb5d2ec57e6fe7ef2f4a44d070a593c3688667b"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-musllinux_1_1_s390x.whl", hash = "sha256:2e396d70bc4ef5325b72b593a72c8979999aa52fb8bcf03f701c1b03e1166918"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:11b53acf2411c3b09e6af37e4b9005cba376c872503c8f28218c7243582df45d"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-win32.whl", hash = "sha256:0bf2dae5291758b6f84cf923bfaa285632816007db0330002fa1de38bfcb7154"}, - {file = "charset_normalizer-3.0.1-cp37-cp37m-win_amd64.whl", hash = "sha256:2c03cc56021a4bd59be889c2b9257dae13bf55041a3372d3295416f86b295fb5"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:024e606be3ed92216e2b6952ed859d86b4cfa52cd5bc5f050e7dc28f9b43ec42"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:4b0d02d7102dd0f997580b51edc4cebcf2ab6397a7edf89f1c73b586c614272c"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:358a7c4cb8ba9b46c453b1dd8d9e431452d5249072e4f56cfda3149f6ab1405e"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:81d6741ab457d14fdedc215516665050f3822d3e56508921cc7239f8c8e66a58"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8b8af03d2e37866d023ad0ddea594edefc31e827fee64f8de5611a1dbc373174"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9cf4e8ad252f7c38dd1f676b46514f92dc0ebeb0db5552f5f403509705e24753"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e696f0dd336161fca9adbb846875d40752e6eba585843c768935ba5c9960722b"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c22d3fe05ce11d3671297dc8973267daa0f938b93ec716e12e0f6dee81591dc1"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:109487860ef6a328f3eec66f2bf78b0b72400280d8f8ea05f69c51644ba6521a"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:37f8febc8ec50c14f3ec9637505f28e58d4f66752207ea177c1d67df25da5aed"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:f97e83fa6c25693c7a35de154681fcc257c1c41b38beb0304b9c4d2d9e164479"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:a152f5f33d64a6be73f1d30c9cc82dfc73cec6477ec268e7c6e4c7d23c2d2291"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:39049da0ffb96c8cbb65cbf5c5f3ca3168990adf3551bd1dee10c48fce8ae820"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-win32.whl", hash = "sha256:4457ea6774b5611f4bed5eaa5df55f70abde42364d498c5134b7ef4c6958e20e"}, - {file = "charset_normalizer-3.0.1-cp38-cp38-win_amd64.whl", hash = "sha256:e62164b50f84e20601c1ff8eb55620d2ad25fb81b59e3cd776a1902527a788af"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:8eade758719add78ec36dc13201483f8e9b5d940329285edcd5f70c0a9edbd7f"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:8499ca8f4502af841f68135133d8258f7b32a53a1d594aa98cc52013fff55678"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:3fc1c4a2ffd64890aebdb3f97e1278b0cc72579a08ca4de8cd2c04799a3a22be"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:00d3ffdaafe92a5dc603cb9bd5111aaa36dfa187c8285c543be562e61b755f6b"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c2ac1b08635a8cd4e0cbeaf6f5e922085908d48eb05d44c5ae9eabab148512ca"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f6f45710b4459401609ebebdbcfb34515da4fc2aa886f95107f556ac69a9147e"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3ae1de54a77dc0d6d5fcf623290af4266412a7c4be0b1ff7444394f03f5c54e3"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3b590df687e3c5ee0deef9fc8c547d81986d9a1b56073d82de008744452d6541"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:ab5de034a886f616a5668aa5d098af2b5385ed70142090e2a31bcbd0af0fdb3d"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:9cb3032517f1627cc012dbc80a8ec976ae76d93ea2b5feaa9d2a5b8882597579"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:608862a7bf6957f2333fc54ab4399e405baad0163dc9f8d99cb236816db169d4"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:0f438ae3532723fb6ead77e7c604be7c8374094ef4ee2c5e03a3a17f1fca256c"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:356541bf4381fa35856dafa6a965916e54bed415ad8a24ee6de6e37deccf2786"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-win32.whl", hash = "sha256:39cf9ed17fe3b1bc81f33c9ceb6ce67683ee7526e65fde1447c772afc54a1bb8"}, - {file = "charset_normalizer-3.0.1-cp39-cp39-win_amd64.whl", hash = "sha256:0a11e971ed097d24c534c037d298ad32c6ce81a45736d31e0ff0ad37ab437d59"}, - {file = "charset_normalizer-3.0.1-py3-none-any.whl", hash = "sha256:7e189e2e1d3ed2f4aebabd2d5b0f931e883676e51c7624826e0a4e5fe8a0bf24"}, + {file = "charset-normalizer-3.1.0.tar.gz", hash = "sha256:34e0a2f9c370eb95597aae63bf85eb5e96826d81e3dcf88b8886012906f509b5"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:e0ac8959c929593fee38da1c2b64ee9778733cdf03c482c9ff1d508b6b593b2b"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:d7fc3fca01da18fbabe4625d64bb612b533533ed10045a2ac3dd194bfa656b60"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:04eefcee095f58eaabe6dc3cc2262f3bcd776d2c67005880894f447b3f2cb9c1"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:20064ead0717cf9a73a6d1e779b23d149b53daf971169289ed2ed43a71e8d3b0"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1435ae15108b1cb6fffbcea2af3d468683b7afed0169ad718451f8db5d1aff6f"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c84132a54c750fda57729d1e2599bb598f5fa0344085dbde5003ba429a4798c0"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:75f2568b4189dda1c567339b48cba4ac7384accb9c2a7ed655cd86b04055c795"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:11d3bcb7be35e7b1bba2c23beedac81ee893ac9871d0ba79effc7fc01167db6c"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:891cf9b48776b5c61c700b55a598621fdb7b1e301a550365571e9624f270c203"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:5f008525e02908b20e04707a4f704cd286d94718f48bb33edddc7d7b584dddc1"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:b06f0d3bf045158d2fb8837c5785fe9ff9b8c93358be64461a1089f5da983137"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:49919f8400b5e49e961f320c735388ee686a62327e773fa5b3ce6721f7e785ce"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:22908891a380d50738e1f978667536f6c6b526a2064156203d418f4856d6e86a"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-win32.whl", hash = "sha256:12d1a39aa6b8c6f6248bb54550efcc1c38ce0d8096a146638fd4738e42284448"}, + {file = "charset_normalizer-3.1.0-cp310-cp310-win_amd64.whl", hash = "sha256:65ed923f84a6844de5fd29726b888e58c62820e0769b76565480e1fdc3d062f8"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9a3267620866c9d17b959a84dd0bd2d45719b817245e49371ead79ed4f710d19"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6734e606355834f13445b6adc38b53c0fd45f1a56a9ba06c2058f86893ae8017"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f8303414c7b03f794347ad062c0516cee0e15f7a612abd0ce1e25caf6ceb47df"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:aaf53a6cebad0eae578f062c7d462155eada9c172bd8c4d250b8c1d8eb7f916a"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3dc5b6a8ecfdc5748a7e429782598e4f17ef378e3e272eeb1340ea57c9109f41"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e1b25e3ad6c909f398df8921780d6a3d120d8c09466720226fc621605b6f92b1"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0ca564606d2caafb0abe6d1b5311c2649e8071eb241b2d64e75a0d0065107e62"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b82fab78e0b1329e183a65260581de4375f619167478dddab510c6c6fb04d9b6"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:bd7163182133c0c7701b25e604cf1611c0d87712e56e88e7ee5d72deab3e76b5"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:11d117e6c63e8f495412d37e7dc2e2fff09c34b2d09dbe2bee3c6229577818be"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:cf6511efa4801b9b38dc5546d7547d5b5c6ef4b081c60b23e4d941d0eba9cbeb"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:abc1185d79f47c0a7aaf7e2412a0eb2c03b724581139193d2d82b3ad8cbb00ac"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:cb7b2ab0188829593b9de646545175547a70d9a6e2b63bf2cd87a0a391599324"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-win32.whl", hash = "sha256:c36bcbc0d5174a80d6cccf43a0ecaca44e81d25be4b7f90f0ed7bcfbb5a00909"}, + {file = "charset_normalizer-3.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:cca4def576f47a09a943666b8f829606bcb17e2bc2d5911a46c8f8da45f56755"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:0c95f12b74681e9ae127728f7e5409cbbef9cd914d5896ef238cc779b8152373"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fca62a8301b605b954ad2e9c3666f9d97f63872aa4efcae5492baca2056b74ab"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ac0aa6cd53ab9a31d397f8303f92c42f534693528fafbdb997c82bae6e477ad9"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c3af8e0f07399d3176b179f2e2634c3ce9c1301379a6b8c9c9aeecd481da494f"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a5fc78f9e3f501a1614a98f7c54d3969f3ad9bba8ba3d9b438c3bc5d047dd28"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:628c985afb2c7d27a4800bfb609e03985aaecb42f955049957814e0491d4006d"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:74db0052d985cf37fa111828d0dd230776ac99c740e1a758ad99094be4f1803d"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:1e8fcdd8f672a1c4fc8d0bd3a2b576b152d2a349782d1eb0f6b8e52e9954731d"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-musllinux_1_1_ppc64le.whl", hash = "sha256:04afa6387e2b282cf78ff3dbce20f0cc071c12dc8f685bd40960cc68644cfea6"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-musllinux_1_1_s390x.whl", hash = "sha256:dd5653e67b149503c68c4018bf07e42eeed6b4e956b24c00ccdf93ac79cdff84"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:d2686f91611f9e17f4548dbf050e75b079bbc2a82be565832bc8ea9047b61c8c"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-win32.whl", hash = "sha256:4155b51ae05ed47199dc5b2a4e62abccb274cee6b01da5b895099b61b1982974"}, + {file = "charset_normalizer-3.1.0-cp37-cp37m-win_amd64.whl", hash = "sha256:322102cdf1ab682ecc7d9b1c5eed4ec59657a65e1c146a0da342b78f4112db23"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:e633940f28c1e913615fd624fcdd72fdba807bf53ea6925d6a588e84e1151531"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:3a06f32c9634a8705f4ca9946d667609f52cf130d5548881401f1eb2c39b1e2c"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:7381c66e0561c5757ffe616af869b916c8b4e42b367ab29fedc98481d1e74e14"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3573d376454d956553c356df45bb824262c397c6e26ce43e8203c4c540ee0acb"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e89df2958e5159b811af9ff0f92614dabf4ff617c03a4c1c6ff53bf1c399e0e1"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:78cacd03e79d009d95635e7d6ff12c21eb89b894c354bd2b2ed0b4763373693b"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:de5695a6f1d8340b12a5d6d4484290ee74d61e467c39ff03b39e30df62cf83a0"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1c60b9c202d00052183c9be85e5eaf18a4ada0a47d188a83c8f5c5b23252f649"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:f645caaf0008bacf349875a974220f1f1da349c5dbe7c4ec93048cdc785a3326"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:ea9f9c6034ea2d93d9147818f17c2a0860d41b71c38b9ce4d55f21b6f9165a11"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:80d1543d58bd3d6c271b66abf454d437a438dff01c3e62fdbcd68f2a11310d4b"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:73dc03a6a7e30b7edc5b01b601e53e7fc924b04e1835e8e407c12c037e81adbd"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:6f5c2e7bc8a4bf7c426599765b1bd33217ec84023033672c1e9a8b35eaeaaaf8"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-win32.whl", hash = "sha256:12a2b561af122e3d94cdb97fe6fb2bb2b82cef0cdca131646fdb940a1eda04f0"}, + {file = "charset_normalizer-3.1.0-cp38-cp38-win_amd64.whl", hash = "sha256:3160a0fd9754aab7d47f95a6b63ab355388d890163eb03b2d2b87ab0a30cfa59"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:38e812a197bf8e71a59fe55b757a84c1f946d0ac114acafaafaf21667a7e169e"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:6baf0baf0d5d265fa7944feb9f7451cc316bfe30e8df1a61b1bb08577c554f31"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:8f25e17ab3039b05f762b0a55ae0b3632b2e073d9c8fc88e89aca31a6198e88f"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3747443b6a904001473370d7810aa19c3a180ccd52a7157aacc264a5ac79265e"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b116502087ce8a6b7a5f1814568ccbd0e9f6cfd99948aa59b0e241dc57cf739f"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d16fd5252f883eb074ca55cb622bc0bee49b979ae4e8639fff6ca3ff44f9f854"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:21fa558996782fc226b529fdd2ed7866c2c6ec91cee82735c98a197fae39f706"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6f6c7a8a57e9405cad7485f4c9d3172ae486cfef1344b5ddd8e5239582d7355e"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:ac3775e3311661d4adace3697a52ac0bab17edd166087d493b52d4f4f553f9f0"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:10c93628d7497c81686e8e5e557aafa78f230cd9e77dd0c40032ef90c18f2230"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:6f4f4668e1831850ebcc2fd0b1cd11721947b6dc7c00bf1c6bd3c929ae14f2c7"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:0be65ccf618c1e7ac9b849c315cc2e8a8751d9cfdaa43027d4f6624bd587ab7e"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:53d0a3fa5f8af98a1e261de6a3943ca631c526635eb5817a87a59d9a57ebf48f"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-win32.whl", hash = "sha256:a04f86f41a8916fe45ac5024ec477f41f886b3c435da2d4e3d2709b22ab02af1"}, + {file = "charset_normalizer-3.1.0-cp39-cp39-win_amd64.whl", hash = "sha256:830d2948a5ec37c386d3170c483063798d7879037492540f10a475e3fd6f244b"}, + {file = "charset_normalizer-3.1.0-py3-none-any.whl", hash = "sha256:3d9098b479e78c85080c98e1e35ff40b4a31d8953102bb0fd7d1b6f8a2111a3d"}, ] [[package]] @@ -371,6 +359,36 @@ files = [ {file = "cloudpickle-2.2.1.tar.gz", hash = "sha256:d89684b8de9e34a2a43b3460fbca07d09d6e25ce858df4d5a44240403b6178f5"}, ] +[[package]] +name = "cmake" +version = "3.26.3" +description = "CMake is an open-source, cross-platform family of tools designed to build, test and package software" +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "cmake-3.26.3-py2.py3-none-macosx_10_10_universal2.macosx_10_10_x86_64.macosx_11_0_arm64.macosx_11_0_universal2.whl", hash = "sha256:9d38ea5b4999f8f042a071bea3e213f085bac26d7ab54cb5a4c6a193c4baf132"}, + {file = "cmake-3.26.3-py2.py3-none-manylinux2010_i686.manylinux_2_12_i686.whl", hash = "sha256:6e5fcd1cfaac33d015e2709e0dd1b7ad352a315367012ac359c9adc062cf075b"}, + {file = "cmake-3.26.3-py2.py3-none-manylinux2010_x86_64.manylinux_2_12_x86_64.whl", hash = "sha256:4d3185738a6405aa15801e684f8d589b00570da4cc676cb1b5bbc902e3023e53"}, + {file = "cmake-3.26.3-py2.py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:b20f7f7ea316ce7bb158df0e3c3453cfab5048939f1291017d16a8a36ad33ae6"}, + {file = "cmake-3.26.3-py2.py3-none-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:46aa385e19c9e4fc95d7d6ce5ee0bbe0d69bdeac4e9bc95c61f78f3973c2f626"}, + {file = "cmake-3.26.3-py2.py3-none-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:71e1df5587ad860b9829211380c42fc90ef2413363f12805b1fa2d87769bf876"}, + {file = "cmake-3.26.3-py2.py3-none-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:543b6958d1615327f484a07ab041029b1740918a8baa336adc9f5f0cbcd8fbd8"}, + {file = "cmake-3.26.3-py2.py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1bc7b47456256bdcc41069f5c658f232bd6e15bf4796d115f6ec98800793daff"}, + {file = "cmake-3.26.3-py2.py3-none-musllinux_1_1_aarch64.whl", hash = "sha256:2ae3db2c2be50fdaf0c9f3a23b2206e9dcd55ca124f16486a841b939f50b595e"}, + {file = "cmake-3.26.3-py2.py3-none-musllinux_1_1_i686.whl", hash = "sha256:1798547b23b89030518c5668dc55aed0e1d01867cf91d7a94e15d33f62a56fd0"}, + {file = "cmake-3.26.3-py2.py3-none-musllinux_1_1_ppc64le.whl", hash = "sha256:d3017a08e6ba53ec2486d89a7953a81d4c4a068fc9f29d83e209f295dd9c59f3"}, + {file = "cmake-3.26.3-py2.py3-none-musllinux_1_1_s390x.whl", hash = "sha256:a922a6f6c1580d0db17b0b75f82e619441dd43c7f1d6a35f7d27e709db48bdbb"}, + {file = "cmake-3.26.3-py2.py3-none-musllinux_1_1_x86_64.whl", hash = "sha256:e0ed796530641c8a21a423f9bb7882117dbbeee11ec78dbc335402a678d937ae"}, + {file = "cmake-3.26.3-py2.py3-none-win32.whl", hash = "sha256:27a6fa1b97744311a7993d6a1e0ce14bd73696dab9ceb96701f1ec11edbd5053"}, + {file = "cmake-3.26.3-py2.py3-none-win_amd64.whl", hash = "sha256:cf910bbb488659d300c86b1dac77e44eeb0457bde2cf76a42d7e51f691544b21"}, + {file = "cmake-3.26.3-py2.py3-none-win_arm64.whl", hash = "sha256:24741a304ada699b339034958777d9a1472ac8ddb9b6194d74f814287ca091ae"}, + {file = "cmake-3.26.3.tar.gz", hash = "sha256:b54cde1f1c0573321b22382bd2ffaf5d08f65188572d128cd4867fb9669723c5"}, +] + +[package.extras] +test = ["codecov (>=2.0.5)", "coverage (>=4.2)", "flake8 (>=3.0.4)", "path.py (>=11.5.0)", "pytest (>=3.0.3)", "pytest-cov (>=2.4.0)", "pytest-runner (>=2.9)", "pytest-virtualenv (>=1.7.0)", "scikit-build (>=0.10.0)", "setuptools (>=28.0.0)", "virtualenv (>=15.0.3)", "wheel"] + [[package]] name = "colorama" version = "0.4.6" @@ -433,14 +451,14 @@ graph = ["objgraph (>=1.7.2)"] [[package]] name = "exceptiongroup" -version = "1.1.0" +version = "1.1.1" description = "Backport of PEP 654 (exception groups)" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "exceptiongroup-1.1.0-py3-none-any.whl", hash = "sha256:327cbda3da756e2de031a3107b81ab7b3770a602c4d16ca618298c526f4bec1e"}, - {file = "exceptiongroup-1.1.0.tar.gz", hash = "sha256:bcb67d800a4497e1b404c2dd44fca47d3b7a5e5433dbab67f96c1a685cdfdf23"}, + {file = "exceptiongroup-1.1.1-py3-none-any.whl", hash = "sha256:232c37c63e4f682982c8b6459f33a8981039e5fb8756b2074364e5055c498c9e"}, + {file = "exceptiongroup-1.1.1.tar.gz", hash = "sha256:d484c3090ba2889ae2928419117447a14daf3c1231d5e30d0aae34f354f01785"}, ] [package.extras] @@ -448,14 +466,14 @@ test = ["pytest (>=6)"] [[package]] name = "fabrics" -version = "0.6.2" +version = "0.6.3" description = "Optimization fabrics in python." category = "main" optional = false python-versions = ">=3.8,<3.10" files = [ - {file = "fabrics-0.6.2-py3-none-any.whl", hash = "sha256:72604fcf9fa416a0b3caa2ca39b1945f6f4f1857770d0fa37370685caca8707f"}, - {file = "fabrics-0.6.2.tar.gz", hash = "sha256:8db31c045e986412a64b7988031c30708ab8bff26312f6bc5174d79ebbffe37e"}, + {file = "fabrics-0.6.3-py3-none-any.whl", hash = "sha256:612662c7e70c1ab223ea073caf0842b5aa2b6685de3e392e5f319afa50231d30"}, + {file = "fabrics-0.6.3.tar.gz", hash = "sha256:62cf127df62d039177c3d8b06296be17bed8c8e2ce26e5109eaf36dc51fe5d96"}, ] [package.dependencies] @@ -468,6 +486,22 @@ pickle-mixin = ">=1.0.2,<2.0.0" pyquaternion = ">=0.9.9,<0.10.0" quaternionic = ">=1.0.0,<2.0.0" +[[package]] +name = "filelock" +version = "3.11.0" +description = "A platform independent file lock." +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "filelock-3.11.0-py3-none-any.whl", hash = "sha256:f08a52314748335c6460fc8fe40cd5638b85001225db78c2aa01c8c0db83b318"}, + {file = "filelock-3.11.0.tar.gz", hash = "sha256:3618c0da67adcc0506b015fd11ef7faf1b493f0b40d87728e19986b536890c37"}, +] + +[package.extras] +docs = ["furo (>=2023.3.27)", "sphinx (>=6.1.3)", "sphinx-autodoc-typehints (>=1.22,!=1.23.4)"] +testing = ["covdefaults (>=2.3)", "coverage (>=7.2.2)", "diff-cover (>=7.5)", "pytest (>=7.2.2)", "pytest-cov (>=4)", "pytest-mock (>=3.10)", "pytest-timeout (>=2.1)"] + [[package]] name = "forwardkinematics" version = "1.1.1" @@ -489,7 +523,7 @@ urdf_parser_py = ">=0.0.3" name = "future" version = "0.18.3" description = "Clean single-source support for Python 3 and 2" -category = "main" +category = "dev" optional = false python-versions = ">=2.6, !=3.0.*, !=3.1.*, !=3.2.*" files = [ @@ -512,7 +546,7 @@ files = [ name = "gevent" version = "22.10.2" description = "Coroutine-based network library" -category = "main" +category = "dev" optional = false python-versions = ">=2.7,!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5" files = [ @@ -620,7 +654,7 @@ files = [ name = "greenlet" version = "2.0.2" description = "Lightweight in-process concurrent programming" -category = "main" +category = "dev" optional = false python-versions = ">=2.7,!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*" files = [ @@ -732,14 +766,14 @@ files = [ [[package]] name = "hydra-core" -version = "1.3.1" +version = "1.3.2" description = "A framework for elegantly configuring complex applications" category = "main" optional = false python-versions = "*" files = [ - {file = "hydra-core-1.3.1.tar.gz", hash = "sha256:8dd42d551befc43dfca0c612cbd58c4f3e273dbd97a87214c1a030ba557d238b"}, - {file = "hydra_core-1.3.1-py3-none-any.whl", hash = "sha256:d1c8b273eba0be68218c4ff1ae9a7df7430ce4aa580f1bbebc03297029761cf4"}, + {file = "hydra-core-1.3.2.tar.gz", hash = "sha256:8a878ed67216997c3e9d88a8e72e7b4767e81af37afb4ea3334b269a4390a824"}, + {file = "hydra_core-1.3.2-py3-none-any.whl", hash = "sha256:fa0238a9e31df3373b35b0bfb672c34cc92718d21f81311d8996a16de1141d8b"}, ] [package.dependencies] @@ -762,14 +796,14 @@ files = [ [[package]] name = "imageio" -version = "2.25.0" +version = "2.27.0" description = "Library for reading and writing a wide range of image, video, scientific, and volumetric data formats." category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "imageio-2.25.0-py3-none-any.whl", hash = "sha256:9ef2fdef1235eef849b1aea399f08508493624a2a2c8cc3bba957dabb7d0b79f"}, - {file = "imageio-2.25.0.tar.gz", hash = "sha256:b80796a1f8c38c697a940a2ad7397ee28900d5c4e51061b9a67d16aca867f33e"}, + {file = "imageio-2.27.0-py3-none-any.whl", hash = "sha256:24c6ad7d000e64eacc2861c402b6fb128f370cb0a6623cf796d83bca0d0d14d3"}, + {file = "imageio-2.27.0.tar.gz", hash = "sha256:ee269c957785ef0373cc7a7323185956d83ec05e6cdf20b42a03ba7b74ac58c6"}, ] [package.dependencies] @@ -777,32 +811,31 @@ numpy = "*" pillow = ">=8.3.2" [package.extras] -all-plugins = ["astropy", "av", "imageio-ffmpeg", "opencv-python", "psutil", "tifffile"] +all-plugins = ["astropy", "av", "imageio-ffmpeg", "psutil", "tifffile"] all-plugins-pypy = ["av", "imageio-ffmpeg", "psutil", "tifffile"] build = ["wheel"] dev = ["black", "flake8", "fsspec[github]", "invoke", "pytest", "pytest-cov"] docs = ["numpydoc", "pydata-sphinx-theme", "sphinx (<6)"] ffmpeg = ["imageio-ffmpeg", "psutil"] fits = ["astropy"] -full = ["astropy", "av", "black", "flake8", "fsspec[github]", "gdal", "imageio-ffmpeg", "invoke", "itk", "numpydoc", "opencv-python", "psutil", "pydata-sphinx-theme", "pytest", "pytest-cov", "sphinx (<6)", "tifffile", "wheel"] +full = ["astropy", "av", "black", "flake8", "fsspec[github]", "gdal", "imageio-ffmpeg", "invoke", "itk", "numpydoc", "psutil", "pydata-sphinx-theme", "pytest", "pytest-cov", "sphinx (<6)", "tifffile", "wheel"] gdal = ["gdal"] itk = ["itk"] linting = ["black", "flake8"] -opencv = ["opencv-python"] pyav = ["av"] test = ["fsspec[github]", "invoke", "pytest", "pytest-cov"] tifffile = ["tifffile"] [[package]] name = "importlib-metadata" -version = "6.0.0" +version = "6.4.1" description = "Read metadata from Python packages" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "importlib_metadata-6.0.0-py3-none-any.whl", hash = "sha256:7efb448ec9a5e313a57655d35aa54cd3e01b7e1fbcf72dce1bf06119420f5bad"}, - {file = "importlib_metadata-6.0.0.tar.gz", hash = "sha256:e354bedeb60efa6affdcc8ae121b73544a7aa74156d047311948f6d711cd378d"}, + {file = "importlib_metadata-6.4.1-py3-none-any.whl", hash = "sha256:63ace321e24167d12fbb176b6015f4dbe06868c54a2af4f15849586afb9027fd"}, + {file = "importlib_metadata-6.4.1.tar.gz", hash = "sha256:eb1a7933041f0f85c94cd130258df3fb0dec060ad8c1c9318892ef4192c47ce1"}, ] [package.dependencies] @@ -815,14 +848,14 @@ testing = ["flake8 (<5)", "flufl.flake8", "importlib-resources (>=1.3)", "packag [[package]] name = "importlib-resources" -version = "5.10.2" +version = "5.12.0" description = "Read resources from Python packages" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "importlib_resources-5.10.2-py3-none-any.whl", hash = "sha256:7d543798b0beca10b6a01ac7cafda9f822c54db9e8376a6bf57e0cbd74d486b6"}, - {file = "importlib_resources-5.10.2.tar.gz", hash = "sha256:e4a96c8cc0339647ff9a5e0550d9f276fc5a01ffa276012b58ec108cfd7b8484"}, + {file = "importlib_resources-5.12.0-py3-none-any.whl", hash = "sha256:7b1deeebbf351c7578e09bf2f63fa2ce8b5ffec296e0d349139d43cca061a81a"}, + {file = "importlib_resources-5.12.0.tar.gz", hash = "sha256:4be82589bf5c1d7999aedf2a45159d10cb3ca4f19b2271f8792bc8e6da7b22f6"}, ] [package.dependencies] @@ -886,6 +919,24 @@ pipfile-deprecated-finder = ["pip-shims (>=0.5.2)", "pipreqs", "requirementslib" plugins = ["setuptools"] requirements-deprecated-finder = ["pip-api", "pipreqs"] +[[package]] +name = "jinja2" +version = "3.1.2" +description = "A very fast and expressive template engine." +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "Jinja2-3.1.2-py3-none-any.whl", hash = "sha256:6088930bfe239f0e6710546ab9c19c9ef35e29792895fed6e6e31a023a182a61"}, + {file = "Jinja2-3.1.2.tar.gz", hash = "sha256:31351a702a408a9e7595a8fc6150fc3f43bb6bf7e319770cbc0db9df9437e852"}, +] + +[package.dependencies] +MarkupSafe = ">=2.0" + +[package.extras] +i18n = ["Babel (>=2.7)"] + [[package]] name = "jsonschema" version = "4.17.3" @@ -954,6 +1005,17 @@ files = [ {file = "lazy_object_proxy-1.9.0-cp39-cp39-win_amd64.whl", hash = "sha256:db1c1722726f47e10e0b5fdbf15ac3b8adb58c091d12b3ab713965795036985f"}, ] +[[package]] +name = "lit" +version = "16.0.1" +description = "A Software Testing Tool" +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "lit-16.0.1.tar.gz", hash = "sha256:630a47291b714cb115015df23ab04267c24fe59aec7ecd7e637d5c75cdb45c91"}, +] + [[package]] name = "llvmlite" version = "0.39.1" @@ -1160,6 +1222,66 @@ numpy = "*" [package.extras] test = ["pytest"] +[[package]] +name = "markupsafe" +version = "2.1.2" +description = "Safely add untrusted strings to HTML/XML markup." +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "MarkupSafe-2.1.2-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:665a36ae6f8f20a4676b53224e33d456a6f5a72657d9c83c2aa00765072f31f7"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:340bea174e9761308703ae988e982005aedf427de816d1afe98147668cc03036"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:22152d00bf4a9c7c83960521fc558f55a1adbc0631fbb00a9471e097b19d72e1"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:28057e985dace2f478e042eaa15606c7efccb700797660629da387eb289b9323"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ca244fa73f50a800cf8c3ebf7fd93149ec37f5cb9596aa8873ae2c1d23498601"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:d9d971ec1e79906046aa3ca266de79eac42f1dbf3612a05dc9368125952bd1a1"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:7e007132af78ea9df29495dbf7b5824cb71648d7133cf7848a2a5dd00d36f9ff"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:7313ce6a199651c4ed9d7e4cfb4aa56fe923b1adf9af3b420ee14e6d9a73df65"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-win32.whl", hash = "sha256:c4a549890a45f57f1ebf99c067a4ad0cb423a05544accaf2b065246827ed9603"}, + {file = "MarkupSafe-2.1.2-cp310-cp310-win_amd64.whl", hash = "sha256:835fb5e38fd89328e9c81067fd642b3593c33e1e17e2fdbf77f5676abb14a156"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2ec4f2d48ae59bbb9d1f9d7efb9236ab81429a764dedca114f5fdabbc3788013"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:608e7073dfa9e38a85d38474c082d4281f4ce276ac0010224eaba11e929dd53a"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:65608c35bfb8a76763f37036547f7adfd09270fbdbf96608be2bead319728fcd"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f2bfb563d0211ce16b63c7cb9395d2c682a23187f54c3d79bfec33e6705473c6"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:da25303d91526aac3672ee6d49a2f3db2d9502a4a60b55519feb1a4c7714e07d"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:9cad97ab29dfc3f0249b483412c85c8ef4766d96cdf9dcf5a1e3caa3f3661cf1"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:085fd3201e7b12809f9e6e9bc1e5c96a368c8523fad5afb02afe3c051ae4afcc"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:1bea30e9bf331f3fef67e0a3877b2288593c98a21ccb2cf29b74c581a4eb3af0"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-win32.whl", hash = "sha256:7df70907e00c970c60b9ef2938d894a9381f38e6b9db73c5be35e59d92e06625"}, + {file = "MarkupSafe-2.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:e55e40ff0cc8cc5c07996915ad367fa47da6b3fc091fdadca7f5403239c5fec3"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:a6e40afa7f45939ca356f348c8e23048e02cb109ced1eb8420961b2f40fb373a"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf877ab4ed6e302ec1d04952ca358b381a882fbd9d1b07cccbfd61783561f98a"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:63ba06c9941e46fa389d389644e2d8225e0e3e5ebcc4ff1ea8506dce646f8c8a"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f1cd098434e83e656abf198f103a8207a8187c0fc110306691a2e94a78d0abb2"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:55f44b440d491028addb3b88f72207d71eeebfb7b5dbf0643f7c023ae1fba619"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:a6f2fcca746e8d5910e18782f976489939d54a91f9411c32051b4aab2bd7c513"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:0b462104ba25f1ac006fdab8b6a01ebbfbce9ed37fd37fd4acd70c67c973e460"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-win32.whl", hash = "sha256:7668b52e102d0ed87cb082380a7e2e1e78737ddecdde129acadb0eccc5423859"}, + {file = "MarkupSafe-2.1.2-cp37-cp37m-win_amd64.whl", hash = "sha256:6d6607f98fcf17e534162f0709aaad3ab7a96032723d8ac8750ffe17ae5a0666"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:a806db027852538d2ad7555b203300173dd1b77ba116de92da9afbc3a3be3eed"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:a4abaec6ca3ad8660690236d11bfe28dfd707778e2442b45addd2f086d6ef094"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f03a532d7dee1bed20bc4884194a16160a2de9ffc6354b3878ec9682bb623c54"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4cf06cdc1dda95223e9d2d3c58d3b178aa5dacb35ee7e3bbac10e4e1faacb419"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:22731d79ed2eb25059ae3df1dfc9cb1546691cc41f4e3130fe6bfbc3ecbbecfa"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:f8ffb705ffcf5ddd0e80b65ddf7bed7ee4f5a441ea7d3419e861a12eaf41af58"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:8db032bf0ce9022a8e41a22598eefc802314e81b879ae093f36ce9ddf39ab1ba"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:2298c859cfc5463f1b64bd55cb3e602528db6fa0f3cfd568d3605c50678f8f03"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-win32.whl", hash = "sha256:50c42830a633fa0cf9e7d27664637532791bfc31c731a87b202d2d8ac40c3ea2"}, + {file = "MarkupSafe-2.1.2-cp38-cp38-win_amd64.whl", hash = "sha256:bb06feb762bade6bf3c8b844462274db0c76acc95c52abe8dbed28ae3d44a147"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:99625a92da8229df6d44335e6fcc558a5037dd0a760e11d84be2260e6f37002f"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:8bca7e26c1dd751236cfb0c6c72d4ad61d986e9a41bbf76cb445f69488b2a2bd"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:40627dcf047dadb22cd25ea7ecfe9cbf3bbbad0482ee5920b582f3809c97654f"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40dfd3fefbef579ee058f139733ac336312663c6706d1163b82b3003fb1925c4"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:090376d812fb6ac5f171e5938e82e7f2d7adc2b629101cec0db8b267815c85e2"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:2e7821bffe00aa6bd07a23913b7f4e01328c3d5cc0b40b36c0bd81d362faeb65"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:c0a33bc9f02c2b17c3ea382f91b4db0e6cde90b63b296422a939886a7a80de1c"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:b8526c6d437855442cdd3d87eede9c425c4445ea011ca38d937db299382e6fa3"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-win32.whl", hash = "sha256:137678c63c977754abe9086a3ec011e8fd985ab90631145dfb9294ad09c102a7"}, + {file = "MarkupSafe-2.1.2-cp39-cp39-win_amd64.whl", hash = "sha256:0576fe974b40a400449768941d5d0858cc624e3249dfd1e0c33674e5c7ca7aed"}, + {file = "MarkupSafe-2.1.2.tar.gz", hash = "sha256:abcabc8c2b26036d62d4c746381a6f7cf60aafcc653198ad678306986b09450d"}, +] + [[package]] name = "mccabe" version = "0.7.0" @@ -1174,18 +1296,20 @@ files = [ [[package]] name = "mpmath" -version = "1.2.1" +version = "1.3.0" description = "Python library for arbitrary-precision floating-point arithmetic" category = "main" optional = false python-versions = "*" files = [ - {file = "mpmath-1.2.1-py3-none-any.whl", hash = "sha256:604bc21bd22d2322a177c73bdb573994ef76e62edd595d17e00aff24b0667e5c"}, - {file = "mpmath-1.2.1.tar.gz", hash = "sha256:79ffb45cf9f4b101a807595bcb3e72e0396202e0b1d25d689134b48c4216a81a"}, + {file = "mpmath-1.3.0-py3-none-any.whl", hash = "sha256:a0b2b9fe80bbcd81a6647ff13108738cfb482d481d826cc0e02f5b35e5c88d2c"}, + {file = "mpmath-1.3.0.tar.gz", hash = "sha256:7a28eb2a9774d00c7bc92411c19a89209d5da7c4c9a9e227be8330a23a25b91f"}, ] [package.extras] develop = ["codecov", "pycodestyle", "pytest (>=4.6)", "pytest-cov", "wheel"] +docs = ["sphinx"] +gmpy = ["gmpy2 (>=2.1.0a4)"] tests = ["pytest (>=4.6)"] [[package]] @@ -1213,94 +1337,105 @@ bullet = ["pybullet (>=3.2.3,<4.0.0)"] [[package]] name = "msgpack" -version = "1.0.4" +version = "1.0.5" description = "MessagePack serializer" -category = "main" +category = "dev" optional = false python-versions = "*" files = [ - {file = "msgpack-1.0.4-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:4ab251d229d10498e9a2f3b1e68ef64cb393394ec477e3370c457f9430ce9250"}, - {file = "msgpack-1.0.4-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:112b0f93202d7c0fef0b7810d465fde23c746a2d482e1e2de2aafd2ce1492c88"}, - {file = "msgpack-1.0.4-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:002b5c72b6cd9b4bafd790f364b8480e859b4712e91f43014fe01e4f957b8467"}, - {file = "msgpack-1.0.4-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:35bc0faa494b0f1d851fd29129b2575b2e26d41d177caacd4206d81502d4c6a6"}, - {file = "msgpack-1.0.4-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4733359808c56d5d7756628736061c432ded018e7a1dff2d35a02439043321aa"}, - {file = "msgpack-1.0.4-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:eb514ad14edf07a1dbe63761fd30f89ae79b42625731e1ccf5e1f1092950eaa6"}, - {file = "msgpack-1.0.4-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:c23080fdeec4716aede32b4e0ef7e213c7b1093eede9ee010949f2a418ced6ba"}, - {file = "msgpack-1.0.4-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:49565b0e3d7896d9ea71d9095df15b7f75a035c49be733051c34762ca95bbf7e"}, - {file = "msgpack-1.0.4-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:aca0f1644d6b5a73eb3e74d4d64d5d8c6c3d577e753a04c9e9c87d07692c58db"}, - {file = "msgpack-1.0.4-cp310-cp310-win32.whl", hash = "sha256:0dfe3947db5fb9ce52aaea6ca28112a170db9eae75adf9339a1aec434dc954ef"}, - {file = "msgpack-1.0.4-cp310-cp310-win_amd64.whl", hash = "sha256:4dea20515f660aa6b7e964433b1808d098dcfcabbebeaaad240d11f909298075"}, - {file = "msgpack-1.0.4-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:e83f80a7fec1a62cf4e6c9a660e39c7f878f603737a0cdac8c13131d11d97f52"}, - {file = "msgpack-1.0.4-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3c11a48cf5e59026ad7cb0dc29e29a01b5a66a3e333dc11c04f7e991fc5510a9"}, - {file = "msgpack-1.0.4-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1276e8f34e139aeff1c77a3cefb295598b504ac5314d32c8c3d54d24fadb94c9"}, - {file = "msgpack-1.0.4-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6c9566f2c39ccced0a38d37c26cc3570983b97833c365a6044edef3574a00c08"}, - {file = "msgpack-1.0.4-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:fcb8a47f43acc113e24e910399376f7277cf8508b27e5b88499f053de6b115a8"}, - {file = "msgpack-1.0.4-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:76ee788122de3a68a02ed6f3a16bbcd97bc7c2e39bd4d94be2f1821e7c4a64e6"}, - {file = "msgpack-1.0.4-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:0a68d3ac0104e2d3510de90a1091720157c319ceeb90d74f7b5295a6bee51bae"}, - {file = "msgpack-1.0.4-cp36-cp36m-win32.whl", hash = "sha256:85f279d88d8e833ec015650fd15ae5eddce0791e1e8a59165318f371158efec6"}, - {file = "msgpack-1.0.4-cp36-cp36m-win_amd64.whl", hash = "sha256:c1683841cd4fa45ac427c18854c3ec3cd9b681694caf5bff04edb9387602d661"}, - {file = "msgpack-1.0.4-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:a75dfb03f8b06f4ab093dafe3ddcc2d633259e6c3f74bb1b01996f5d8aa5868c"}, - {file = "msgpack-1.0.4-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9667bdfdf523c40d2511f0e98a6c9d3603be6b371ae9a238b7ef2dc4e7a427b0"}, - {file = "msgpack-1.0.4-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:11184bc7e56fd74c00ead4f9cc9a3091d62ecb96e97653add7a879a14b003227"}, - {file = "msgpack-1.0.4-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ac5bd7901487c4a1dd51a8c58f2632b15d838d07ceedaa5e4c080f7190925bff"}, - {file = "msgpack-1.0.4-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:1e91d641d2bfe91ba4c52039adc5bccf27c335356055825c7f88742c8bb900dd"}, - {file = "msgpack-1.0.4-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:2a2df1b55a78eb5f5b7d2a4bb221cd8363913830145fad05374a80bf0877cb1e"}, - {file = "msgpack-1.0.4-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:545e3cf0cf74f3e48b470f68ed19551ae6f9722814ea969305794645da091236"}, - {file = "msgpack-1.0.4-cp37-cp37m-win32.whl", hash = "sha256:2cc5ca2712ac0003bcb625c96368fd08a0f86bbc1a5578802512d87bc592fe44"}, - {file = "msgpack-1.0.4-cp37-cp37m-win_amd64.whl", hash = "sha256:eba96145051ccec0ec86611fe9cf693ce55f2a3ce89c06ed307de0e085730ec1"}, - {file = "msgpack-1.0.4-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:7760f85956c415578c17edb39eed99f9181a48375b0d4a94076d84148cf67b2d"}, - {file = "msgpack-1.0.4-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:449e57cc1ff18d3b444eb554e44613cffcccb32805d16726a5494038c3b93dab"}, - {file = "msgpack-1.0.4-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:d603de2b8d2ea3f3bcb2efe286849aa7a81531abc52d8454da12f46235092bcb"}, - {file = "msgpack-1.0.4-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:48f5d88c99f64c456413d74a975bd605a9b0526293218a3b77220a2c15458ba9"}, - {file = "msgpack-1.0.4-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6916c78f33602ecf0509cc40379271ba0f9ab572b066bd4bdafd7434dee4bc6e"}, - {file = "msgpack-1.0.4-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:81fc7ba725464651190b196f3cd848e8553d4d510114a954681fd0b9c479d7e1"}, - {file = "msgpack-1.0.4-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:d5b5b962221fa2c5d3a7f8133f9abffc114fe218eb4365e40f17732ade576c8e"}, - {file = "msgpack-1.0.4-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:77ccd2af37f3db0ea59fb280fa2165bf1b096510ba9fe0cc2bf8fa92a22fdb43"}, - {file = "msgpack-1.0.4-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:b17be2478b622939e39b816e0aa8242611cc8d3583d1cd8ec31b249f04623243"}, - {file = "msgpack-1.0.4-cp38-cp38-win32.whl", hash = "sha256:2bb8cdf50dd623392fa75525cce44a65a12a00c98e1e37bf0fb08ddce2ff60d2"}, - {file = "msgpack-1.0.4-cp38-cp38-win_amd64.whl", hash = "sha256:26b8feaca40a90cbe031b03d82b2898bf560027160d3eae1423f4a67654ec5d6"}, - {file = "msgpack-1.0.4-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:462497af5fd4e0edbb1559c352ad84f6c577ffbbb708566a0abaaa84acd9f3ae"}, - {file = "msgpack-1.0.4-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:2999623886c5c02deefe156e8f869c3b0aaeba14bfc50aa2486a0415178fce55"}, - {file = "msgpack-1.0.4-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:f0029245c51fd9473dc1aede1160b0a29f4a912e6b1dd353fa6d317085b219da"}, - {file = "msgpack-1.0.4-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ed6f7b854a823ea44cf94919ba3f727e230da29feb4a99711433f25800cf747f"}, - {file = "msgpack-1.0.4-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0df96d6eaf45ceca04b3f3b4b111b86b33785683d682c655063ef8057d61fd92"}, - {file = "msgpack-1.0.4-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6a4192b1ab40f8dca3f2877b70e63799d95c62c068c84dc028b40a6cb03ccd0f"}, - {file = "msgpack-1.0.4-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:0e3590f9fb9f7fbc36df366267870e77269c03172d086fa76bb4eba8b2b46624"}, - {file = "msgpack-1.0.4-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:1576bd97527a93c44fa856770197dec00d223b0b9f36ef03f65bac60197cedf8"}, - {file = "msgpack-1.0.4-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:63e29d6e8c9ca22b21846234913c3466b7e4ee6e422f205a2988083de3b08cae"}, - {file = "msgpack-1.0.4-cp39-cp39-win32.whl", hash = "sha256:fb62ea4b62bfcb0b380d5680f9a4b3f9a2d166d9394e9bbd9666c0ee09a3645c"}, - {file = "msgpack-1.0.4-cp39-cp39-win_amd64.whl", hash = "sha256:4d5834a2a48965a349da1c5a79760d94a1a0172fbb5ab6b5b33cbf8447e109ce"}, - {file = "msgpack-1.0.4.tar.gz", hash = "sha256:f5d869c18f030202eb412f08b28d2afeea553d6613aee89e200d7aca7ef01f5f"}, + {file = "msgpack-1.0.5-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:525228efd79bb831cf6830a732e2e80bc1b05436b086d4264814b4b2955b2fa9"}, + {file = "msgpack-1.0.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:4f8d8b3bf1ff2672567d6b5c725a1b347fe838b912772aa8ae2bf70338d5a198"}, + {file = "msgpack-1.0.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:cdc793c50be3f01106245a61b739328f7dccc2c648b501e237f0699fe1395b81"}, + {file = "msgpack-1.0.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5cb47c21a8a65b165ce29f2bec852790cbc04936f502966768e4aae9fa763cb7"}, + {file = "msgpack-1.0.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e42b9594cc3bf4d838d67d6ed62b9e59e201862a25e9a157019e171fbe672dd3"}, + {file = "msgpack-1.0.5-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:55b56a24893105dc52c1253649b60f475f36b3aa0fc66115bffafb624d7cb30b"}, + {file = "msgpack-1.0.5-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:1967f6129fc50a43bfe0951c35acbb729be89a55d849fab7686004da85103f1c"}, + {file = "msgpack-1.0.5-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:20a97bf595a232c3ee6d57ddaadd5453d174a52594bf9c21d10407e2a2d9b3bd"}, + {file = "msgpack-1.0.5-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:d25dd59bbbbb996eacf7be6b4ad082ed7eacc4e8f3d2df1ba43822da9bfa122a"}, + {file = "msgpack-1.0.5-cp310-cp310-win32.whl", hash = "sha256:382b2c77589331f2cb80b67cc058c00f225e19827dbc818d700f61513ab47bea"}, + {file = "msgpack-1.0.5-cp310-cp310-win_amd64.whl", hash = "sha256:4867aa2df9e2a5fa5f76d7d5565d25ec76e84c106b55509e78c1ede0f152659a"}, + {file = "msgpack-1.0.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9f5ae84c5c8a857ec44dc180a8b0cc08238e021f57abdf51a8182e915e6299f0"}, + {file = "msgpack-1.0.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:9e6ca5d5699bcd89ae605c150aee83b5321f2115695e741b99618f4856c50898"}, + {file = "msgpack-1.0.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5494ea30d517a3576749cad32fa27f7585c65f5f38309c88c6d137877fa28a5a"}, + {file = "msgpack-1.0.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1ab2f3331cb1b54165976a9d976cb251a83183631c88076613c6c780f0d6e45a"}, + {file = "msgpack-1.0.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:28592e20bbb1620848256ebc105fc420436af59515793ed27d5c77a217477705"}, + {file = "msgpack-1.0.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fe5c63197c55bce6385d9aee16c4d0641684628f63ace85f73571e65ad1c1e8d"}, + {file = "msgpack-1.0.5-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ed40e926fa2f297e8a653c954b732f125ef97bdd4c889f243182299de27e2aa9"}, + {file = "msgpack-1.0.5-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:b2de4c1c0538dcb7010902a2b97f4e00fc4ddf2c8cda9749af0e594d3b7fa3d7"}, + {file = "msgpack-1.0.5-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:bf22a83f973b50f9d38e55c6aade04c41ddda19b00c4ebc558930d78eecc64ed"}, + {file = "msgpack-1.0.5-cp311-cp311-win32.whl", hash = "sha256:c396e2cc213d12ce017b686e0f53497f94f8ba2b24799c25d913d46c08ec422c"}, + {file = "msgpack-1.0.5-cp311-cp311-win_amd64.whl", hash = "sha256:6c4c68d87497f66f96d50142a2b73b97972130d93677ce930718f68828b382e2"}, + {file = "msgpack-1.0.5-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:a2b031c2e9b9af485d5e3c4520f4220d74f4d222a5b8dc8c1a3ab9448ca79c57"}, + {file = "msgpack-1.0.5-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4f837b93669ce4336e24d08286c38761132bc7ab29782727f8557e1eb21b2080"}, + {file = "msgpack-1.0.5-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b1d46dfe3832660f53b13b925d4e0fa1432b00f5f7210eb3ad3bb9a13c6204a6"}, + {file = "msgpack-1.0.5-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:366c9a7b9057e1547f4ad51d8facad8b406bab69c7d72c0eb6f529cf76d4b85f"}, + {file = "msgpack-1.0.5-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:4c075728a1095efd0634a7dccb06204919a2f67d1893b6aa8e00497258bf926c"}, + {file = "msgpack-1.0.5-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:f933bbda5a3ee63b8834179096923b094b76f0c7a73c1cfe8f07ad608c58844b"}, + {file = "msgpack-1.0.5-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:36961b0568c36027c76e2ae3ca1132e35123dcec0706c4b7992683cc26c1320c"}, + {file = "msgpack-1.0.5-cp36-cp36m-win32.whl", hash = "sha256:b5ef2f015b95f912c2fcab19c36814963b5463f1fb9049846994b007962743e9"}, + {file = "msgpack-1.0.5-cp36-cp36m-win_amd64.whl", hash = "sha256:288e32b47e67f7b171f86b030e527e302c91bd3f40fd9033483f2cacc37f327a"}, + {file = "msgpack-1.0.5-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:137850656634abddfb88236008339fdaba3178f4751b28f270d2ebe77a563b6c"}, + {file = "msgpack-1.0.5-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0c05a4a96585525916b109bb85f8cb6511db1c6f5b9d9cbcbc940dc6b4be944b"}, + {file = "msgpack-1.0.5-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:56a62ec00b636583e5cb6ad313bbed36bb7ead5fa3a3e38938503142c72cba4f"}, + {file = "msgpack-1.0.5-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ef8108f8dedf204bb7b42994abf93882da1159728a2d4c5e82012edd92c9da9f"}, + {file = "msgpack-1.0.5-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:1835c84d65f46900920b3708f5ba829fb19b1096c1800ad60bae8418652a951d"}, + {file = "msgpack-1.0.5-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:e57916ef1bd0fee4f21c4600e9d1da352d8816b52a599c46460e93a6e9f17086"}, + {file = "msgpack-1.0.5-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:17358523b85973e5f242ad74aa4712b7ee560715562554aa2134d96e7aa4cbbf"}, + {file = "msgpack-1.0.5-cp37-cp37m-win32.whl", hash = "sha256:cb5aaa8c17760909ec6cb15e744c3ebc2ca8918e727216e79607b7bbce9c8f77"}, + {file = "msgpack-1.0.5-cp37-cp37m-win_amd64.whl", hash = "sha256:ab31e908d8424d55601ad7075e471b7d0140d4d3dd3272daf39c5c19d936bd82"}, + {file = "msgpack-1.0.5-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:b72d0698f86e8d9ddf9442bdedec15b71df3598199ba33322d9711a19f08145c"}, + {file = "msgpack-1.0.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:379026812e49258016dd84ad79ac8446922234d498058ae1d415f04b522d5b2d"}, + {file = "msgpack-1.0.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:332360ff25469c346a1c5e47cbe2a725517919892eda5cfaffe6046656f0b7bb"}, + {file = "msgpack-1.0.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:476a8fe8fae289fdf273d6d2a6cb6e35b5a58541693e8f9f019bfe990a51e4ba"}, + {file = "msgpack-1.0.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a9985b214f33311df47e274eb788a5893a761d025e2b92c723ba4c63936b69b1"}, + {file = "msgpack-1.0.5-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:48296af57cdb1d885843afd73c4656be5c76c0c6328db3440c9601a98f303d87"}, + {file = "msgpack-1.0.5-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:addab7e2e1fcc04bd08e4eb631c2a90960c340e40dfc4a5e24d2ff0d5a3b3edb"}, + {file = "msgpack-1.0.5-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:916723458c25dfb77ff07f4c66aed34e47503b2eb3188b3adbec8d8aa6e00f48"}, + {file = "msgpack-1.0.5-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:821c7e677cc6acf0fd3f7ac664c98803827ae6de594a9f99563e48c5a2f27eb0"}, + {file = "msgpack-1.0.5-cp38-cp38-win32.whl", hash = "sha256:1c0f7c47f0087ffda62961d425e4407961a7ffd2aa004c81b9c07d9269512f6e"}, + {file = "msgpack-1.0.5-cp38-cp38-win_amd64.whl", hash = "sha256:bae7de2026cbfe3782c8b78b0db9cbfc5455e079f1937cb0ab8d133496ac55e1"}, + {file = "msgpack-1.0.5-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:20c784e66b613c7f16f632e7b5e8a1651aa5702463d61394671ba07b2fc9e025"}, + {file = "msgpack-1.0.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:266fa4202c0eb94d26822d9bfd7af25d1e2c088927fe8de9033d929dd5ba24c5"}, + {file = "msgpack-1.0.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:18334484eafc2b1aa47a6d42427da7fa8f2ab3d60b674120bce7a895a0a85bdd"}, + {file = "msgpack-1.0.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:57e1f3528bd95cc44684beda696f74d3aaa8a5e58c816214b9046512240ef437"}, + {file = "msgpack-1.0.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:586d0d636f9a628ddc6a17bfd45aa5b5efaf1606d2b60fa5d87b8986326e933f"}, + {file = "msgpack-1.0.5-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a740fa0e4087a734455f0fc3abf5e746004c9da72fbd541e9b113013c8dc3282"}, + {file = "msgpack-1.0.5-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:3055b0455e45810820db1f29d900bf39466df96ddca11dfa6d074fa47054376d"}, + {file = "msgpack-1.0.5-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:a61215eac016f391129a013c9e46f3ab308db5f5ec9f25811e811f96962599a8"}, + {file = "msgpack-1.0.5-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:362d9655cd369b08fda06b6657a303eb7172d5279997abe094512e919cf74b11"}, + {file = "msgpack-1.0.5-cp39-cp39-win32.whl", hash = "sha256:ac9dd47af78cae935901a9a500104e2dea2e253207c924cc95de149606dc43cc"}, + {file = "msgpack-1.0.5-cp39-cp39-win_amd64.whl", hash = "sha256:06f5174b5f8ed0ed919da0e62cbd4ffde676a374aba4020034da05fab67b9164"}, + {file = "msgpack-1.0.5.tar.gz", hash = "sha256:c075544284eadc5cddc70f4757331d99dcbc16b2bbd4849d15f8aae4cf36d31c"}, ] [[package]] name = "mypy-extensions" -version = "0.4.3" -description = "Experimental type system extensions for programs checked with the mypy typechecker." +version = "1.0.0" +description = "Type system extensions for programs checked with the mypy type checker." category = "dev" optional = false -python-versions = "*" +python-versions = ">=3.5" files = [ - {file = "mypy_extensions-0.4.3-py2.py3-none-any.whl", hash = "sha256:090fedd75945a69ae91ce1303b5824f428daf5a028d2f6ab8a299250a846f15d"}, - {file = "mypy_extensions-0.4.3.tar.gz", hash = "sha256:2d82818f5bb3e369420cb3c4060a7970edba416647068eb4c5343488a6c604a8"}, + {file = "mypy_extensions-1.0.0-py3-none-any.whl", hash = "sha256:4392f6c0eb8a5668a69e23d168ffa70f0be9ccfd32b5cc2d26a34ae5b844552d"}, + {file = "mypy_extensions-1.0.0.tar.gz", hash = "sha256:75dbf8955dc00442a438fc4d0666508a9a97b6bd41aa2f0ffe9d2f2725af0782"}, ] [[package]] name = "networkx" -version = "3.0" +version = "3.1" description = "Python package for creating and manipulating graphs and networks" category = "main" optional = false python-versions = ">=3.8" files = [ - {file = "networkx-3.0-py3-none-any.whl", hash = "sha256:58058d66b1818043527244fab9d41a51fcd7dcc271748015f3c181b8a90c8e2e"}, - {file = "networkx-3.0.tar.gz", hash = "sha256:9a9992345353618ae98339c2b63d8201c381c2944f38a2ab49cb45a4c667e412"}, + {file = "networkx-3.1-py3-none-any.whl", hash = "sha256:4f33f68cb2afcf86f28a45f43efc27a9386b535d567d2127f8f61d51dec58d36"}, + {file = "networkx-3.1.tar.gz", hash = "sha256:de346335408f84de0eada6ff9fafafff9bcda11f0a0dfaa931133debb146ab61"}, ] [package.extras] default = ["matplotlib (>=3.4)", "numpy (>=1.20)", "pandas (>=1.3)", "scipy (>=1.8)"] -developer = ["mypy (>=0.991)", "pre-commit (>=2.20)"] -doc = ["nb2plots (>=0.6)", "numpydoc (>=1.5)", "pillow (>=9.2)", "pydata-sphinx-theme (>=0.11)", "sphinx (==5.2.3)", "sphinx-gallery (>=0.11)", "texext (>=0.6.7)"] +developer = ["mypy (>=1.1)", "pre-commit (>=3.2)"] +doc = ["nb2plots (>=0.6)", "numpydoc (>=1.5)", "pillow (>=9.4)", "pydata-sphinx-theme (>=0.13)", "sphinx (>=6.1)", "sphinx-gallery (>=0.12)", "texext (>=0.6.7)"] extra = ["lxml (>=4.6)", "pydot (>=1.4.2)", "pygraphviz (>=1.10)", "sympy (>=1.10)"] test = ["codecov (>=2.1)", "pytest (>=7.2)", "pytest-cov (>=4.0)"] @@ -1432,6 +1567,22 @@ files = [ setuptools = "*" wheel = "*" +[[package]] +name = "nvidia-cuda-cupti-cu11" +version = "11.7.101" +description = "CUDA profiling tools runtime libs." +category = "main" +optional = false +python-versions = ">=3" +files = [ + {file = "nvidia_cuda_cupti_cu11-11.7.101-py3-none-manylinux1_x86_64.whl", hash = "sha256:e0cfd9854e1f2edaa36ca20d21cd0bdd5dcfca4e3b9e130a082e05b33b6c5895"}, + {file = "nvidia_cuda_cupti_cu11-11.7.101-py3-none-win_amd64.whl", hash = "sha256:7cc5b8f91ae5e1389c3c0ad8866b3b016a175e827ea8f162a672990a402ab2b0"}, +] + +[package.dependencies] +setuptools = "*" +wheel = "*" + [[package]] name = "nvidia-cuda-nvrtc-cu11" version = "11.7.99" @@ -1481,6 +1632,94 @@ files = [ setuptools = "*" wheel = "*" +[[package]] +name = "nvidia-cufft-cu11" +version = "10.9.0.58" +description = "CUFFT native runtime libraries" +category = "main" +optional = false +python-versions = ">=3" +files = [ + {file = "nvidia_cufft_cu11-10.9.0.58-py3-none-manylinux1_x86_64.whl", hash = "sha256:222f9da70c80384632fd6035e4c3f16762d64ea7a843829cb278f98b3cb7dd81"}, + {file = "nvidia_cufft_cu11-10.9.0.58-py3-none-win_amd64.whl", hash = "sha256:c4d316f17c745ec9c728e30409612eaf77a8404c3733cdf6c9c1569634d1ca03"}, +] + +[[package]] +name = "nvidia-curand-cu11" +version = "10.2.10.91" +description = "CURAND native runtime libraries" +category = "main" +optional = false +python-versions = ">=3" +files = [ + {file = "nvidia_curand_cu11-10.2.10.91-py3-none-manylinux1_x86_64.whl", hash = "sha256:eecb269c970fa599a2660c9232fa46aaccbf90d9170b96c462e13bcb4d129e2c"}, + {file = "nvidia_curand_cu11-10.2.10.91-py3-none-win_amd64.whl", hash = "sha256:f742052af0e1e75523bde18895a9ed016ecf1e5aa0ecddfcc3658fd11a1ff417"}, +] + +[package.dependencies] +setuptools = "*" +wheel = "*" + +[[package]] +name = "nvidia-cusolver-cu11" +version = "11.4.0.1" +description = "CUDA solver native runtime libraries" +category = "main" +optional = false +python-versions = ">=3" +files = [ + {file = "nvidia_cusolver_cu11-11.4.0.1-2-py3-none-manylinux1_x86_64.whl", hash = "sha256:72fa7261d755ed55c0074960df5904b65e2326f7adce364cbe4945063c1be412"}, + {file = "nvidia_cusolver_cu11-11.4.0.1-py3-none-manylinux1_x86_64.whl", hash = "sha256:700b781bfefd57d161443aff9ace1878584b93e0b2cfef3d6e9296d96febbf99"}, + {file = "nvidia_cusolver_cu11-11.4.0.1-py3-none-win_amd64.whl", hash = "sha256:00f70b256add65f8c1eb3b6a65308795a93e7740f6df9e273eccbba770d370c4"}, +] + +[package.dependencies] +setuptools = "*" +wheel = "*" + +[[package]] +name = "nvidia-cusparse-cu11" +version = "11.7.4.91" +description = "CUSPARSE native runtime libraries" +category = "main" +optional = false +python-versions = ">=3" +files = [ + {file = "nvidia_cusparse_cu11-11.7.4.91-py3-none-manylinux1_x86_64.whl", hash = "sha256:a3389de714db63321aa11fbec3919271f415ef19fda58aed7f2ede488c32733d"}, + {file = "nvidia_cusparse_cu11-11.7.4.91-py3-none-win_amd64.whl", hash = "sha256:304a01599534f5186a8ed1c3756879282c72c118bc77dd890dc1ff868cad25b9"}, +] + +[package.dependencies] +setuptools = "*" +wheel = "*" + +[[package]] +name = "nvidia-nccl-cu11" +version = "2.14.3" +description = "NVIDIA Collective Communication Library (NCCL) Runtime" +category = "main" +optional = false +python-versions = ">=3" +files = [ + {file = "nvidia_nccl_cu11-2.14.3-py3-none-manylinux1_x86_64.whl", hash = "sha256:5e5534257d1284b8e825bc3a182c6f06acd6eb405e9f89d49340e98cd8f136eb"}, +] + +[[package]] +name = "nvidia-nvtx-cu11" +version = "11.7.91" +description = "NVIDIA Tools Extension" +category = "main" +optional = false +python-versions = ">=3" +files = [ + {file = "nvidia_nvtx_cu11-11.7.91-py3-none-manylinux1_x86_64.whl", hash = "sha256:b22c64eee426a62fc00952b507d6d29cf62b4c9df7a480fcc417e540e05fd5ac"}, + {file = "nvidia_nvtx_cu11-11.7.91-py3-none-win_amd64.whl", hash = "sha256:dfd7fcb2a91742513027d63a26b757f38dd8b07fecac282c4d132a9d373ff064"}, +] + +[package.dependencies] +setuptools = "*" +wheel = "*" + [[package]] name = "omegaconf" version = "2.3.0" @@ -1499,26 +1738,26 @@ PyYAML = ">=5.1.0" [[package]] name = "packaging" -version = "23.0" +version = "23.1" description = "Core utilities for Python packages" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "packaging-23.0-py3-none-any.whl", hash = "sha256:714ac14496c3e68c99c29b00845f7a2b85f3bb6f1078fd9f72fd20f0570002b2"}, - {file = "packaging-23.0.tar.gz", hash = "sha256:b6ad297f8907de0fa2fe1ccbd26fdaf387f5f47c7275fedf8cce89f99446cf97"}, + {file = "packaging-23.1-py3-none-any.whl", hash = "sha256:994793af429502c4ea2ebf6bf664629d07c1a9fe974af92966e4b8d2df7edc61"}, + {file = "packaging-23.1.tar.gz", hash = "sha256:a392980d2b6cffa644431898be54b0045151319d1e7ec34f0cfed48767dd334f"}, ] [[package]] name = "pathspec" -version = "0.11.0" +version = "0.11.1" description = "Utility library for gitignore style pattern matching of file paths." category = "dev" optional = false python-versions = ">=3.7" files = [ - {file = "pathspec-0.11.0-py3-none-any.whl", hash = "sha256:3a66eb970cbac598f9e5ccb5b2cf58930cd8e3ed86d393d541eaf2d8b1705229"}, - {file = "pathspec-0.11.0.tar.gz", hash = "sha256:64d338d4e0914e91c1792321e6907b5a593f1ab1851de7fc269557a21b30ebbc"}, + {file = "pathspec-0.11.1-py3-none-any.whl", hash = "sha256:d8af70af76652554bd134c22b3e8a1cc46ed7d91edcdd721ef1a0c51a84a5293"}, + {file = "pathspec-0.11.1.tar.gz", hash = "sha256:2798de800fa92780e33acca925945e9a19a133b715067cf165b8866c15a31687"}, ] [[package]] @@ -1534,93 +1773,82 @@ files = [ [[package]] name = "pillow" -version = "9.4.0" +version = "9.5.0" description = "Python Imaging Library (Fork)" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "Pillow-9.4.0-1-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:1b4b4e9dda4f4e4c4e6896f93e84a8f0bcca3b059de9ddf67dac3c334b1195e1"}, - {file = "Pillow-9.4.0-1-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:fb5c1ad6bad98c57482236a21bf985ab0ef42bd51f7ad4e4538e89a997624e12"}, - {file = "Pillow-9.4.0-1-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:f0caf4a5dcf610d96c3bd32932bfac8aee61c96e60481c2a0ea58da435e25acd"}, - {file = "Pillow-9.4.0-1-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:3f4cc516e0b264c8d4ccd6b6cbc69a07c6d582d8337df79be1e15a5056b258c9"}, - {file = "Pillow-9.4.0-1-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:b8c2f6eb0df979ee99433d8b3f6d193d9590f735cf12274c108bd954e30ca858"}, - {file = "Pillow-9.4.0-1-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:b70756ec9417c34e097f987b4d8c510975216ad26ba6e57ccb53bc758f490dab"}, - {file = "Pillow-9.4.0-1-pp39-pypy39_pp73-macosx_10_10_x86_64.whl", hash = "sha256:43521ce2c4b865d385e78579a082b6ad1166ebed2b1a2293c3be1d68dd7ca3b9"}, - {file = "Pillow-9.4.0-2-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:9d9a62576b68cd90f7075876f4e8444487db5eeea0e4df3ba298ee38a8d067b0"}, - {file = "Pillow-9.4.0-2-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:87708d78a14d56a990fbf4f9cb350b7d89ee8988705e58e39bdf4d82c149210f"}, - {file = "Pillow-9.4.0-2-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:8a2b5874d17e72dfb80d917213abd55d7e1ed2479f38f001f264f7ce7bae757c"}, - {file = "Pillow-9.4.0-2-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:83125753a60cfc8c412de5896d10a0a405e0bd88d0470ad82e0869ddf0cb3848"}, - {file = "Pillow-9.4.0-2-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:9e5f94742033898bfe84c93c831a6f552bb629448d4072dd312306bab3bd96f1"}, - {file = "Pillow-9.4.0-2-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:013016af6b3a12a2f40b704677f8b51f72cb007dac785a9933d5c86a72a7fe33"}, - {file = "Pillow-9.4.0-2-pp39-pypy39_pp73-macosx_10_10_x86_64.whl", hash = "sha256:99d92d148dd03fd19d16175b6d355cc1b01faf80dae93c6c3eb4163709edc0a9"}, - {file = "Pillow-9.4.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:2968c58feca624bb6c8502f9564dd187d0e1389964898f5e9e1fbc8533169157"}, - {file = "Pillow-9.4.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c5c1362c14aee73f50143d74389b2c158707b4abce2cb055b7ad37ce60738d47"}, - {file = "Pillow-9.4.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bd752c5ff1b4a870b7661234694f24b1d2b9076b8bf337321a814c612665f343"}, - {file = "Pillow-9.4.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9a3049a10261d7f2b6514d35bbb7a4dfc3ece4c4de14ef5876c4b7a23a0e566d"}, - {file = "Pillow-9.4.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:16a8df99701f9095bea8a6c4b3197da105df6f74e6176c5b410bc2df2fd29a57"}, - {file = "Pillow-9.4.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:94cdff45173b1919350601f82d61365e792895e3c3a3443cf99819e6fbf717a5"}, - {file = "Pillow-9.4.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:ed3e4b4e1e6de75fdc16d3259098de7c6571b1a6cc863b1a49e7d3d53e036070"}, - {file = "Pillow-9.4.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:d5b2f8a31bd43e0f18172d8ac82347c8f37ef3e0b414431157718aa234991b28"}, - {file = "Pillow-9.4.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:09b89ddc95c248ee788328528e6a2996e09eaccddeeb82a5356e92645733be35"}, - {file = "Pillow-9.4.0-cp310-cp310-win32.whl", hash = "sha256:f09598b416ba39a8f489c124447b007fe865f786a89dbfa48bb5cf395693132a"}, - {file = "Pillow-9.4.0-cp310-cp310-win_amd64.whl", hash = "sha256:f6e78171be3fb7941f9910ea15b4b14ec27725865a73c15277bc39f5ca4f8391"}, - {file = "Pillow-9.4.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:3fa1284762aacca6dc97474ee9c16f83990b8eeb6697f2ba17140d54b453e133"}, - {file = "Pillow-9.4.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:eaef5d2de3c7e9b21f1e762f289d17b726c2239a42b11e25446abf82b26ac132"}, - {file = "Pillow-9.4.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a4dfdae195335abb4e89cc9762b2edc524f3c6e80d647a9a81bf81e17e3fb6f0"}, - {file = "Pillow-9.4.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6abfb51a82e919e3933eb137e17c4ae9c0475a25508ea88993bb59faf82f3b35"}, - {file = "Pillow-9.4.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:451f10ef963918e65b8869e17d67db5e2f4ab40e716ee6ce7129b0cde2876eab"}, - {file = "Pillow-9.4.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:6663977496d616b618b6cfa43ec86e479ee62b942e1da76a2c3daa1c75933ef4"}, - {file = "Pillow-9.4.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:60e7da3a3ad1812c128750fc1bc14a7ceeb8d29f77e0a2356a8fb2aa8925287d"}, - {file = "Pillow-9.4.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:19005a8e58b7c1796bc0167862b1f54a64d3b44ee5d48152b06bb861458bc0f8"}, - {file = "Pillow-9.4.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:f715c32e774a60a337b2bb8ad9839b4abf75b267a0f18806f6f4f5f1688c4b5a"}, - {file = "Pillow-9.4.0-cp311-cp311-win32.whl", hash = "sha256:b222090c455d6d1a64e6b7bb5f4035c4dff479e22455c9eaa1bdd4c75b52c80c"}, - {file = "Pillow-9.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:ba6612b6548220ff5e9df85261bddc811a057b0b465a1226b39bfb8550616aee"}, - {file = "Pillow-9.4.0-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:5f532a2ad4d174eb73494e7397988e22bf427f91acc8e6ebf5bb10597b49c493"}, - {file = "Pillow-9.4.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5dd5a9c3091a0f414a963d427f920368e2b6a4c2f7527fdd82cde8ef0bc7a327"}, - {file = "Pillow-9.4.0-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ef21af928e807f10bf4141cad4746eee692a0dd3ff56cfb25fce076ec3cc8abe"}, - {file = "Pillow-9.4.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:847b114580c5cc9ebaf216dd8c8dbc6b00a3b7ab0131e173d7120e6deade1f57"}, - {file = "Pillow-9.4.0-cp37-cp37m-manylinux_2_28_aarch64.whl", hash = "sha256:653d7fb2df65efefbcbf81ef5fe5e5be931f1ee4332c2893ca638c9b11a409c4"}, - {file = "Pillow-9.4.0-cp37-cp37m-manylinux_2_28_x86_64.whl", hash = "sha256:46f39cab8bbf4a384ba7cb0bc8bae7b7062b6a11cfac1ca4bc144dea90d4a9f5"}, - {file = "Pillow-9.4.0-cp37-cp37m-win32.whl", hash = "sha256:7ac7594397698f77bce84382929747130765f66406dc2cd8b4ab4da68ade4c6e"}, - {file = "Pillow-9.4.0-cp37-cp37m-win_amd64.whl", hash = "sha256:46c259e87199041583658457372a183636ae8cd56dbf3f0755e0f376a7f9d0e6"}, - {file = "Pillow-9.4.0-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:0e51f608da093e5d9038c592b5b575cadc12fd748af1479b5e858045fff955a9"}, - {file = "Pillow-9.4.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:765cb54c0b8724a7c12c55146ae4647e0274a839fb6de7bcba841e04298e1011"}, - {file = "Pillow-9.4.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:519e14e2c49fcf7616d6d2cfc5c70adae95682ae20f0395e9280db85e8d6c4df"}, - {file = "Pillow-9.4.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d197df5489004db87d90b918033edbeee0bd6df3848a204bca3ff0a903bef837"}, - {file = "Pillow-9.4.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0845adc64fe9886db00f5ab68c4a8cd933ab749a87747555cec1c95acea64b0b"}, - {file = "Pillow-9.4.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:e1339790c083c5a4de48f688b4841f18df839eb3c9584a770cbd818b33e26d5d"}, - {file = "Pillow-9.4.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:a96e6e23f2b79433390273eaf8cc94fec9c6370842e577ab10dabdcc7ea0a66b"}, - {file = "Pillow-9.4.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:7cfc287da09f9d2a7ec146ee4d72d6ea1342e770d975e49a8621bf54eaa8f30f"}, - {file = "Pillow-9.4.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:d7081c084ceb58278dd3cf81f836bc818978c0ccc770cbbb202125ddabec6628"}, - {file = "Pillow-9.4.0-cp38-cp38-win32.whl", hash = "sha256:df41112ccce5d47770a0c13651479fbcd8793f34232a2dd9faeccb75eb5d0d0d"}, - {file = "Pillow-9.4.0-cp38-cp38-win_amd64.whl", hash = "sha256:7a21222644ab69ddd9967cfe6f2bb420b460dae4289c9d40ff9a4896e7c35c9a"}, - {file = "Pillow-9.4.0-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:0f3269304c1a7ce82f1759c12ce731ef9b6e95b6df829dccd9fe42912cc48569"}, - {file = "Pillow-9.4.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:cb362e3b0976dc994857391b776ddaa8c13c28a16f80ac6522c23d5257156bed"}, - {file = "Pillow-9.4.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a2e0f87144fcbbe54297cae708c5e7f9da21a4646523456b00cc956bd4c65815"}, - {file = "Pillow-9.4.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:28676836c7796805914b76b1837a40f76827ee0d5398f72f7dcc634bae7c6264"}, - {file = "Pillow-9.4.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0884ba7b515163a1a05440a138adeb722b8a6ae2c2b33aea93ea3118dd3a899e"}, - {file = "Pillow-9.4.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:53dcb50fbdc3fb2c55431a9b30caeb2f7027fcd2aeb501459464f0214200a503"}, - {file = "Pillow-9.4.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:e8c5cf126889a4de385c02a2c3d3aba4b00f70234bfddae82a5eaa3ee6d5e3e6"}, - {file = "Pillow-9.4.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:6c6b1389ed66cdd174d040105123a5a1bc91d0aa7059c7261d20e583b6d8cbd2"}, - {file = "Pillow-9.4.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:0dd4c681b82214b36273c18ca7ee87065a50e013112eea7d78c7a1b89a739153"}, - {file = "Pillow-9.4.0-cp39-cp39-win32.whl", hash = "sha256:6d9dfb9959a3b0039ee06c1a1a90dc23bac3b430842dcb97908ddde05870601c"}, - {file = "Pillow-9.4.0-cp39-cp39-win_amd64.whl", hash = "sha256:54614444887e0d3043557d9dbc697dbb16cfb5a35d672b7a0fcc1ed0cf1c600b"}, - {file = "Pillow-9.4.0-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:b9b752ab91e78234941e44abdecc07f1f0d8f51fb62941d32995b8161f68cfe5"}, - {file = "Pillow-9.4.0-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d3b56206244dc8711f7e8b7d6cad4663917cd5b2d950799425076681e8766286"}, - {file = "Pillow-9.4.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:aabdab8ec1e7ca7f1434d042bf8b1e92056245fb179790dc97ed040361f16bfd"}, - {file = "Pillow-9.4.0-pp38-pypy38_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:db74f5562c09953b2c5f8ec4b7dfd3f5421f31811e97d1dbc0a7c93d6e3a24df"}, - {file = "Pillow-9.4.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:e9d7747847c53a16a729b6ee5e737cf170f7a16611c143d95aa60a109a59c336"}, - {file = "Pillow-9.4.0-pp39-pypy39_pp73-macosx_10_10_x86_64.whl", hash = "sha256:b52ff4f4e002f828ea6483faf4c4e8deea8d743cf801b74910243c58acc6eda3"}, - {file = "Pillow-9.4.0-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:575d8912dca808edd9acd6f7795199332696d3469665ef26163cd090fa1f8bfa"}, - {file = "Pillow-9.4.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c3c4ed2ff6760e98d262e0cc9c9a7f7b8a9f61aa4d47c58835cdaf7b0b8811bb"}, - {file = "Pillow-9.4.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:e621b0246192d3b9cb1dc62c78cfa4c6f6d2ddc0ec207d43c0dedecb914f152a"}, - {file = "Pillow-9.4.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:8f127e7b028900421cad64f51f75c051b628db17fb00e099eb148761eed598c9"}, - {file = "Pillow-9.4.0.tar.gz", hash = "sha256:a1c2d7780448eb93fbcc3789bf3916aa5720d942e37945f4056680317f1cd23e"}, + {file = "Pillow-9.5.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:ace6ca218308447b9077c14ea4ef381ba0b67ee78d64046b3f19cf4e1139ad16"}, + {file = "Pillow-9.5.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:d3d403753c9d5adc04d4694d35cf0391f0f3d57c8e0030aac09d7678fa8030aa"}, + {file = "Pillow-9.5.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5ba1b81ee69573fe7124881762bb4cd2e4b6ed9dd28c9c60a632902fe8db8b38"}, + {file = "Pillow-9.5.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fe7e1c262d3392afcf5071df9afa574544f28eac825284596ac6db56e6d11062"}, + {file = "Pillow-9.5.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f36397bf3f7d7c6a3abdea815ecf6fd14e7fcd4418ab24bae01008d8d8ca15e"}, + {file = "Pillow-9.5.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:252a03f1bdddce077eff2354c3861bf437c892fb1832f75ce813ee94347aa9b5"}, + {file = "Pillow-9.5.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:85ec677246533e27770b0de5cf0f9d6e4ec0c212a1f89dfc941b64b21226009d"}, + {file = "Pillow-9.5.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:b416f03d37d27290cb93597335a2f85ed446731200705b22bb927405320de903"}, + {file = "Pillow-9.5.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:1781a624c229cb35a2ac31cc4a77e28cafc8900733a864870c49bfeedacd106a"}, + {file = "Pillow-9.5.0-cp310-cp310-win32.whl", hash = "sha256:8507eda3cd0608a1f94f58c64817e83ec12fa93a9436938b191b80d9e4c0fc44"}, + {file = "Pillow-9.5.0-cp310-cp310-win_amd64.whl", hash = "sha256:d3c6b54e304c60c4181da1c9dadf83e4a54fd266a99c70ba646a9baa626819eb"}, + {file = "Pillow-9.5.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:7ec6f6ce99dab90b52da21cf0dc519e21095e332ff3b399a357c187b1a5eee32"}, + {file = "Pillow-9.5.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:560737e70cb9c6255d6dcba3de6578a9e2ec4b573659943a5e7e4af13f298f5c"}, + {file = "Pillow-9.5.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:96e88745a55b88a7c64fa49bceff363a1a27d9a64e04019c2281049444a571e3"}, + {file = "Pillow-9.5.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d9c206c29b46cfd343ea7cdfe1232443072bbb270d6a46f59c259460db76779a"}, + {file = "Pillow-9.5.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cfcc2c53c06f2ccb8976fb5c71d448bdd0a07d26d8e07e321c103416444c7ad1"}, + {file = "Pillow-9.5.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:a0f9bb6c80e6efcde93ffc51256d5cfb2155ff8f78292f074f60f9e70b942d99"}, + {file = "Pillow-9.5.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:8d935f924bbab8f0a9a28404422da8af4904e36d5c33fc6f677e4c4485515625"}, + {file = "Pillow-9.5.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:fed1e1cf6a42577953abbe8e6cf2fe2f566daebde7c34724ec8803c4c0cda579"}, + {file = "Pillow-9.5.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:c1170d6b195555644f0616fd6ed929dfcf6333b8675fcca044ae5ab110ded296"}, + {file = "Pillow-9.5.0-cp311-cp311-win32.whl", hash = "sha256:54f7102ad31a3de5666827526e248c3530b3a33539dbda27c6843d19d72644ec"}, + {file = "Pillow-9.5.0-cp311-cp311-win_amd64.whl", hash = "sha256:cfa4561277f677ecf651e2b22dc43e8f5368b74a25a8f7d1d4a3a243e573f2d4"}, + {file = "Pillow-9.5.0-cp311-cp311-win_arm64.whl", hash = "sha256:965e4a05ef364e7b973dd17fc765f42233415974d773e82144c9bbaaaea5d089"}, + {file = "Pillow-9.5.0-cp312-cp312-win32.whl", hash = "sha256:22baf0c3cf0c7f26e82d6e1adf118027afb325e703922c8dfc1d5d0156bb2eeb"}, + {file = "Pillow-9.5.0-cp312-cp312-win_amd64.whl", hash = "sha256:432b975c009cf649420615388561c0ce7cc31ce9b2e374db659ee4f7d57a1f8b"}, + {file = "Pillow-9.5.0-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:5d4ebf8e1db4441a55c509c4baa7a0587a0210f7cd25fcfe74dbbce7a4bd1906"}, + {file = "Pillow-9.5.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:375f6e5ee9620a271acb6820b3d1e94ffa8e741c0601db4c0c4d3cb0a9c224bf"}, + {file = "Pillow-9.5.0-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:99eb6cafb6ba90e436684e08dad8be1637efb71c4f2180ee6b8f940739406e78"}, + {file = "Pillow-9.5.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2dfaaf10b6172697b9bceb9a3bd7b951819d1ca339a5ef294d1f1ac6d7f63270"}, + {file = "Pillow-9.5.0-cp37-cp37m-manylinux_2_28_aarch64.whl", hash = "sha256:763782b2e03e45e2c77d7779875f4432e25121ef002a41829d8868700d119392"}, + {file = "Pillow-9.5.0-cp37-cp37m-manylinux_2_28_x86_64.whl", hash = "sha256:35f6e77122a0c0762268216315bf239cf52b88865bba522999dc38f1c52b9b47"}, + {file = "Pillow-9.5.0-cp37-cp37m-win32.whl", hash = "sha256:aca1c196f407ec7cf04dcbb15d19a43c507a81f7ffc45b690899d6a76ac9fda7"}, + {file = "Pillow-9.5.0-cp37-cp37m-win_amd64.whl", hash = "sha256:322724c0032af6692456cd6ed554bb85f8149214d97398bb80613b04e33769f6"}, + {file = "Pillow-9.5.0-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:a0aa9417994d91301056f3d0038af1199eb7adc86e646a36b9e050b06f526597"}, + {file = "Pillow-9.5.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:f8286396b351785801a976b1e85ea88e937712ee2c3ac653710a4a57a8da5d9c"}, + {file = "Pillow-9.5.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c830a02caeb789633863b466b9de10c015bded434deb3ec87c768e53752ad22a"}, + {file = "Pillow-9.5.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fbd359831c1657d69bb81f0db962905ee05e5e9451913b18b831febfe0519082"}, + {file = "Pillow-9.5.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f8fc330c3370a81bbf3f88557097d1ea26cd8b019d6433aa59f71195f5ddebbf"}, + {file = "Pillow-9.5.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:7002d0797a3e4193c7cdee3198d7c14f92c0836d6b4a3f3046a64bd1ce8df2bf"}, + {file = "Pillow-9.5.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:229e2c79c00e85989a34b5981a2b67aa079fd08c903f0aaead522a1d68d79e51"}, + {file = "Pillow-9.5.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:9adf58f5d64e474bed00d69bcd86ec4bcaa4123bfa70a65ce72e424bfb88ed96"}, + {file = "Pillow-9.5.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:662da1f3f89a302cc22faa9f14a262c2e3951f9dbc9617609a47521c69dd9f8f"}, + {file = "Pillow-9.5.0-cp38-cp38-win32.whl", hash = "sha256:6608ff3bf781eee0cd14d0901a2b9cc3d3834516532e3bd673a0a204dc8615fc"}, + {file = "Pillow-9.5.0-cp38-cp38-win_amd64.whl", hash = "sha256:e49eb4e95ff6fd7c0c402508894b1ef0e01b99a44320ba7d8ecbabefddcc5569"}, + {file = "Pillow-9.5.0-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:482877592e927fd263028c105b36272398e3e1be3269efda09f6ba21fd83ec66"}, + {file = "Pillow-9.5.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:3ded42b9ad70e5f1754fb7c2e2d6465a9c842e41d178f262e08b8c85ed8a1d8e"}, + {file = "Pillow-9.5.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c446d2245ba29820d405315083d55299a796695d747efceb5717a8b450324115"}, + {file = "Pillow-9.5.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8aca1152d93dcc27dc55395604dcfc55bed5f25ef4c98716a928bacba90d33a3"}, + {file = "Pillow-9.5.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:608488bdcbdb4ba7837461442b90ea6f3079397ddc968c31265c1e056964f1ef"}, + {file = "Pillow-9.5.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:60037a8db8750e474af7ffc9faa9b5859e6c6d0a50e55c45576bf28be7419705"}, + {file = "Pillow-9.5.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:07999f5834bdc404c442146942a2ecadd1cb6292f5229f4ed3b31e0a108746b1"}, + {file = "Pillow-9.5.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:a127ae76092974abfbfa38ca2d12cbeddcdeac0fb71f9627cc1135bedaf9d51a"}, + {file = "Pillow-9.5.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:489f8389261e5ed43ac8ff7b453162af39c3e8abd730af8363587ba64bb2e865"}, + {file = "Pillow-9.5.0-cp39-cp39-win32.whl", hash = "sha256:9b1af95c3a967bf1da94f253e56b6286b50af23392a886720f563c547e48e964"}, + {file = "Pillow-9.5.0-cp39-cp39-win_amd64.whl", hash = "sha256:77165c4a5e7d5a284f10a6efaa39a0ae8ba839da344f20b111d62cc932fa4e5d"}, + {file = "Pillow-9.5.0-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:833b86a98e0ede388fa29363159c9b1a294b0905b5128baf01db683672f230f5"}, + {file = "Pillow-9.5.0-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:aaf305d6d40bd9632198c766fb64f0c1a83ca5b667f16c1e79e1661ab5060140"}, + {file = "Pillow-9.5.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0852ddb76d85f127c135b6dd1f0bb88dbb9ee990d2cd9aa9e28526c93e794fba"}, + {file = "Pillow-9.5.0-pp38-pypy38_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:91ec6fe47b5eb5a9968c79ad9ed78c342b1f97a091677ba0e012701add857829"}, + {file = "Pillow-9.5.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:cb841572862f629b99725ebaec3287fc6d275be9b14443ea746c1dd325053cbd"}, + {file = "Pillow-9.5.0-pp39-pypy39_pp73-macosx_10_10_x86_64.whl", hash = "sha256:c380b27d041209b849ed246b111b7c166ba36d7933ec6e41175fd15ab9eb1572"}, + {file = "Pillow-9.5.0-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7c9af5a3b406a50e313467e3565fc99929717f780164fe6fbb7704edba0cebbe"}, + {file = "Pillow-9.5.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5671583eab84af046a397d6d0ba25343c00cd50bce03787948e0fff01d4fd9b1"}, + {file = "Pillow-9.5.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:84a6f19ce086c1bf894644b43cd129702f781ba5751ca8572f08aa40ef0ab7b7"}, + {file = "Pillow-9.5.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:1e7723bd90ef94eda669a3c2c19d549874dd5badaeefabefd26053304abe5799"}, + {file = "Pillow-9.5.0.tar.gz", hash = "sha256:bf548479d336726d7a0eceb6e767e179fbde37833ae42794602631a070d630f1"}, ] [package.extras] -docs = ["furo", "olefile", "sphinx (>=2.4)", "sphinx-copybutton", "sphinx-inline-tabs", "sphinx-issues (>=3.0.1)", "sphinx-removed-in", "sphinxext-opengraph"] +docs = ["furo", "olefile", "sphinx (>=2.4)", "sphinx-copybutton", "sphinx-inline-tabs", "sphinx-removed-in", "sphinxext-opengraph"] tests = ["check-manifest", "coverage", "defusedxml", "markdown2", "olefile", "packaging", "pyroma", "pytest", "pytest-cov", "pytest-timeout"] [[package]] @@ -1637,19 +1865,19 @@ files = [ [[package]] name = "platformdirs" -version = "2.6.2" +version = "3.2.0" description = "A small Python package for determining appropriate platform-specific dirs, e.g. a \"user data dir\"." category = "dev" optional = false python-versions = ">=3.7" files = [ - {file = "platformdirs-2.6.2-py3-none-any.whl", hash = "sha256:83c8f6d04389165de7c9b6f0c682439697887bca0aa2f1c87ef1826be3584490"}, - {file = "platformdirs-2.6.2.tar.gz", hash = "sha256:e1fea1fe471b9ff8332e229df3cb7de4f53eeea4998d3b6bfff542115e998bd2"}, + {file = "platformdirs-3.2.0-py3-none-any.whl", hash = "sha256:ebe11c0d7a805086e99506aa331612429a72ca7cd52a1f0d277dc4adc20cb10e"}, + {file = "platformdirs-3.2.0.tar.gz", hash = "sha256:d5b638ca397f25f979350ff789db335903d7ea010ab28903f57b27e1b16c2b08"}, ] [package.extras] -docs = ["furo (>=2022.12.7)", "proselint (>=0.13)", "sphinx (>=5.3)", "sphinx-autodoc-typehints (>=1.19.5)"] -test = ["appdirs (==1.4.4)", "covdefaults (>=2.2.2)", "pytest (>=7.2)", "pytest-cov (>=4)", "pytest-mock (>=3.10)"] +docs = ["furo (>=2022.12.7)", "proselint (>=0.13)", "sphinx (>=6.1.3)", "sphinx-autodoc-typehints (>=1.22,!=1.23.4)"] +test = ["appdirs (==1.4.4)", "covdefaults (>=2.3)", "pytest (>=7.2.2)", "pytest-cov (>=4)", "pytest-mock (>=3.10)"] [[package]] name = "pluggy" @@ -1707,7 +1935,7 @@ validation = ["lxml"] name = "pycparser" version = "2.21" description = "C parser in Python" -category = "main" +category = "dev" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" files = [ @@ -1717,18 +1945,18 @@ files = [ [[package]] name = "pylint" -version = "2.16.1" +version = "2.17.2" description = "python code static checker" category = "dev" optional = false python-versions = ">=3.7.2" files = [ - {file = "pylint-2.16.1-py3-none-any.whl", hash = "sha256:bad9d7c36037f6043a1e848a43004dfd5ea5ceb05815d713ba56ca4503a9fe37"}, - {file = "pylint-2.16.1.tar.gz", hash = "sha256:ffe7fa536bb38ba35006a7c8a6d2efbfdd3d95bbf21199cad31f76b1c50aaf30"}, + {file = "pylint-2.17.2-py3-none-any.whl", hash = "sha256:001cc91366a7df2970941d7e6bbefcbf98694e00102c1f121c531a814ddc2ea8"}, + {file = "pylint-2.17.2.tar.gz", hash = "sha256:1b647da5249e7c279118f657ca28b6aaebb299f86bf92affc632acf199f7adbb"}, ] [package.dependencies] -astroid = ">=2.14.1,<=2.16.0-dev0" +astroid = ">=2.15.2,<=2.17.0-dev0" colorama = {version = ">=0.4.5", markers = "sys_platform == \"win32\""} dill = {version = ">=0.2", markers = "python_version < \"3.11\""} isort = ">=4.2.5,<6" @@ -1801,18 +2029,17 @@ files = [ [[package]] name = "pytest" -version = "7.2.1" +version = "7.3.1" description = "pytest: simple powerful testing with Python" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "pytest-7.2.1-py3-none-any.whl", hash = "sha256:c7c6ca206e93355074ae32f7403e8ea12163b1163c976fee7d4d84027c162be5"}, - {file = "pytest-7.2.1.tar.gz", hash = "sha256:d45e0952f3727241918b8fd0f376f5ff6b301cc0777c6f9a556935c92d8a7d42"}, + {file = "pytest-7.3.1-py3-none-any.whl", hash = "sha256:3799fa815351fea3a5e96ac7e503a96fa51cc9942c3753cda7651b93c1cfa362"}, + {file = "pytest-7.3.1.tar.gz", hash = "sha256:434afafd78b1d78ed0addf160ad2b77a30d35d4bdf8af234fe621919d9ed15e3"}, ] [package.dependencies] -attrs = ">=19.2.0" colorama = {version = "*", markers = "sys_platform == \"win32\""} exceptiongroup = {version = ">=1.0.0rc8", markers = "python_version < \"3.11\""} iniconfig = "*" @@ -1821,7 +2048,7 @@ pluggy = ">=0.12,<2.0" tomli = {version = ">=1.0.0", markers = "python_version < \"3.11\""} [package.extras] -testing = ["argcomplete", "hypothesis (>=3.56)", "mock", "nose", "pygments (>=2.7.2)", "requests", "xmlschema"] +testing = ["argcomplete", "attrs (>=19.2.0)", "hypothesis (>=3.56)", "mock", "nose", "pygments (>=2.7.2)", "requests", "xmlschema"] [[package]] name = "python-dateutil" @@ -1892,7 +2119,7 @@ files = [ name = "pyzmq" version = "25.0.2" description = "Python bindings for 0MQ" -category = "main" +category = "dev" optional = false python-versions = ">=3.6" files = [ @@ -2079,33 +2306,33 @@ files = [ [[package]] name = "scipy" -version = "1.10.0" +version = "1.10.1" description = "Fundamental algorithms for scientific computing in Python" category = "main" optional = false python-versions = "<3.12,>=3.8" files = [ - {file = "scipy-1.10.0-cp310-cp310-macosx_10_15_x86_64.whl", hash = "sha256:b901b423c91281a974f6cd1c36f5c6c523e665b5a6d5e80fcb2334e14670eefd"}, - {file = "scipy-1.10.0-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:16ba05d3d1b9f2141004f3f36888e05894a525960b07f4c2bfc0456b955a00be"}, - {file = "scipy-1.10.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:151f066fe7d6653c3ffefd489497b8fa66d7316e3e0d0c0f7ff6acca1b802809"}, - {file = "scipy-1.10.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2f9ea0a37aca111a407cb98aa4e8dfde6e5d9333bae06dfa5d938d14c80bb5c3"}, - {file = "scipy-1.10.0-cp310-cp310-win_amd64.whl", hash = "sha256:27e548276b5a88b51212b61f6dda49a24acf5d770dff940bd372b3f7ced8c6c2"}, - {file = "scipy-1.10.0-cp311-cp311-macosx_10_15_x86_64.whl", hash = "sha256:42ab8b9e7dc1ebe248e55f54eea5307b6ab15011a7883367af48dd781d1312e4"}, - {file = "scipy-1.10.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:e096b062d2efdea57f972d232358cb068413dc54eec4f24158bcbb5cb8bddfd8"}, - {file = "scipy-1.10.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4df25a28bd22c990b22129d3c637fd5c3be4b7c94f975dca909d8bab3309b694"}, - {file = "scipy-1.10.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2ad449db4e0820e4b42baccefc98ec772ad7818dcbc9e28b85aa05a536b0f1a2"}, - {file = "scipy-1.10.0-cp311-cp311-win_amd64.whl", hash = "sha256:6faf86ef7717891195ae0537e48da7524d30bc3b828b30c9b115d04ea42f076f"}, - {file = "scipy-1.10.0-cp38-cp38-macosx_10_15_x86_64.whl", hash = "sha256:4bd0e3278126bc882d10414436e58fa3f1eca0aa88b534fcbf80ed47e854f46c"}, - {file = "scipy-1.10.0-cp38-cp38-macosx_12_0_arm64.whl", hash = "sha256:38bfbd18dcc69eeb589811e77fae552fa923067fdfbb2e171c9eac749885f210"}, - {file = "scipy-1.10.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0ab2a58064836632e2cec31ca197d3695c86b066bc4818052b3f5381bfd2a728"}, - {file = "scipy-1.10.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5cd7a30970c29d9768a7164f564d1fbf2842bfc77b7d114a99bc32703ce0bf48"}, - {file = "scipy-1.10.0-cp38-cp38-win_amd64.whl", hash = "sha256:9b878c671655864af59c108c20e4da1e796154bd78c0ed6bb02bc41c84625686"}, - {file = "scipy-1.10.0-cp39-cp39-macosx_10_15_x86_64.whl", hash = "sha256:3afcbddb4488ac950ce1147e7580178b333a29cd43524c689b2e3543a080a2c8"}, - {file = "scipy-1.10.0-cp39-cp39-macosx_12_0_arm64.whl", hash = "sha256:6e4497e5142f325a5423ff5fda2fff5b5d953da028637ff7c704378c8c284ea7"}, - {file = "scipy-1.10.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:441cab2166607c82e6d7a8683779cb89ba0f475b983c7e4ab88f3668e268c143"}, - {file = "scipy-1.10.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0490dc499fe23e4be35b8b6dd1e60a4a34f0c4adb30ac671e6332446b3cbbb5a"}, - {file = "scipy-1.10.0-cp39-cp39-win_amd64.whl", hash = "sha256:954ff69d2d1bf666b794c1d7216e0a746c9d9289096a64ab3355a17c7c59db54"}, - {file = "scipy-1.10.0.tar.gz", hash = "sha256:c8b3cbc636a87a89b770c6afc999baa6bcbb01691b5ccbbc1b1791c7c0a07540"}, + {file = "scipy-1.10.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:e7354fd7527a4b0377ce55f286805b34e8c54b91be865bac273f527e1b839019"}, + {file = "scipy-1.10.1-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:4b3f429188c66603a1a5c549fb414e4d3bdc2a24792e061ffbd607d3d75fd84e"}, + {file = "scipy-1.10.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1553b5dcddd64ba9a0d95355e63fe6c3fc303a8fd77c7bc91e77d61363f7433f"}, + {file = "scipy-1.10.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4c0ff64b06b10e35215abce517252b375e580a6125fd5fdf6421b98efbefb2d2"}, + {file = "scipy-1.10.1-cp310-cp310-win_amd64.whl", hash = "sha256:fae8a7b898c42dffe3f7361c40d5952b6bf32d10c4569098d276b4c547905ee1"}, + {file = "scipy-1.10.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0f1564ea217e82c1bbe75ddf7285ba0709ecd503f048cb1236ae9995f64217bd"}, + {file = "scipy-1.10.1-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:d925fa1c81b772882aa55bcc10bf88324dadb66ff85d548c71515f6689c6dac5"}, + {file = "scipy-1.10.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:aaea0a6be54462ec027de54fca511540980d1e9eea68b2d5c1dbfe084797be35"}, + {file = "scipy-1.10.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:15a35c4242ec5f292c3dd364a7c71a61be87a3d4ddcc693372813c0b73c9af1d"}, + {file = "scipy-1.10.1-cp311-cp311-win_amd64.whl", hash = "sha256:43b8e0bcb877faf0abfb613d51026cd5cc78918e9530e375727bf0625c82788f"}, + {file = "scipy-1.10.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:5678f88c68ea866ed9ebe3a989091088553ba12c6090244fdae3e467b1139c35"}, + {file = "scipy-1.10.1-cp38-cp38-macosx_12_0_arm64.whl", hash = "sha256:39becb03541f9e58243f4197584286e339029e8908c46f7221abeea4b749fa88"}, + {file = "scipy-1.10.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bce5869c8d68cf383ce240e44c1d9ae7c06078a9396df68ce88a1230f93a30c1"}, + {file = "scipy-1.10.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:07c3457ce0b3ad5124f98a86533106b643dd811dd61b548e78cf4c8786652f6f"}, + {file = "scipy-1.10.1-cp38-cp38-win_amd64.whl", hash = "sha256:049a8bbf0ad95277ffba9b3b7d23e5369cc39e66406d60422c8cfef40ccc8415"}, + {file = "scipy-1.10.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:cd9f1027ff30d90618914a64ca9b1a77a431159df0e2a195d8a9e8a04c78abf9"}, + {file = "scipy-1.10.1-cp39-cp39-macosx_12_0_arm64.whl", hash = "sha256:79c8e5a6c6ffaf3a2262ef1be1e108a035cf4f05c14df56057b64acc5bebffb6"}, + {file = "scipy-1.10.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:51af417a000d2dbe1ec6c372dfe688e041a7084da4fdd350aeb139bd3fb55353"}, + {file = "scipy-1.10.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1b4735d6c28aad3cdcf52117e0e91d6b39acd4272f3f5cd9907c24ee931ad601"}, + {file = "scipy-1.10.1-cp39-cp39-win_amd64.whl", hash = "sha256:7ff7f37b1bf4417baca958d254e8e2875d0cc23aaadbe65b3d5b3077b0eb23ea"}, + {file = "scipy-1.10.1.tar.gz", hash = "sha256:2cf9dfb80a7b4589ba4c40ce7588986d6d5cebc5457cad2c2880f6bc2d42f3a5"}, ] [package.dependencies] @@ -2118,14 +2345,14 @@ test = ["asv", "gmpy2", "mpmath", "pooch", "pytest", "pytest-cov", "pytest-timeo [[package]] name = "setuptools" -version = "67.1.0" +version = "67.6.1" description = "Easily download, build, install, upgrade, and uninstall Python packages" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "setuptools-67.1.0-py3-none-any.whl", hash = "sha256:a7687c12b444eaac951ea87a9627c4f904ac757e7abdc5aac32833234af90378"}, - {file = "setuptools-67.1.0.tar.gz", hash = "sha256:e261cdf010c11a41cb5cb5f1bf3338a7433832029f559a6a7614bd42a967c300"}, + {file = "setuptools-67.6.1-py3-none-any.whl", hash = "sha256:e728ca814a823bf7bf60162daf9db95b93d532948c4c0bea762ce62f60189078"}, + {file = "setuptools-67.6.1.tar.gz", hash = "sha256:257de92a9d50a60b8e22abfcbb771571fde0dbf3ec234463212027a4eeecbe9a"}, ] [package.extras] @@ -2244,52 +2471,67 @@ files = [ [[package]] name = "tomlkit" -version = "0.11.6" +version = "0.11.7" description = "Style preserving TOML library" category = "dev" optional = false -python-versions = ">=3.6" +python-versions = ">=3.7" files = [ - {file = "tomlkit-0.11.6-py3-none-any.whl", hash = "sha256:07de26b0d8cfc18f871aec595fda24d95b08fef89d147caa861939f37230bf4b"}, - {file = "tomlkit-0.11.6.tar.gz", hash = "sha256:71b952e5721688937fb02cf9d354dbcf0785066149d2855e44531ebdd2b65d73"}, + {file = "tomlkit-0.11.7-py3-none-any.whl", hash = "sha256:5325463a7da2ef0c6bbfefb62a3dc883aebe679984709aee32a317907d0a8d3c"}, + {file = "tomlkit-0.11.7.tar.gz", hash = "sha256:f392ef70ad87a672f02519f99967d28a4d3047133e2d1df936511465fbb3791d"}, ] [[package]] name = "torch" -version = "1.13.1" +version = "2.0.0" description = "Tensors and Dynamic neural networks in Python with strong GPU acceleration" category = "main" optional = false -python-versions = ">=3.7.0" +python-versions = ">=3.8.0" files = [ - {file = "torch-1.13.1-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:fd12043868a34a8da7d490bf6db66991108b00ffbeecb034228bfcbbd4197143"}, - {file = "torch-1.13.1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:d9fe785d375f2e26a5d5eba5de91f89e6a3be5d11efb497e76705fdf93fa3c2e"}, - {file = "torch-1.13.1-cp310-cp310-win_amd64.whl", hash = "sha256:98124598cdff4c287dbf50f53fb455f0c1e3a88022b39648102957f3445e9b76"}, - {file = "torch-1.13.1-cp310-none-macosx_10_9_x86_64.whl", hash = "sha256:393a6273c832e047581063fb74335ff50b4c566217019cc6ace318cd79eb0566"}, - {file = "torch-1.13.1-cp310-none-macosx_11_0_arm64.whl", hash = "sha256:0122806b111b949d21fa1a5f9764d1fd2fcc4a47cb7f8ff914204fd4fc752ed5"}, - {file = "torch-1.13.1-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:22128502fd8f5b25ac1cd849ecb64a418382ae81dd4ce2b5cebaa09ab15b0d9b"}, - {file = "torch-1.13.1-cp37-cp37m-manylinux1_x86_64.whl", hash = "sha256:76024be052b659ac1304ab8475ab03ea0a12124c3e7626282c9c86798ac7bc11"}, - {file = "torch-1.13.1-cp37-cp37m-manylinux2014_aarch64.whl", hash = "sha256:ea8dda84d796094eb8709df0fcd6b56dc20b58fdd6bc4e8d7109930dafc8e419"}, - {file = "torch-1.13.1-cp37-cp37m-win_amd64.whl", hash = "sha256:2ee7b81e9c457252bddd7d3da66fb1f619a5d12c24d7074de91c4ddafb832c93"}, - {file = "torch-1.13.1-cp37-none-macosx_10_9_x86_64.whl", hash = "sha256:0d9b8061048cfb78e675b9d2ea8503bfe30db43d583599ae8626b1263a0c1380"}, - {file = "torch-1.13.1-cp37-none-macosx_11_0_arm64.whl", hash = "sha256:f402ca80b66e9fbd661ed4287d7553f7f3899d9ab54bf5c67faada1555abde28"}, - {file = "torch-1.13.1-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:727dbf00e2cf858052364c0e2a496684b9cb5aa01dc8a8bc8bbb7c54502bdcdd"}, - {file = "torch-1.13.1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:df8434b0695e9ceb8cc70650afc1310d8ba949e6db2a0525ddd9c3b2b181e5fe"}, - {file = "torch-1.13.1-cp38-cp38-win_amd64.whl", hash = "sha256:5e1e722a41f52a3f26f0c4fcec227e02c6c42f7c094f32e49d4beef7d1e213ea"}, - {file = "torch-1.13.1-cp38-none-macosx_10_9_x86_64.whl", hash = "sha256:33e67eea526e0bbb9151263e65417a9ef2d8fa53cbe628e87310060c9dcfa312"}, - {file = "torch-1.13.1-cp38-none-macosx_11_0_arm64.whl", hash = "sha256:eeeb204d30fd40af6a2d80879b46a7efbe3cf43cdbeb8838dd4f3d126cc90b2b"}, - {file = "torch-1.13.1-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:50ff5e76d70074f6653d191fe4f6a42fdbe0cf942fbe2a3af0b75eaa414ac038"}, - {file = "torch-1.13.1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:2c3581a3fd81eb1f0f22997cddffea569fea53bafa372b2c0471db373b26aafc"}, - {file = "torch-1.13.1-cp39-cp39-win_amd64.whl", hash = "sha256:0aa46f0ac95050c604bcf9ef71da9f1172e5037fdf2ebe051962d47b123848e7"}, - {file = "torch-1.13.1-cp39-none-macosx_10_9_x86_64.whl", hash = "sha256:6930791efa8757cb6974af73d4996b6b50c592882a324b8fb0589c6a9ba2ddaf"}, - {file = "torch-1.13.1-cp39-none-macosx_11_0_arm64.whl", hash = "sha256:e0df902a7c7dd6c795698532ee5970ce898672625635d885eade9976e5a04949"}, + {file = "torch-2.0.0-1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:c9090bda7d2eeeecd74f51b721420dbeb44f838d4536cc1b284e879417e3064a"}, + {file = "torch-2.0.0-1-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:bd42db2a48a20574d2c33489e120e9f32789c4dc13c514b0c44272972d14a2d7"}, + {file = "torch-2.0.0-1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:8969aa8375bcbc0c2993e7ede0a7f889df9515f18b9b548433f412affed478d9"}, + {file = "torch-2.0.0-1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:ab2da16567cb55b67ae39e32d520d68ec736191d88ac79526ca5874754c32203"}, + {file = "torch-2.0.0-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:7a9319a67294ef02459a19738bbfa8727bb5307b822dadd708bc2ccf6c901aca"}, + {file = "torch-2.0.0-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:9f01fe1f6263f31bd04e1757946fd63ad531ae37f28bb2dbf66f5c826ee089f4"}, + {file = "torch-2.0.0-cp310-cp310-win_amd64.whl", hash = "sha256:527f4ae68df7b8301ee6b1158ca56350282ea633686537b30dbb5d7b4a52622a"}, + {file = "torch-2.0.0-cp310-none-macosx_10_9_x86_64.whl", hash = "sha256:ce9b5a49bd513dff7950a5a07d6e26594dd51989cee05ba388b03e8e366fd5d5"}, + {file = "torch-2.0.0-cp310-none-macosx_11_0_arm64.whl", hash = "sha256:53e1c33c6896583cdb9a583693e22e99266444c4a43392dddc562640d39e542b"}, + {file = "torch-2.0.0-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:09651bff72e439d004c991f15add0c397c66f98ab36fe60d5514b44e4da722e8"}, + {file = "torch-2.0.0-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:d439aec349c98f12819e8564b8c54008e4613dd4428582af0e6e14c24ca85870"}, + {file = "torch-2.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:2802f84f021907deee7e9470ed10c0e78af7457ac9a08a6cd7d55adef835fede"}, + {file = "torch-2.0.0-cp311-none-macosx_10_9_x86_64.whl", hash = "sha256:01858620f25f25e7a9ec4b547ff38e5e27c92d38ec4ccba9cfbfb31d7071ed9c"}, + {file = "torch-2.0.0-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:9a2e53b5783ef5896a6af338b36d782f28e83c8ddfc2ac44b67b066d9d76f498"}, + {file = "torch-2.0.0-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:ec5fff2447663e369682838ff0f82187b4d846057ef4d119a8dea7772a0b17dd"}, + {file = "torch-2.0.0-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:11b0384fe3c18c01b8fc5992e70fc519cde65e44c51cc87be1838c1803daf42f"}, + {file = "torch-2.0.0-cp38-cp38-win_amd64.whl", hash = "sha256:e54846aa63855298cfb1195487f032e413e7ac9cbfa978fda32354cc39551475"}, + {file = "torch-2.0.0-cp38-none-macosx_10_9_x86_64.whl", hash = "sha256:cc788cbbbbc6eb4c90e52c550efd067586c2693092cf367c135b34893a64ae78"}, + {file = "torch-2.0.0-cp38-none-macosx_11_0_arm64.whl", hash = "sha256:d292640f0fd72b7a31b2a6e3b635eb5065fcbedd4478f9cad1a1e7a9ec861d35"}, + {file = "torch-2.0.0-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:6befaad784004b7af357e3d87fa0863c1f642866291f12a4c2af2de435e8ac5c"}, + {file = "torch-2.0.0-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:a83b26bd6ae36fbf5fee3d56973d9816e2002e8a3b7d9205531167c28aaa38a7"}, + {file = "torch-2.0.0-cp39-cp39-win_amd64.whl", hash = "sha256:c7e67195e1c3e33da53954b026e89a8e1ff3bc1aeb9eb32b677172d4a9b5dcbf"}, + {file = "torch-2.0.0-cp39-none-macosx_10_9_x86_64.whl", hash = "sha256:6e0b97beb037a165669c312591f242382e9109a240e20054d5a5782d9236cad0"}, + {file = "torch-2.0.0-cp39-none-macosx_11_0_arm64.whl", hash = "sha256:297a4919aff1c0f98a58ebe969200f71350a1d4d4f986dbfd60c02ffce780e99"}, ] [package.dependencies] -nvidia-cublas-cu11 = {version = "11.10.3.66", markers = "platform_system == \"Linux\""} -nvidia-cuda-nvrtc-cu11 = {version = "11.7.99", markers = "platform_system == \"Linux\""} -nvidia-cuda-runtime-cu11 = {version = "11.7.99", markers = "platform_system == \"Linux\""} -nvidia-cudnn-cu11 = {version = "8.5.0.96", markers = "platform_system == \"Linux\""} +filelock = "*" +jinja2 = "*" +networkx = "*" +nvidia-cublas-cu11 = {version = "11.10.3.66", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cuda-cupti-cu11 = {version = "11.7.101", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cuda-nvrtc-cu11 = {version = "11.7.99", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cuda-runtime-cu11 = {version = "11.7.99", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cudnn-cu11 = {version = "8.5.0.96", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cufft-cu11 = {version = "10.9.0.58", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-curand-cu11 = {version = "10.2.10.91", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cusolver-cu11 = {version = "11.4.0.1", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cusparse-cu11 = {version = "11.7.4.91", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-nccl-cu11 = {version = "2.14.3", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-nvtx-cu11 = {version = "11.7.91", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +sympy = "*" +triton = {version = "2.0.0", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} typing-extensions = "*" [package.extras] @@ -2297,53 +2539,53 @@ opt-einsum = ["opt-einsum (>=3.3)"] [[package]] name = "torchvision" -version = "0.14.1" +version = "0.15.1" description = "image and video datasets and models for torch deep learning" category = "main" optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "torchvision-0.14.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:eeb05dd9dd3af5428fee525400759daf8da8e4caec45ddd6908cfb36571f6433"}, - {file = "torchvision-0.14.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8d0766ea92affa7af248e327dd85f7c9cfdf51a57530b43212d4e1858548e9d7"}, - {file = "torchvision-0.14.1-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:6d7b35653113664ea3fdcb71f515cfbf29d2fe393000fd8aaff27a1284de6908"}, - {file = "torchvision-0.14.1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:8a9eb773a2fa8f516e404ac09c059fb14e6882c48fdbb9c946327d2ce5dba6cd"}, - {file = "torchvision-0.14.1-cp310-cp310-win_amd64.whl", hash = "sha256:13986f0c15377ff23039e1401012ccb6ecf71024ce53def27139e4eac5a57592"}, - {file = "torchvision-0.14.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:fb7a793fd33ce1abec24b42778419a3fb1e3159d7dfcb274a3ca8fb8cbc408dc"}, - {file = "torchvision-0.14.1-cp37-cp37m-manylinux1_x86_64.whl", hash = "sha256:89fb0419780ec9a9eb9f7856a0149f6ac9f956b28f44b0c0080c6b5b48044db7"}, - {file = "torchvision-0.14.1-cp37-cp37m-manylinux2014_aarch64.whl", hash = "sha256:a2d4237d3c9705d7729eb4534e4eb06f1d6be7ff1df391204dfb51586d9b0ecb"}, - {file = "torchvision-0.14.1-cp37-cp37m-win_amd64.whl", hash = "sha256:92a324712a87957443cc34223274298ae9496853f115c252f8fc02b931f2340e"}, - {file = "torchvision-0.14.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:68ed03359dcd3da9cd21b8ab94da21158df8a6a0c5bad0bf4a42f0e448d28cb3"}, - {file = "torchvision-0.14.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:30fcf0e9fe57d4ac4ce6426659a57dce199637ccb6c70be1128670f177692624"}, - {file = "torchvision-0.14.1-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:0ed02aefd09bf1114d35f1aa7dce55aa61c2c7e57f9aa02dce362860be654e85"}, - {file = "torchvision-0.14.1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:a541e49fc3c4e90e49e6988428ab047415ed52ea97d0c0bfd147d8bacb8f4df8"}, - {file = "torchvision-0.14.1-cp38-cp38-win_amd64.whl", hash = "sha256:6099b3191dc2516099a32ae38a5fb349b42e863872a13545ab1a524b6567be60"}, - {file = "torchvision-0.14.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:c5e744f56e5f5b452deb5fc0f3f2ba4d2f00612d14d8da0dbefea8f09ac7690b"}, - {file = "torchvision-0.14.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:758b20d079e810b4740bd60d1eb16e49da830e3360f9be379eb177ee221fa5d4"}, - {file = "torchvision-0.14.1-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:83045507ef8d3c015d4df6be79491375b2f901352cfca6e72b4723e9c4f9a55d"}, - {file = "torchvision-0.14.1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:eaed58cf454323ed9222d4e0dd5fb897064f454b400696e03a5200e65d3a1e76"}, - {file = "torchvision-0.14.1-cp39-cp39-win_amd64.whl", hash = "sha256:b337e1245ca4353623dd563c03cd8f020c2496a7c5d12bba4d2e381999c766e0"}, + {file = "torchvision-0.15.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:bc10d48e9a60d006d0c1b48dea87f1ec9b63d856737d592f7c5c44cd87f3f4b7"}, + {file = "torchvision-0.15.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:3708d3410fdcaf6280e358cda9de2a4ab06cc0b4c0fd9aeeac550ec2563a887e"}, + {file = "torchvision-0.15.1-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:d4de10c837f1493c1c54344388e300a06c96914c6cc55fcb2527c21f2f010bbd"}, + {file = "torchvision-0.15.1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:b82fcc5abc9b5c96495c76596a1573025cc1e09d97d2d6fda717c44b9ca45881"}, + {file = "torchvision-0.15.1-cp310-cp310-win_amd64.whl", hash = "sha256:c84e97d8cc4fe167d87adad0a2a6424cff90544365545b20669bc50e6ea46875"}, + {file = "torchvision-0.15.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:97b90eb3b7333a31d049c4ccfd1064361e8491874959d38f466af64d67418cef"}, + {file = "torchvision-0.15.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:6b60e1c839ae2a071befbba69b17468d67feafdf576e90ff9645bfbee998de17"}, + {file = "torchvision-0.15.1-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:13f71a3372d9168b01481a754ebaa171207f3dc455bf2fd86906c69222443738"}, + {file = "torchvision-0.15.1-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:b2e8394726009090b40f6cc3a95cc878cc011dfac3d8e7a6060c79213d360880"}, + {file = "torchvision-0.15.1-cp311-cp311-win_amd64.whl", hash = "sha256:2852f501189483187ce9eb0ccd01b3f4f0918d29057e4a18b3cce8dad9a8a964"}, + {file = "torchvision-0.15.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:e5861baaeea87d19b6fd7d131e11a4a6bd17be14234c490a259bb360775e9520"}, + {file = "torchvision-0.15.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:e714f362b9d8217cf4d68509b679ebc9ddf128cfe80f6c1def8e3f8a18466e75"}, + {file = "torchvision-0.15.1-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:43624accad1e47f16824be4db37ad678dd89326ad90b69c9c6363eeb22b9467e"}, + {file = "torchvision-0.15.1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:7fe9b0cd3311b0db9e6d45ffab594ced06418fa4e2aa15eb2e60d55e5c51135c"}, + {file = "torchvision-0.15.1-cp38-cp38-win_amd64.whl", hash = "sha256:b45324ea4911a23a4b00b5a15cdbe36d47f93137206dab9f8c606d81b69dd3a7"}, + {file = "torchvision-0.15.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:1dfdec7c7df967330bba3341a781e0c047d4e0163e67164a9918500362bf7d91"}, + {file = "torchvision-0.15.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:c153710186cec0338d4fff411459a57ddbc8504436123ca73b3f0bdc26ff918c"}, + {file = "torchvision-0.15.1-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:ff4e650aa601f32ab97bce06704868dd2baad69ca4d454fa1f0012a51199f2bc"}, + {file = "torchvision-0.15.1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:e9b4bb2a15849391df0415d2f76dd36e6528e4253f7b69322b7a0d682535544b"}, + {file = "torchvision-0.15.1-cp39-cp39-win_amd64.whl", hash = "sha256:21e6beb69e77ef6575c4fdd0ab332b96e8a7f144eee0d333acff469c827a4b5e"}, ] [package.dependencies] numpy = "*" pillow = ">=5.3.0,<8.3.0 || >=8.4.0" requests = "*" -torch = "1.13.1" -typing-extensions = "*" +torch = "2.0.0" [package.extras] scipy = ["scipy"] [[package]] name = "trimesh" -version = "3.18.3" +version = "3.21.5" description = "Import, export, process, analyze and view triangular meshes." category = "main" optional = false python-versions = "*" files = [ - {file = "trimesh-3.18.3-py3-none-any.whl", hash = "sha256:7427fe09a3591b0e9d5d5fc03afccce761c2a5e89508741543fc41f986ee15e5"}, - {file = "trimesh-3.18.3.tar.gz", hash = "sha256:955a01041af3ca1ad2991d85334c68f1424108e4a1c1a60eac8a5e030427efa3"}, + {file = "trimesh-3.21.5-py3-none-any.whl", hash = "sha256:5ae1ca5e4f4a5f41aa79067a9c39e083e37d7148022bb150cb0e6f89ec614df3"}, + {file = "trimesh-3.21.5.tar.gz", hash = "sha256:74741bc7f9fcb94b98951db8dc8ec8364a2ef52ac2ca0761c7ba06182ef329be"}, ] [package.dependencies] @@ -2352,7 +2594,6 @@ colorlog = {version = "*", optional = true, markers = "extra == \"easy\""} jsonschema = {version = "*", optional = true, markers = "extra == \"easy\""} lxml = {version = "*", optional = true, markers = "extra == \"easy\""} mapbox-earcut = {version = "*", optional = true, markers = "extra == \"easy\""} -msgpack = {version = "*", optional = true, markers = "extra == \"easy\""} networkx = {version = "*", optional = true, markers = "extra == \"easy\""} numpy = "*" pillow = {version = "*", optional = true, markers = "extra == \"easy\""} @@ -2367,20 +2608,58 @@ sympy = {version = "*", optional = true, markers = "extra == \"easy\""} xxhash = {version = "*", optional = true, markers = "extra == \"easy\""} [package.extras] -all = ["chardet", "colorlog", "glooey", "jsonschema", "lxml", "mapbox-earcut", "meshio", "msgpack", "networkx", "pillow", "psutil", "pycollada", "pyglet (<2)", "python-fcl", "requests", "rtree", "scikit-image", "scipy", "setuptools", "shapely", "svg.path", "sympy", "xatlas", "xxhash"] -easy = ["chardet", "colorlog", "jsonschema", "lxml", "mapbox-earcut", "msgpack", "networkx", "pillow", "pycollada", "requests", "rtree", "scipy", "setuptools", "shapely", "svg.path", "sympy", "xxhash"] -test = ["autopep8", "coveralls", "ezdxf", "flake8", "flake8-no-implicit-concat", "flake8-pyproject", "pyinstrument", "pytest", "pytest-cov"] +all = ["chardet", "colorlog", "glooey", "jsonschema", "lxml", "mapbox-earcut", "meshio", "networkx", "pillow", "psutil", "pycollada", "pyglet (<2)", "python-fcl", "requests", "rtree", "scikit-image", "scipy", "setuptools", "shapely", "svg.path", "sympy", "xatlas", "xxhash"] +easy = ["chardet", "colorlog", "jsonschema", "lxml", "mapbox-earcut", "networkx", "pillow", "pycollada", "requests", "rtree", "scipy", "setuptools", "shapely", "svg.path", "sympy", "xxhash"] +test = ["autopep8", "coveralls", "ezdxf", "pyinstrument", "pytest", "pytest-cov", "ruff"] + +[[package]] +name = "triton" +version = "2.0.0" +description = "A language and compiler for custom Deep Learning operations" +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "triton-2.0.0-1-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:38806ee9663f4b0f7cd64790e96c579374089e58f49aac4a6608121aa55e2505"}, + {file = "triton-2.0.0-1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:226941c7b8595219ddef59a1fdb821e8c744289a132415ddd584facedeb475b1"}, + {file = "triton-2.0.0-1-cp36-cp36m-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4c9fc8c89874bc48eb7e7b2107a9b8d2c0bf139778637be5bfccb09191685cfd"}, + {file = "triton-2.0.0-1-cp37-cp37m-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d2684b6a60b9f174f447f36f933e9a45f31db96cb723723ecd2dcfd1c57b778b"}, + {file = "triton-2.0.0-1-cp38-cp38-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:9d4978298b74fcf59a75fe71e535c092b023088933b2f1df933ec32615e4beef"}, + {file = "triton-2.0.0-1-cp39-cp39-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:74f118c12b437fb2ca25e1a04759173b517582fcf4c7be11913316c764213656"}, + {file = "triton-2.0.0-1-pp37-pypy37_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:9618815a8da1d9157514f08f855d9e9ff92e329cd81c0305003eb9ec25cc5add"}, + {file = "triton-2.0.0-1-pp38-pypy38_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1aca3303629cd3136375b82cb9921727f804e47ebee27b2677fef23005c3851a"}, + {file = "triton-2.0.0-1-pp39-pypy39_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e3e13aa8b527c9b642e3a9defcc0fbd8ffbe1c80d8ac8c15a01692478dc64d8a"}, + {file = "triton-2.0.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f05a7e64e4ca0565535e3d5d3405d7e49f9d308505bb7773d21fb26a4c008c2"}, + {file = "triton-2.0.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bb4b99ca3c6844066e516658541d876c28a5f6e3a852286bbc97ad57134827fd"}, + {file = "triton-2.0.0-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:47b4d70dc92fb40af553b4460492c31dc7d3a114a979ffb7a5cdedb7eb546c08"}, + {file = "triton-2.0.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fedce6a381901b1547e0e7e1f2546e4f65dca6d91e2d8a7305a2d1f5551895be"}, + {file = "triton-2.0.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:75834f27926eab6c7f00ce73aaf1ab5bfb9bec6eb57ab7c0bfc0a23fac803b4c"}, + {file = "triton-2.0.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0117722f8c2b579cd429e0bee80f7731ae05f63fe8e9414acd9a679885fcbf42"}, + {file = "triton-2.0.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bcd9be5d0c2e45d2b7e6ddc6da20112b6862d69741576f9c3dbaf941d745ecae"}, + {file = "triton-2.0.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:42a0d2c3fc2eab4ba71384f2e785fbfd47aa41ae05fa58bf12cb31dcbd0aeceb"}, + {file = "triton-2.0.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:52c47b72c72693198163ece9d90a721299e4fb3b8e24fd13141e384ad952724f"}, +] + +[package.dependencies] +cmake = "*" +filelock = "*" +lit = "*" +torch = "*" + +[package.extras] +tests = ["autopep8", "flake8", "isort", "numpy", "pytest", "scipy (>=1.7.1)"] +tutorials = ["matplotlib", "pandas", "tabulate"] [[package]] name = "typing-extensions" -version = "4.4.0" +version = "4.5.0" description = "Backported and Experimental Type Hints for Python 3.7+" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "typing_extensions-4.4.0-py3-none-any.whl", hash = "sha256:16fa4864408f655d35ec496218b85f79b3437c829e93320c7c9215ccfd92489e"}, - {file = "typing_extensions-4.4.0.tar.gz", hash = "sha256:1511434bb92bf8dd198c12b1cc812e800d4181cfcb867674e0f8279cc93087aa"}, + {file = "typing_extensions-4.5.0-py3-none-any.whl", hash = "sha256:fb33085c39dd998ac16d1431ebc293a8b3eedd00fd4a32de0ff79002c19511b4"}, + {file = "typing_extensions-4.5.0.tar.gz", hash = "sha256:5cb5f4a79139d699607b3ef622a1dedafa84e115ab0024e0d9c044a9479ca7cb"}, ] [[package]] @@ -2400,34 +2679,34 @@ pyyaml = "*" [[package]] name = "urdfenvs" -version = "0.5.2" +version = "0.5.6" description = "Simple simulation environment for robots, based on the urdf files." category = "dev" optional = false python-versions = ">=3.8,<4.0" files = [ - {file = "urdfenvs-0.5.2-py3-none-any.whl", hash = "sha256:deaa6fd39deab9b653dee93c1ad5cf15ccb103178395eb9ee12be0bfa02ffcc3"}, - {file = "urdfenvs-0.5.2.tar.gz", hash = "sha256:ea94e48fb76494bb1d01188390dcfbfc48e09871bd36c1e57aaf947929da6c14"}, + {file = "urdfenvs-0.5.6-py3-none-any.whl", hash = "sha256:dab593f02c26e3121575eb3be3429f738f55df5c7a67d802a1cba90216e59ac7"}, + {file = "urdfenvs-0.5.6.tar.gz", hash = "sha256:4424165b8be92db7af356a98407e5b6d9bf428b33e5c1727ab4f0a4e71bb242b"}, ] [package.dependencies] deprecation = ">=2.1.0,<3.0.0" gym = ">=0.22,<0.23" -mpscenes = ">=0.3.0,<0.4.0" +mpscenes = ">=0.3.1,<0.4.0" numpy = ">=1.19,<1.24" pybullet = ">=3.2.1,<4.0.0" yourdfpy = ">=0.0.52,<0.0.53" [[package]] name = "urllib3" -version = "1.26.14" +version = "1.26.15" description = "HTTP library with thread-safe connection pooling, file post, and more." category = "main" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*, !=3.5.*" files = [ - {file = "urllib3-1.26.14-py2.py3-none-any.whl", hash = "sha256:75edcdc2f7d85b137124a6c3c9fc3933cdeaa12ecb9a6a959f22797a0feca7e1"}, - {file = "urllib3-1.26.14.tar.gz", hash = "sha256:076907bf8fd355cde77728471316625a4d2f7e713c125f51953bb5b3eecf4f72"}, + {file = "urllib3-1.26.15-py2.py3-none-any.whl", hash = "sha256:aa751d169e23c7479ce47a0cb0da579e3ede798f994f5816a74e4f4500dcea42"}, + {file = "urllib3-1.26.15.tar.gz", hash = "sha256:8a388717b9476f934a21484e8c8e61875ab60644d29b9b39e11e4b9dc1c6b305"}, ] [package.extras] @@ -2437,91 +2716,102 @@ socks = ["PySocks (>=1.5.6,!=1.5.7,<2.0)"] [[package]] name = "wheel" -version = "0.38.4" +version = "0.40.0" description = "A built-package format for Python" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "wheel-0.38.4-py3-none-any.whl", hash = "sha256:b60533f3f5d530e971d6737ca6d58681ee434818fab630c83a734bb10c083ce8"}, - {file = "wheel-0.38.4.tar.gz", hash = "sha256:965f5259b566725405b05e7cf774052044b1ed30119b5d586b2703aafe8719ac"}, + {file = "wheel-0.40.0-py3-none-any.whl", hash = "sha256:d236b20e7cb522daf2390fa84c55eea81c5c30190f90f29ae2ca1ad8355bf247"}, + {file = "wheel-0.40.0.tar.gz", hash = "sha256:cd1196f3faee2b31968d626e1731c94f99cbdb67cf5a46e4f5656cbee7738873"}, ] [package.extras] -test = ["pytest (>=3.0.0)"] +test = ["pytest (>=6.0.0)"] [[package]] name = "wrapt" -version = "1.14.1" +version = "1.15.0" description = "Module for decorators, wrappers and monkey patching." category = "dev" optional = false python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,>=2.7" files = [ - {file = "wrapt-1.14.1-cp27-cp27m-macosx_10_9_x86_64.whl", hash = "sha256:1b376b3f4896e7930f1f772ac4b064ac12598d1c38d04907e696cc4d794b43d3"}, - {file = "wrapt-1.14.1-cp27-cp27m-manylinux1_i686.whl", hash = "sha256:903500616422a40a98a5a3c4ff4ed9d0066f3b4c951fa286018ecdf0750194ef"}, - {file = "wrapt-1.14.1-cp27-cp27m-manylinux1_x86_64.whl", hash = "sha256:5a9a0d155deafd9448baff28c08e150d9b24ff010e899311ddd63c45c2445e28"}, - {file = "wrapt-1.14.1-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:ddaea91abf8b0d13443f6dac52e89051a5063c7d014710dcb4d4abb2ff811a59"}, - {file = "wrapt-1.14.1-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:36f582d0c6bc99d5f39cd3ac2a9062e57f3cf606ade29a0a0d6b323462f4dd87"}, - {file = "wrapt-1.14.1-cp27-cp27mu-manylinux1_i686.whl", hash = "sha256:7ef58fb89674095bfc57c4069e95d7a31cfdc0939e2a579882ac7d55aadfd2a1"}, - {file = "wrapt-1.14.1-cp27-cp27mu-manylinux1_x86_64.whl", hash = "sha256:e2f83e18fe2f4c9e7db597e988f72712c0c3676d337d8b101f6758107c42425b"}, - {file = "wrapt-1.14.1-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:ee2b1b1769f6707a8a445162ea16dddf74285c3964f605877a20e38545c3c462"}, - {file = "wrapt-1.14.1-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:833b58d5d0b7e5b9832869f039203389ac7cbf01765639c7309fd50ef619e0b1"}, - {file = "wrapt-1.14.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:80bb5c256f1415f747011dc3604b59bc1f91c6e7150bd7db03b19170ee06b320"}, - {file = "wrapt-1.14.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:07f7a7d0f388028b2df1d916e94bbb40624c59b48ecc6cbc232546706fac74c2"}, - {file = "wrapt-1.14.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:02b41b633c6261feff8ddd8d11c711df6842aba629fdd3da10249a53211a72c4"}, - {file = "wrapt-1.14.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2fe803deacd09a233e4762a1adcea5db5d31e6be577a43352936179d14d90069"}, - {file = "wrapt-1.14.1-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:257fd78c513e0fb5cdbe058c27a0624c9884e735bbd131935fd49e9fe719d310"}, - {file = "wrapt-1.14.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:4fcc4649dc762cddacd193e6b55bc02edca674067f5f98166d7713b193932b7f"}, - {file = "wrapt-1.14.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:11871514607b15cfeb87c547a49bca19fde402f32e2b1c24a632506c0a756656"}, - {file = "wrapt-1.14.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:8ad85f7f4e20964db4daadcab70b47ab05c7c1cf2a7c1e51087bfaa83831854c"}, - {file = "wrapt-1.14.1-cp310-cp310-win32.whl", hash = "sha256:a9a52172be0b5aae932bef82a79ec0a0ce87288c7d132946d645eba03f0ad8a8"}, - {file = "wrapt-1.14.1-cp310-cp310-win_amd64.whl", hash = "sha256:6d323e1554b3d22cfc03cd3243b5bb815a51f5249fdcbb86fda4bf62bab9e164"}, - {file = "wrapt-1.14.1-cp35-cp35m-manylinux1_i686.whl", hash = "sha256:43ca3bbbe97af00f49efb06e352eae40434ca9d915906f77def219b88e85d907"}, - {file = "wrapt-1.14.1-cp35-cp35m-manylinux1_x86_64.whl", hash = "sha256:6b1a564e6cb69922c7fe3a678b9f9a3c54e72b469875aa8018f18b4d1dd1adf3"}, - {file = "wrapt-1.14.1-cp35-cp35m-manylinux2010_i686.whl", hash = "sha256:00b6d4ea20a906c0ca56d84f93065b398ab74b927a7a3dbd470f6fc503f95dc3"}, - {file = "wrapt-1.14.1-cp35-cp35m-manylinux2010_x86_64.whl", hash = "sha256:a85d2b46be66a71bedde836d9e41859879cc54a2a04fad1191eb50c2066f6e9d"}, - {file = "wrapt-1.14.1-cp35-cp35m-win32.whl", hash = "sha256:dbcda74c67263139358f4d188ae5faae95c30929281bc6866d00573783c422b7"}, - {file = "wrapt-1.14.1-cp35-cp35m-win_amd64.whl", hash = "sha256:b21bb4c09ffabfa0e85e3a6b623e19b80e7acd709b9f91452b8297ace2a8ab00"}, - {file = "wrapt-1.14.1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:9e0fd32e0148dd5dea6af5fee42beb949098564cc23211a88d799e434255a1f4"}, - {file = "wrapt-1.14.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9736af4641846491aedb3c3f56b9bc5568d92b0692303b5a305301a95dfd38b1"}, - {file = "wrapt-1.14.1-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5b02d65b9ccf0ef6c34cba6cf5bf2aab1bb2f49c6090bafeecc9cd81ad4ea1c1"}, - {file = "wrapt-1.14.1-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:21ac0156c4b089b330b7666db40feee30a5d52634cc4560e1905d6529a3897ff"}, - {file = "wrapt-1.14.1-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:9f3e6f9e05148ff90002b884fbc2a86bd303ae847e472f44ecc06c2cd2fcdb2d"}, - {file = "wrapt-1.14.1-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:6e743de5e9c3d1b7185870f480587b75b1cb604832e380d64f9504a0535912d1"}, - {file = "wrapt-1.14.1-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:d79d7d5dc8a32b7093e81e97dad755127ff77bcc899e845f41bf71747af0c569"}, - {file = "wrapt-1.14.1-cp36-cp36m-win32.whl", hash = "sha256:81b19725065dcb43df02b37e03278c011a09e49757287dca60c5aecdd5a0b8ed"}, - {file = "wrapt-1.14.1-cp36-cp36m-win_amd64.whl", hash = "sha256:b014c23646a467558be7da3d6b9fa409b2c567d2110599b7cf9a0c5992b3b471"}, - {file = "wrapt-1.14.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:88bd7b6bd70a5b6803c1abf6bca012f7ed963e58c68d76ee20b9d751c74a3248"}, - {file = "wrapt-1.14.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b5901a312f4d14c59918c221323068fad0540e34324925c8475263841dbdfe68"}, - {file = "wrapt-1.14.1-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d77c85fedff92cf788face9bfa3ebaa364448ebb1d765302e9af11bf449ca36d"}, - {file = "wrapt-1.14.1-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8d649d616e5c6a678b26d15ece345354f7c2286acd6db868e65fcc5ff7c24a77"}, - {file = "wrapt-1.14.1-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:7d2872609603cb35ca513d7404a94d6d608fc13211563571117046c9d2bcc3d7"}, - {file = "wrapt-1.14.1-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:ee6acae74a2b91865910eef5e7de37dc6895ad96fa23603d1d27ea69df545015"}, - {file = "wrapt-1.14.1-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:2b39d38039a1fdad98c87279b48bc5dce2c0ca0d73483b12cb72aa9609278e8a"}, - {file = "wrapt-1.14.1-cp37-cp37m-win32.whl", hash = "sha256:60db23fa423575eeb65ea430cee741acb7c26a1365d103f7b0f6ec412b893853"}, - {file = "wrapt-1.14.1-cp37-cp37m-win_amd64.whl", hash = "sha256:709fe01086a55cf79d20f741f39325018f4df051ef39fe921b1ebe780a66184c"}, - {file = "wrapt-1.14.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:8c0ce1e99116d5ab21355d8ebe53d9460366704ea38ae4d9f6933188f327b456"}, - {file = "wrapt-1.14.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:e3fb1677c720409d5f671e39bac6c9e0e422584e5f518bfd50aa4cbbea02433f"}, - {file = "wrapt-1.14.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:642c2e7a804fcf18c222e1060df25fc210b9c58db7c91416fb055897fc27e8cc"}, - {file = "wrapt-1.14.1-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7b7c050ae976e286906dd3f26009e117eb000fb2cf3533398c5ad9ccc86867b1"}, - {file = "wrapt-1.14.1-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ef3f72c9666bba2bab70d2a8b79f2c6d2c1a42a7f7e2b0ec83bb2f9e383950af"}, - {file = "wrapt-1.14.1-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:01c205616a89d09827986bc4e859bcabd64f5a0662a7fe95e0d359424e0e071b"}, - {file = "wrapt-1.14.1-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:5a0f54ce2c092aaf439813735584b9537cad479575a09892b8352fea5e988dc0"}, - {file = "wrapt-1.14.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:2cf71233a0ed05ccdabe209c606fe0bac7379fdcf687f39b944420d2a09fdb57"}, - {file = "wrapt-1.14.1-cp38-cp38-win32.whl", hash = "sha256:aa31fdcc33fef9eb2552cbcbfee7773d5a6792c137b359e82879c101e98584c5"}, - {file = "wrapt-1.14.1-cp38-cp38-win_amd64.whl", hash = "sha256:d1967f46ea8f2db647c786e78d8cc7e4313dbd1b0aca360592d8027b8508e24d"}, - {file = "wrapt-1.14.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:3232822c7d98d23895ccc443bbdf57c7412c5a65996c30442ebe6ed3df335383"}, - {file = "wrapt-1.14.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:988635d122aaf2bdcef9e795435662bcd65b02f4f4c1ae37fbee7401c440b3a7"}, - {file = "wrapt-1.14.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9cca3c2cdadb362116235fdbd411735de4328c61425b0aa9f872fd76d02c4e86"}, - {file = "wrapt-1.14.1-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d52a25136894c63de15a35bc0bdc5adb4b0e173b9c0d07a2be9d3ca64a332735"}, - {file = "wrapt-1.14.1-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40e7bc81c9e2b2734ea4bc1aceb8a8f0ceaac7c5299bc5d69e37c44d9081d43b"}, - {file = "wrapt-1.14.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:b9b7a708dd92306328117d8c4b62e2194d00c365f18eff11a9b53c6f923b01e3"}, - {file = "wrapt-1.14.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:6a9a25751acb379b466ff6be78a315e2b439d4c94c1e99cb7266d40a537995d3"}, - {file = "wrapt-1.14.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:34aa51c45f28ba7f12accd624225e2b1e5a3a45206aa191f6f9aac931d9d56fe"}, - {file = "wrapt-1.14.1-cp39-cp39-win32.whl", hash = "sha256:dee0ce50c6a2dd9056c20db781e9c1cfd33e77d2d569f5d1d9321c641bb903d5"}, - {file = "wrapt-1.14.1-cp39-cp39-win_amd64.whl", hash = "sha256:dee60e1de1898bde3b238f18340eec6148986da0455d8ba7848d50470a7a32fb"}, - {file = "wrapt-1.14.1.tar.gz", hash = "sha256:380a85cf89e0e69b7cfbe2ea9f765f004ff419f34194018a6827ac0e3edfed4d"}, + {file = "wrapt-1.15.0-cp27-cp27m-macosx_10_9_x86_64.whl", hash = "sha256:ca1cccf838cd28d5a0883b342474c630ac48cac5df0ee6eacc9c7290f76b11c1"}, + {file = "wrapt-1.15.0-cp27-cp27m-manylinux1_i686.whl", hash = "sha256:e826aadda3cae59295b95343db8f3d965fb31059da7de01ee8d1c40a60398b29"}, + {file = "wrapt-1.15.0-cp27-cp27m-manylinux1_x86_64.whl", hash = "sha256:5fc8e02f5984a55d2c653f5fea93531e9836abbd84342c1d1e17abc4a15084c2"}, + {file = "wrapt-1.15.0-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:96e25c8603a155559231c19c0349245eeb4ac0096fe3c1d0be5c47e075bd4f46"}, + {file = "wrapt-1.15.0-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:40737a081d7497efea35ab9304b829b857f21558acfc7b3272f908d33b0d9d4c"}, + {file = "wrapt-1.15.0-cp27-cp27mu-manylinux1_i686.whl", hash = "sha256:f87ec75864c37c4c6cb908d282e1969e79763e0d9becdfe9fe5473b7bb1e5f09"}, + {file = "wrapt-1.15.0-cp27-cp27mu-manylinux1_x86_64.whl", hash = "sha256:1286eb30261894e4c70d124d44b7fd07825340869945c79d05bda53a40caa079"}, + {file = "wrapt-1.15.0-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:493d389a2b63c88ad56cdc35d0fa5752daac56ca755805b1b0c530f785767d5e"}, + {file = "wrapt-1.15.0-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:58d7a75d731e8c63614222bcb21dd992b4ab01a399f1f09dd82af17bbfc2368a"}, + {file = "wrapt-1.15.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:21f6d9a0d5b3a207cdf7acf8e58d7d13d463e639f0c7e01d82cdb671e6cb7923"}, + {file = "wrapt-1.15.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ce42618f67741d4697684e501ef02f29e758a123aa2d669e2d964ff734ee00ee"}, + {file = "wrapt-1.15.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:41d07d029dd4157ae27beab04d22b8e261eddfc6ecd64ff7000b10dc8b3a5727"}, + {file = "wrapt-1.15.0-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:54accd4b8bc202966bafafd16e69da9d5640ff92389d33d28555c5fd4f25ccb7"}, + {file = "wrapt-1.15.0-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2fbfbca668dd15b744418265a9607baa970c347eefd0db6a518aaf0cfbd153c0"}, + {file = "wrapt-1.15.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:76e9c727a874b4856d11a32fb0b389afc61ce8aaf281ada613713ddeadd1cfec"}, + {file = "wrapt-1.15.0-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:e20076a211cd6f9b44a6be58f7eeafa7ab5720eb796975d0c03f05b47d89eb90"}, + {file = "wrapt-1.15.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:a74d56552ddbde46c246b5b89199cb3fd182f9c346c784e1a93e4dc3f5ec9975"}, + {file = "wrapt-1.15.0-cp310-cp310-win32.whl", hash = "sha256:26458da5653aa5b3d8dc8b24192f574a58984c749401f98fff994d41d3f08da1"}, + {file = "wrapt-1.15.0-cp310-cp310-win_amd64.whl", hash = "sha256:75760a47c06b5974aa5e01949bf7e66d2af4d08cb8c1d6516af5e39595397f5e"}, + {file = "wrapt-1.15.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ba1711cda2d30634a7e452fc79eabcadaffedf241ff206db2ee93dd2c89a60e7"}, + {file = "wrapt-1.15.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:56374914b132c702aa9aa9959c550004b8847148f95e1b824772d453ac204a72"}, + {file = "wrapt-1.15.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a89ce3fd220ff144bd9d54da333ec0de0399b52c9ac3d2ce34b569cf1a5748fb"}, + {file = "wrapt-1.15.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3bbe623731d03b186b3d6b0d6f51865bf598587c38d6f7b0be2e27414f7f214e"}, + {file = "wrapt-1.15.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3abbe948c3cbde2689370a262a8d04e32ec2dd4f27103669a45c6929bcdbfe7c"}, + {file = "wrapt-1.15.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:b67b819628e3b748fd3c2192c15fb951f549d0f47c0449af0764d7647302fda3"}, + {file = "wrapt-1.15.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:7eebcdbe3677e58dd4c0e03b4f2cfa346ed4049687d839adad68cc38bb559c92"}, + {file = "wrapt-1.15.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:74934ebd71950e3db69960a7da29204f89624dde411afbfb3b4858c1409b1e98"}, + {file = "wrapt-1.15.0-cp311-cp311-win32.whl", hash = "sha256:bd84395aab8e4d36263cd1b9308cd504f6cf713b7d6d3ce25ea55670baec5416"}, + {file = "wrapt-1.15.0-cp311-cp311-win_amd64.whl", hash = "sha256:a487f72a25904e2b4bbc0817ce7a8de94363bd7e79890510174da9d901c38705"}, + {file = "wrapt-1.15.0-cp35-cp35m-manylinux1_i686.whl", hash = "sha256:4ff0d20f2e670800d3ed2b220d40984162089a6e2c9646fdb09b85e6f9a8fc29"}, + {file = "wrapt-1.15.0-cp35-cp35m-manylinux1_x86_64.whl", hash = "sha256:9ed6aa0726b9b60911f4aed8ec5b8dd7bf3491476015819f56473ffaef8959bd"}, + {file = "wrapt-1.15.0-cp35-cp35m-manylinux2010_i686.whl", hash = "sha256:896689fddba4f23ef7c718279e42f8834041a21342d95e56922e1c10c0cc7afb"}, + {file = "wrapt-1.15.0-cp35-cp35m-manylinux2010_x86_64.whl", hash = "sha256:75669d77bb2c071333417617a235324a1618dba66f82a750362eccbe5b61d248"}, + {file = "wrapt-1.15.0-cp35-cp35m-win32.whl", hash = "sha256:fbec11614dba0424ca72f4e8ba3c420dba07b4a7c206c8c8e4e73f2e98f4c559"}, + {file = "wrapt-1.15.0-cp35-cp35m-win_amd64.whl", hash = "sha256:fd69666217b62fa5d7c6aa88e507493a34dec4fa20c5bd925e4bc12fce586639"}, + {file = "wrapt-1.15.0-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:b0724f05c396b0a4c36a3226c31648385deb6a65d8992644c12a4963c70326ba"}, + {file = "wrapt-1.15.0-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bbeccb1aa40ab88cd29e6c7d8585582c99548f55f9b2581dfc5ba68c59a85752"}, + {file = "wrapt-1.15.0-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:38adf7198f8f154502883242f9fe7333ab05a5b02de7d83aa2d88ea621f13364"}, + {file = "wrapt-1.15.0-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:578383d740457fa790fdf85e6d346fda1416a40549fe8db08e5e9bd281c6a475"}, + {file = "wrapt-1.15.0-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:a4cbb9ff5795cd66f0066bdf5947f170f5d63a9274f99bdbca02fd973adcf2a8"}, + {file = "wrapt-1.15.0-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:af5bd9ccb188f6a5fdda9f1f09d9f4c86cc8a539bd48a0bfdc97723970348418"}, + {file = "wrapt-1.15.0-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:b56d5519e470d3f2fe4aa7585f0632b060d532d0696c5bdfb5e8319e1d0f69a2"}, + {file = "wrapt-1.15.0-cp36-cp36m-win32.whl", hash = "sha256:77d4c1b881076c3ba173484dfa53d3582c1c8ff1f914c6461ab70c8428b796c1"}, + {file = "wrapt-1.15.0-cp36-cp36m-win_amd64.whl", hash = "sha256:077ff0d1f9d9e4ce6476c1a924a3332452c1406e59d90a2cf24aeb29eeac9420"}, + {file = "wrapt-1.15.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:5c5aa28df055697d7c37d2099a7bc09f559d5053c3349b1ad0c39000e611d317"}, + {file = "wrapt-1.15.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3a8564f283394634a7a7054b7983e47dbf39c07712d7b177b37e03f2467a024e"}, + {file = "wrapt-1.15.0-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:780c82a41dc493b62fc5884fb1d3a3b81106642c5c5c78d6a0d4cbe96d62ba7e"}, + {file = "wrapt-1.15.0-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e169e957c33576f47e21864cf3fc9ff47c223a4ebca8960079b8bd36cb014fd0"}, + {file = "wrapt-1.15.0-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:b02f21c1e2074943312d03d243ac4388319f2456576b2c6023041c4d57cd7019"}, + {file = "wrapt-1.15.0-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:f2e69b3ed24544b0d3dbe2c5c0ba5153ce50dcebb576fdc4696d52aa22db6034"}, + {file = "wrapt-1.15.0-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:d787272ed958a05b2c86311d3a4135d3c2aeea4fc655705f074130aa57d71653"}, + {file = "wrapt-1.15.0-cp37-cp37m-win32.whl", hash = "sha256:02fce1852f755f44f95af51f69d22e45080102e9d00258053b79367d07af39c0"}, + {file = "wrapt-1.15.0-cp37-cp37m-win_amd64.whl", hash = "sha256:abd52a09d03adf9c763d706df707c343293d5d106aea53483e0ec8d9e310ad5e"}, + {file = "wrapt-1.15.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:cdb4f085756c96a3af04e6eca7f08b1345e94b53af8921b25c72f096e704e145"}, + {file = "wrapt-1.15.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:230ae493696a371f1dbffaad3dafbb742a4d27a0afd2b1aecebe52b740167e7f"}, + {file = "wrapt-1.15.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:63424c681923b9f3bfbc5e3205aafe790904053d42ddcc08542181a30a7a51bd"}, + {file = "wrapt-1.15.0-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d6bcbfc99f55655c3d93feb7ef3800bd5bbe963a755687cbf1f490a71fb7794b"}, + {file = "wrapt-1.15.0-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c99f4309f5145b93eca6e35ac1a988f0dc0a7ccf9ccdcd78d3c0adf57224e62f"}, + {file = "wrapt-1.15.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:b130fe77361d6771ecf5a219d8e0817d61b236b7d8b37cc045172e574ed219e6"}, + {file = "wrapt-1.15.0-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:96177eb5645b1c6985f5c11d03fc2dbda9ad24ec0f3a46dcce91445747e15094"}, + {file = "wrapt-1.15.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:d5fe3e099cf07d0fb5a1e23d399e5d4d1ca3e6dfcbe5c8570ccff3e9208274f7"}, + {file = "wrapt-1.15.0-cp38-cp38-win32.whl", hash = "sha256:abd8f36c99512755b8456047b7be10372fca271bf1467a1caa88db991e7c421b"}, + {file = "wrapt-1.15.0-cp38-cp38-win_amd64.whl", hash = "sha256:b06fa97478a5f478fb05e1980980a7cdf2712015493b44d0c87606c1513ed5b1"}, + {file = "wrapt-1.15.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:2e51de54d4fb8fb50d6ee8327f9828306a959ae394d3e01a1ba8b2f937747d86"}, + {file = "wrapt-1.15.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:0970ddb69bba00670e58955f8019bec4a42d1785db3faa043c33d81de2bf843c"}, + {file = "wrapt-1.15.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76407ab327158c510f44ded207e2f76b657303e17cb7a572ffe2f5a8a48aa04d"}, + {file = "wrapt-1.15.0-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:cd525e0e52a5ff16653a3fc9e3dd827981917d34996600bbc34c05d048ca35cc"}, + {file = "wrapt-1.15.0-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9d37ac69edc5614b90516807de32d08cb8e7b12260a285ee330955604ed9dd29"}, + {file = "wrapt-1.15.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:078e2a1a86544e644a68422f881c48b84fef6d18f8c7a957ffd3f2e0a74a0d4a"}, + {file = "wrapt-1.15.0-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:2cf56d0e237280baed46f0b5316661da892565ff58309d4d2ed7dba763d984b8"}, + {file = "wrapt-1.15.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:7dc0713bf81287a00516ef43137273b23ee414fe41a3c14be10dd95ed98a2df9"}, + {file = "wrapt-1.15.0-cp39-cp39-win32.whl", hash = "sha256:46ed616d5fb42f98630ed70c3529541408166c22cdfd4540b88d5f21006b0eff"}, + {file = "wrapt-1.15.0-cp39-cp39-win_amd64.whl", hash = "sha256:eef4d64c650f33347c1f9266fa5ae001440b232ad9b98f1f43dfe7a79435c0a6"}, + {file = "wrapt-1.15.0-py3-none-any.whl", hash = "sha256:64b1df0f83706b4ef4cfb4fb0e4c2669100fd7ecacfb59e091fad300d4e04640"}, + {file = "wrapt-1.15.0.tar.gz", hash = "sha256:d06730c6aed78cee4126234cf2d071e01b44b915e725a6cb439a879ec9754a3a"}, ] [[package]] @@ -2657,7 +2947,7 @@ testing = ["pytest", "pytest-cov", "setuptools"] name = "zerorpc" version = "0.6.3" description = "zerorpc is a flexible RPC based on zeromq." -category = "main" +category = "dev" optional = false python-versions = "*" files = [ @@ -2673,25 +2963,25 @@ pyzmq = ">=13.1.0" [[package]] name = "zipp" -version = "3.12.0" +version = "3.15.0" description = "Backport of pathlib-compatible object wrapper for zip files" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "zipp-3.12.0-py3-none-any.whl", hash = "sha256:9eb0a4c5feab9b08871db0d672745b53450d7f26992fd1e4653aa43345e97b86"}, - {file = "zipp-3.12.0.tar.gz", hash = "sha256:73efd63936398aac78fd92b6f4865190119d6c91b531532e798977ea8dd402eb"}, + {file = "zipp-3.15.0-py3-none-any.whl", hash = "sha256:48904fc76a60e542af151aded95726c1a5c34ed43ab4134b597665c86d7ad556"}, + {file = "zipp-3.15.0.tar.gz", hash = "sha256:112929ad649da941c23de50f356a2b5570c954b65150642bccdd66bf194d224b"}, ] [package.extras] docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] -testing = ["flake8 (<5)", "func-timeout", "jaraco.functools", "jaraco.itertools", "more-itertools", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=1.3)", "pytest-flake8", "pytest-mypy (>=0.9.1)"] +testing = ["big-O", "flake8 (<5)", "jaraco.functools", "jaraco.itertools", "more-itertools", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=1.3)", "pytest-flake8", "pytest-mypy (>=0.9.1)"] [[package]] name = "zope-event" version = "4.6" description = "Very basic event publishing system" -category = "main" +category = "dev" optional = false python-versions = "*" files = [ @@ -2710,7 +3000,7 @@ test = ["zope.testrunner"] name = "zope-interface" version = "6.0" description = "Interfaces for Python" -category = "main" +category = "dev" optional = false python-versions = ">=3.7" files = [ @@ -2757,4 +3047,4 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] [metadata] lock-version = "2.0" python-versions = "^3.8,<3.9" -content-hash = "ed443ff98b3f0dbbeef543e2fa74358d4b27a91cb03d31c8c4b3b67b073605af" +content-hash = "8a3fefcfb4865389275f2055f0a8220a89282d01902b9b773d0e0caa5f2e340a" diff --git a/pyproject.toml b/pyproject.toml index 79a099e..664d1fc 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -27,6 +27,7 @@ optional = true pylint = "^2.16.1" black = "^23.1.0" urdfenvs = "^0.5.1" +zerorpc = "^0.6.3" [build-system] requires = ["poetry-core"] From 03245be5d07be477d220d2c3a73560f0145e04e1 Mon Sep 17 00:00:00 2001 From: corradopezzato Date: Tue, 18 Apr 2023 14:17:56 +0200 Subject: [PATCH 18/26] update poetry toml --- poetry.lock | 182 ++++++++++++++++++++++++++++++++++++++++++++++++- pyproject.toml | 1 + 2 files changed, 181 insertions(+), 2 deletions(-) diff --git a/poetry.lock b/poetry.lock index 1192a73..b61a4a2 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry 1.4.2 and should not be changed by hand. +# This file is automatically @generated by Poetry and should not be changed by hand. [[package]] name = "antlr4-python3-runtime" @@ -530,6 +530,30 @@ files = [ {file = "future-0.18.3.tar.gz", hash = "sha256:34a17436ed1e96697a86f9de3d15a3b0be01d8bc8de9c1dffd59fb8234ed5307"}, ] +[[package]] +name = "fvcore" +version = "0.1.5.post20221221" +description = "Collection of common code shared among different research projects in FAIR computer vision team" +category = "main" +optional = false +python-versions = ">=3.6" +files = [ + {file = "fvcore-0.1.5.post20221221.tar.gz", hash = "sha256:f2fb0bb90572ae651c11c78e20493ed19b2240550a7e4bbb2d6de87bdd037860"}, +] + +[package.dependencies] +iopath = ">=0.1.7" +numpy = "*" +Pillow = "*" +pyyaml = ">=5.1" +tabulate = "*" +termcolor = ">=1.1" +tqdm = "*" +yacs = ">=0.1.6" + +[package.extras] +all = ["shapely"] + [[package]] name = "geomdl" version = "5.3.1" @@ -877,6 +901,25 @@ files = [ {file = "iniconfig-2.0.0.tar.gz", hash = "sha256:2d91e135bf72d31a410b17c16da610a82cb55f6b0477d1a902134b24a455b8b3"}, ] +[[package]] +name = "iopath" +version = "0.1.10" +description = "A library for providing I/O abstraction." +category = "main" +optional = false +python-versions = ">=3.6" +files = [ + {file = "iopath-0.1.10.tar.gz", hash = "sha256:3311c16a4d9137223e20f141655759933e1eda24f8bff166af834af3c645ef01"}, +] + +[package.dependencies] +portalocker = "*" +tqdm = "*" +typing_extensions = "*" + +[package.extras] +aws = ["boto3"] + [[package]] name = "isaacgym" version = "1.0rc4" @@ -1895,6 +1938,26 @@ files = [ dev = ["pre-commit", "tox"] testing = ["pytest", "pytest-benchmark"] +[[package]] +name = "portalocker" +version = "2.7.0" +description = "Wraps the portalocker recipe for easy usage" +category = "main" +optional = false +python-versions = ">=3.5" +files = [ + {file = "portalocker-2.7.0-py2.py3-none-any.whl", hash = "sha256:a07c5b4f3985c3cf4798369631fb7011adb498e2a46d8440efc75a8f29a0f983"}, + {file = "portalocker-2.7.0.tar.gz", hash = "sha256:032e81d534a88ec1736d03f780ba073f047a06c478b06e2937486f334e955c51"}, +] + +[package.dependencies] +pywin32 = {version = ">=226", markers = "platform_system == \"Windows\""} + +[package.extras] +docs = ["sphinx (>=1.7.1)"] +redis = ["redis"] +tests = ["pytest (>=5.4.1)", "pytest-cov (>=2.8.1)", "pytest-mypy (>=0.8.0)", "pytest-timeout (>=2.1.0)", "redis", "sphinx (>=6.0.0)"] + [[package]] name = "pybullet" version = "3.2.5" @@ -2065,6 +2128,54 @@ files = [ [package.dependencies] six = ">=1.5" +[[package]] +name = "pytorch3d" +version = "0.3.0" +description = "PyTorch3D is FAIR's library of reusable components for deep Learning with 3D data." +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "pytorch3d-0.3.0-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:eb801ffe322330e534d5bdc5499253d6bf9afefb6a3b7c4dd0783eb372526555"}, + {file = "pytorch3d-0.3.0-cp36-cp36m-manylinux1_x86_64.whl", hash = "sha256:99e4fcf9fca52e1df08fccb83ed65650fb4b2c453725dcda929b1770b5e4e08e"}, + {file = "pytorch3d-0.3.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:41fa5d735695389180bd247cdd48abb9bc641cc00b570551001c5de2916c5f28"}, + {file = "pytorch3d-0.3.0-cp37-cp37m-manylinux1_x86_64.whl", hash = "sha256:67405168ed740f834d558afb6ef36123d55896ac63ba08b230abd78879d995dd"}, + {file = "pytorch3d-0.3.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:86e87723c4c697a2bd524966a563adbd4d35b301a0a422727b4e2eca5de649f2"}, + {file = "pytorch3d-0.3.0-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:e2d057289e0c83a66600ff166dd0e7209b414dbeea514b48b1c383cfbecf35e1"}, +] + +[package.dependencies] +fvcore = "*" +torchvision = ">=0.4" + +[package.extras] +all = ["imageio", "ipywidgets", "matplotlib", "tqdm (>4.29.0)"] +dev = ["black (==19.3b0)", "flake8", "isort"] + +[[package]] +name = "pywin32" +version = "306" +description = "Python for Window Extensions" +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "pywin32-306-cp310-cp310-win32.whl", hash = "sha256:06d3420a5155ba65f0b72f2699b5bacf3109f36acbe8923765c22938a69dfc8d"}, + {file = "pywin32-306-cp310-cp310-win_amd64.whl", hash = "sha256:84f4471dbca1887ea3803d8848a1616429ac94a4a8d05f4bc9c5dcfd42ca99c8"}, + {file = "pywin32-306-cp311-cp311-win32.whl", hash = "sha256:e65028133d15b64d2ed8f06dd9fbc268352478d4f9289e69c190ecd6818b6407"}, + {file = "pywin32-306-cp311-cp311-win_amd64.whl", hash = "sha256:a7639f51c184c0272e93f244eb24dafca9b1855707d94c192d4a0b4c01e1100e"}, + {file = "pywin32-306-cp311-cp311-win_arm64.whl", hash = "sha256:70dba0c913d19f942a2db25217d9a1b726c278f483a919f1abfed79c9cf64d3a"}, + {file = "pywin32-306-cp312-cp312-win32.whl", hash = "sha256:383229d515657f4e3ed1343da8be101000562bf514591ff383ae940cad65458b"}, + {file = "pywin32-306-cp312-cp312-win_amd64.whl", hash = "sha256:37257794c1ad39ee9be652da0462dc2e394c8159dfd913a8a4e8eb6fd346da0e"}, + {file = "pywin32-306-cp312-cp312-win_arm64.whl", hash = "sha256:5821ec52f6d321aa59e2db7e0a35b997de60c201943557d108af9d4ae1ec7040"}, + {file = "pywin32-306-cp37-cp37m-win32.whl", hash = "sha256:1c73ea9a0d2283d889001998059f5eaaba3b6238f767c9cf2833b13e6a685f65"}, + {file = "pywin32-306-cp37-cp37m-win_amd64.whl", hash = "sha256:72c5f621542d7bdd4fdb716227be0dd3f8565c11b280be6315b06ace35487d36"}, + {file = "pywin32-306-cp38-cp38-win32.whl", hash = "sha256:e4c092e2589b5cf0d365849e73e02c391c1349958c5ac3e9d5ccb9a28e017b3a"}, + {file = "pywin32-306-cp38-cp38-win_amd64.whl", hash = "sha256:e8ac1ae3601bee6ca9f7cb4b5363bf1c0badb935ef243c4733ff9a393b1690c0"}, + {file = "pywin32-306-cp39-cp39-win32.whl", hash = "sha256:e25fd5b485b55ac9c057f67d94bc203f3f6595078d1fb3b458c9c28b7153a802"}, + {file = "pywin32-306-cp39-cp39-win_amd64.whl", hash = "sha256:39b61c15272833b5c329a2989999dcae836b1eed650252ab1b7bfbe1d59f30f4"}, +] + [[package]] name = "pyyaml" version = "6.0" @@ -2457,6 +2568,36 @@ files = [ [package.dependencies] mpmath = ">=0.19" +[[package]] +name = "tabulate" +version = "0.9.0" +description = "Pretty-print tabular data" +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "tabulate-0.9.0-py3-none-any.whl", hash = "sha256:024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f"}, + {file = "tabulate-0.9.0.tar.gz", hash = "sha256:0095b12bf5966de529c0feb1fa08671671b3368eec77d7ef7ab114be2c068b3c"}, +] + +[package.extras] +widechars = ["wcwidth"] + +[[package]] +name = "termcolor" +version = "2.2.0" +description = "ANSI color formatting for output in terminal" +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "termcolor-2.2.0-py3-none-any.whl", hash = "sha256:91ddd848e7251200eac969846cbae2dacd7d71c2871e92733289e7e3666f48e7"}, + {file = "termcolor-2.2.0.tar.gz", hash = "sha256:dfc8ac3f350788f23b2947b3e6cfa5a53b630b612e6cd8965a015a776020b99a"}, +] + +[package.extras] +tests = ["pytest", "pytest-cov"] + [[package]] name = "tomli" version = "2.0.1" @@ -2576,6 +2717,27 @@ torch = "2.0.0" [package.extras] scipy = ["scipy"] +[[package]] +name = "tqdm" +version = "4.65.0" +description = "Fast, Extensible Progress Meter" +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "tqdm-4.65.0-py3-none-any.whl", hash = "sha256:c4f53a17fe37e132815abceec022631be8ffe1b9381c2e6e30aa70edc99e9671"}, + {file = "tqdm-4.65.0.tar.gz", hash = "sha256:1871fb68a86b8fb3b59ca4cdd3dcccbc7e6d613eeed31f4c332531977b89beb5"}, +] + +[package.dependencies] +colorama = {version = "*", markers = "platform_system == \"Windows\""} + +[package.extras] +dev = ["py-make (>=0.1.0)", "twine", "wheel"] +notebook = ["ipywidgets (>=6)"] +slack = ["slack-sdk"] +telegram = ["requests"] + [[package]] name = "trimesh" version = "3.21.5" @@ -2922,6 +3084,22 @@ files = [ {file = "xxhash-3.2.0.tar.gz", hash = "sha256:1afd47af8955c5db730f630ad53ae798cf7fae0acb64cebb3cf94d35c47dd088"}, ] +[[package]] +name = "yacs" +version = "0.1.8" +description = "Yet Another Configuration System" +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "yacs-0.1.8-py2-none-any.whl", hash = "sha256:d43d1854c1ffc4634c5b349d1c1120f86f05c3a294c9d141134f282961ab5d94"}, + {file = "yacs-0.1.8-py3-none-any.whl", hash = "sha256:99f893e30497a4b66842821bac316386f7bd5c4f47ad35c9073ef089aa33af32"}, + {file = "yacs-0.1.8.tar.gz", hash = "sha256:efc4c732942b3103bea904ee89af98bcd27d01f0ac12d8d4d369f1e7a2914384"}, +] + +[package.dependencies] +PyYAML = "*" + [[package]] name = "yourdfpy" version = "0.0.52" @@ -3047,4 +3225,4 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] [metadata] lock-version = "2.0" python-versions = "^3.8,<3.9" -content-hash = "8a3fefcfb4865389275f2055f0a8220a89282d01902b9b773d0e0caa5f2e340a" +content-hash = "483dd375f067f04529d38190deef979634b1814c9703937bae06b5e2544a11e4" diff --git a/pyproject.toml b/pyproject.toml index 664d1fc..3a7b583 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -19,6 +19,7 @@ ghalton = "^0.6.2" mpscenes = "^0.3.1" fabrics = "^0.6.2" yourdfpy = "^0.0.52" +pytorch3d = "^0.3.0" [tool.poetry.group.dev] optional = true From a2732c2c4dfa4cdfbc58a6d672a3f2cc5ffdf291 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Wed, 19 Apr 2023 10:55:22 +0200 Subject: [PATCH 19/26] Fixes bug where the robot_positions were zero tensors --- mppiisaac/planner/isaacgym_wrapper.py | 26 ++++++++++++++++++-------- 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 1c0ea51..35eb714 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -193,16 +193,10 @@ def start_sim(self): self.ee_positions_buffer = [] # helpfull slices - #self.robot_positions = self.root_state[:, 0, 0:3] # [x, y, z] + self.robot_indices = torch.tensor([i for i, a in enumerate(self.env_cfg) if a.type == "robot"], device="cuda:0") - indices = torch.tensor([i for i, a in enumerate(self.env_cfg) if a.type == "robot"], device="cuda:0") - self.robot_root_states = torch.index_select(self.root_state, 1, indices) - self.robot_positions = self.robot_root_states[:, :, 0:3] - self.robot_velocities = self.robot_root_states[:, :, 7:10] + self.obstacle_indices = torch.tensor([i for i, a in enumerate(self.env_cfg) if a.type in ["sphere", "box"]], device="cuda:0") - indices = torch.tensor([i for i, a in enumerate(self.env_cfg) if a.type in ["sphere", "box"]], device="cuda:0") - self.obstacle_root_states = torch.index_select(self.root_state, 1, indices) - self.obstacle_positions = self.obstacle_root_states[:, :, 0:3] # [x, y, z] if self.ee_link_present: self.ee_positions = self.rigid_body_state[ :, self.robot_rigid_body_ee_idx, 0:3 @@ -213,6 +207,22 @@ def start_sim(self): self.gym.refresh_rigid_body_state_tensor(self.sim) self.gym.refresh_net_contact_force_tensor(self.sim) + @property + def robot_positions(self): + return torch.index_select(self.root_state, 1, self.robot_indices)[:, :, 0:3] + + @property + def robot_velocities(self): + return torch.index_select(self.root_state, 1, self.robot_indices)[:, :, 7:10] + + @property + def obstacle_positions(self): + return torch.index_select(self.root_state, 1, self.obstacle_indices)[:, :, 0:3] + + @property + def robot_velocities(self): + return torch.index_select(self.root_state, 1, self.obstacle_indices)[:, :, 7:10] + def stop_sim(self): if self.viewer: self.gym.destroy_viewer(self.viewer) From bab45b140b605f9e9c7e787d15ce15ffc9de6605 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Wed, 19 Apr 2023 11:40:14 +0200 Subject: [PATCH 20/26] fix boxer example --- conf/mppi/boxer.yaml | 6 +++--- examples/boxer_robot.py | 4 +++- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/conf/mppi/boxer.yaml b/conf/mppi/boxer.yaml index 88cc07b..1f37e1e 100644 --- a/conf/mppi/boxer.yaml +++ b/conf/mppi/boxer.yaml @@ -3,13 +3,13 @@ defaults: mppi_mode: "halton-spline" # halton-spline, simple sampling_method: "halton" # halton, random -num_samples: 100 +num_samples: 400 horizon: 20 # At least 12 for Halton Sampling device: "cuda:0" -lambda_: 0.01 +lambda_: 0.05 u_min: [-0.6, -1.3] u_max: [0.6, 1.3] -noise_sigma: [[1., 0.], [0., 1.5]] +noise_sigma: [[10., 0.], [0., 15.]] update_cov: False rollout_var_discount: 0.95 sample_null_action: True diff --git a/examples/boxer_robot.py b/examples/boxer_robot.py index 681336b..ed3529c 100644 --- a/examples/boxer_robot.py +++ b/examples/boxer_robot.py @@ -105,8 +105,10 @@ def run_boxer_robot(cfg: ExampleConfig): #Todo fix joint with zero friction ob_robot = ob["robot_0"] + pos = ob_robot["joint_state"]["position"] + pos[2] = pos[2] - 3.14/2 action = planner.compute_action( - q=ob_robot["joint_state"]["position"], + q=pos, qdot=ob_robot["joint_state"]["velocity"], ) ( From 5d60fed0a6d49e27899160cf6cd95fccb8f5d49a Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Wed, 19 Apr 2023 14:08:39 +0200 Subject: [PATCH 21/26] change collision group from -1 to an increment of the current env, because -1 collides with everything --- mppiisaac/planner/isaacgym_wrapper.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 35eb714..1977c66 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -243,7 +243,7 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: asset=asset, pose=pose, name=actor.name, - group=env_idx if actor.collision else -1, + group=env_idx if actor.collision else env_idx+self.num_envs, ) self.gym.set_rigid_body_color( env, handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, gymapi.Vec3(*actor.color) From 5b079bb16171c66126de32de6879ef65267e6559 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Wed, 19 Apr 2023 14:22:52 +0200 Subject: [PATCH 22/26] fix ik wheel order, and remove rotation from boxer example. This is only necessary when using the boxer.urdf of a later version of urdfenvs (0.7.3) --- examples/boxer_robot.py | 3 +-- mppiisaac/planner/isaacgym_wrapper.py | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/examples/boxer_robot.py b/examples/boxer_robot.py index ed3529c..fea6647 100644 --- a/examples/boxer_robot.py +++ b/examples/boxer_robot.py @@ -41,7 +41,7 @@ def initalize_environment(cfg) -> UrdfEnv: robots = [ BoxerRobot(mode="vel"), ] - env: UrdfEnv = gym.make("urdf-env-v0", dt=0.02, robots=robots, render=cfg.render) + env: UrdfEnv = gym.make("urdf-env-v0", dt=cfg.isaacgym.dt, robots=robots, render=cfg.render) # Set the initial position and velocity of the boxer robot env.reset() goal_dict = { @@ -106,7 +106,6 @@ def run_boxer_robot(cfg: ExampleConfig): ob_robot = ob["robot_0"] pos = ob_robot["joint_state"]["position"] - pos[2] = pos[2] - 3.14/2 action = planner.compute_action( q=pos, qdot=ob_robot["joint_state"]["velocity"], diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 35eb714..2234a00 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -311,8 +311,8 @@ def _ik(self, actor, u): # Diff drive fk u_ik = u.clone() - u_ik[:, 1] = (u[:, 0] / r) - ((L * u[:, 1]) / (2 * r)) - u_ik[:, 0] = (u[:, 0] / r) + ((L * u[:, 1]) / (2 * r)) + u_ik[:, 0] = (u[:, 0] / r) - ((L * u[:, 1]) / (2 * r)) + u_ik[:, 1] = (u[:, 0] / r) + ((L * u[:, 1]) / (2 * r)) if wheel_sets > 1: u_ik = u_ik.repeat(1, wheel_sets) From 11f213b0f4e606279d77cc9e5c52626e2e171b0a Mon Sep 17 00:00:00 2001 From: Max Spahn Date: Fri, 21 Apr 2023 09:34:41 +0200 Subject: [PATCH 23/26] Adds config for jackal. --- conf/config_jackal_robot.yaml | 4 ++-- conf/mppi/jackal.yaml | 4 ++-- examples/jackal_robot.py | 26 ++++++++++++++++++++++---- 3 files changed, 26 insertions(+), 8 deletions(-) diff --git a/conf/config_jackal_robot.yaml b/conf/config_jackal_robot.yaml index 36c61c6..5ad7b19 100644 --- a/conf/config_jackal_robot.yaml +++ b/conf/config_jackal_robot.yaml @@ -10,6 +10,6 @@ fix_base: false flip_visual: false nx: 4 differential_drive: true -wheel_radius: 0.14 -wheel_base: 0.400 +wheel_radius: 0.098 +wheel_base: 0.45559 wheel_count: 4 diff --git a/conf/mppi/jackal.yaml b/conf/mppi/jackal.yaml index c94d5de..53e8e89 100644 --- a/conf/mppi/jackal.yaml +++ b/conf/mppi/jackal.yaml @@ -7,8 +7,8 @@ num_samples: 100 horizon: 20 # At least 12 for Halton Sampling device: "cuda:0" lambda_: 0.01 -u_min: -1.5 -u_max: 1.5 +u_min: [-0.6, -1.5] +u_max: [0.6, 1.5] noise_sigma: [[1., 0.], [0., 1.]] update_cov: False rollout_var_discount: 0.95 diff --git a/examples/jackal_robot.py b/examples/jackal_robot.py index 42b45df..5334761 100644 --- a/examples/jackal_robot.py +++ b/examples/jackal_robot.py @@ -1,6 +1,6 @@ import gym import numpy as np -from urdfenvs.robots.jackal import JackalRobot +from urdfenvs.robots.generic_urdf import GenericDiffDriveRobot from urdfenvs.urdf_common.urdf_env import UrdfEnv from mppiisaac.planner.mppi_isaac import MPPIisaacPlanner import hydra @@ -11,7 +11,10 @@ from mppiisaac.utils.config_store import ExampleConfig -# MPPI to navigate a simple robot to a goal position +urdf_file = ( + os.path.dirname(os.path.abspath(__file__)) + + "/../assets/urdf/jackal/jackal.urdf" +) class Objective(object): def __init__(self, cfg, device): @@ -39,9 +42,24 @@ def initalize_environment(cfg) -> UrdfEnv: """ # urdf_file = os.path.dirname(os.path.abspath(__file__)) + "/../assets/urdf/" + cfg.urdf_file robots = [ - JackalRobot(mode="vel"), + GenericDiffDriveRobot( + urdf=urdf_file, + mode="vel", + actuated_wheels=[ + "rear_right_wheel", + "rear_left_wheel", + "front_right_wheel", + "front_left_wheel", + ], + castor_wheels=[], + wheel_radius = cfg.wheel_radius, + wheel_distance = cfg.wheel_base, + ), ] - env: UrdfEnv = gym.make("urdf-env-v0", dt=0.02, robots=robots, render=cfg.render) + env = gym.make( + "urdf-env-v0", + dt=0.01, robots=robots, render=cfg.render + ) # Set the initial position and velocity of the jackal robot env.reset() goal_dict = { From 57c3424bf2ce636792ee63dd157f01fc3463fdce Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Fri, 21 Apr 2023 11:30:13 +0200 Subject: [PATCH 24/26] Adds actor asset scale randomization, with gaussian distribution. --- mppiisaac/planner/isaacgym_wrapper.py | 81 +++++++++++++++++---------- 1 file changed, 50 insertions(+), 31 deletions(-) diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index 8ce6adf..e134c69 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -21,6 +21,8 @@ class IsaacGymConfig(object): viewer: bool = False num_obstacles: int = 10 spacing: float = 6.0 + randomize_envs: bool = False + randomization_sigma: float = 0.1 def parse_isaacgym_config(cfg: IsaacGymConfig) -> gymapi.SimParams: @@ -121,37 +123,8 @@ def start_sim(self): # Load / create assets for all actors in the envs self.env_actor_assets = [] for actor_cfg in self.env_cfg: - asset_options = gymapi.AssetOptions() - asset_options.fix_base_link = actor_cfg.fixed - if actor_cfg.type == "robot": - asset_file = "urdf/" + actor_cfg.urdf_file - asset_options.flip_visual_attachments = actor_cfg.flip_visual - asset_options.disable_gravity = not actor_cfg.gravity - actor_asset = self.gym.load_asset( - sim=self.sim, - rootpath=f"{file_path}/../../assets", - filename=asset_file, - options=asset_options, - ) - elif actor_cfg.type == "box": - actor_asset = self.gym.create_box( - sim=self.sim, - width=actor_cfg.size[0], - height=actor_cfg.size[1], - depth=actor_cfg.size[2], - options=asset_options, - ) - elif actor_cfg.type == "sphere": - actor_asset = self.gym.create_sphere( - sim=self.sim, - radius=actor_cfg.size[0], - options=asset_options, - ) - else: - raise NotImplementedError( - f"actor asset of type {actor_cfg.type} is not yet implemented!" - ) - self.env_actor_assets.append(actor_asset) + asset = self.load_asset(actor_cfg) + self.env_actor_assets.append(asset) # Create envs and fill with assets self.envs = [] @@ -234,7 +207,53 @@ def add_to_envs(self, additions): self.stop_sim() self.start_sim() + def load_asset(self, actor_cfg): + asset_options = gymapi.AssetOptions() + asset_options.fix_base_link = actor_cfg.fixed + if actor_cfg.type == "robot": + asset_file = "urdf/" + actor_cfg.urdf_file + asset_options.flip_visual_attachments = actor_cfg.flip_visual + asset_options.disable_gravity = not actor_cfg.gravity + actor_asset = self.gym.load_asset( + sim=self.sim, + rootpath=f"{file_path}/../../assets", + filename=asset_file, + options=asset_options, + ) + elif actor_cfg.type == "box": + noise = ( + np.random.normal(loc=0, scale=self.cfg.randomization_sigma, size=3) + * self.cfg.randomize_envs + ) + actor_asset = self.gym.create_box( + sim=self.sim, + width=actor_cfg.size[0] + noise[0], + height=actor_cfg.size[1] + noise[1], + depth=actor_cfg.size[2] + noise[2], + options=asset_options, + ) + elif actor_cfg.type == "sphere": + noise = ( + np.random.normal(loc=0, scale=self.cfg.randomization_sigma, size=1) + * self.cfg.randomize_envs + ) + print(noise) + actor_asset = self.gym.create_sphere( + sim=self.sim, + radius=actor_cfg.size[0] + noise[0], + options=asset_options, + ) + else: + raise NotImplementedError( + f"actor asset of type {actor_cfg.type} is not yet implemented!" + ) + + return actor_asset + def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: + if self.cfg.randomize_envs and actor.type != 'robot': + asset = self.load_asset(actor) + pose = gymapi.Transform() pose.p = gymapi.Vec3(*actor.init_pos) pose.r = gymapi.Quat(*actor.init_ori) From 1090390c47a7d7a4c5577ea6fb3f9fc63e95036c Mon Sep 17 00:00:00 2001 From: cpezzato Date: Fri, 21 Apr 2023 15:03:21 +0200 Subject: [PATCH 25/26] Adds mass and friction randomization, only for obj_to_push --- conf/config_panda_push.yaml | 2 +- conf/isaacgym/push.yaml | 6 ++++++ examples/panda_push_server.py | 2 +- mppiisaac/planner/isaacgym_wrapper.py | 19 ++++++++++++------- 4 files changed, 20 insertions(+), 9 deletions(-) create mode 100644 conf/isaacgym/push.yaml diff --git a/conf/config_panda_push.yaml b/conf/config_panda_push.yaml index 91d369b..08480d3 100644 --- a/conf/config_panda_push.yaml +++ b/conf/config_panda_push.yaml @@ -1,6 +1,6 @@ defaults: - mppi: panda_push - - isaacgym: normal + - isaacgym: push goal: [0.5, 0.4, 0.7] render: true diff --git a/conf/isaacgym/push.yaml b/conf/isaacgym/push.yaml new file mode 100644 index 0000000..77d3d49 --- /dev/null +++ b/conf/isaacgym/push.yaml @@ -0,0 +1,6 @@ +defaults: + - base_isaacgym + +dt: 0.04 +randomize_envs: True +randomization_sigma: 0.005 \ No newline at end of file diff --git a/examples/panda_push_server.py b/examples/panda_push_server.py index 564868d..9cf8041 100644 --- a/examples/panda_push_server.py +++ b/examples/panda_push_server.py @@ -60,7 +60,7 @@ def run_panda_robot(cfg: ExampleConfig): }, { "type": "box", - "name": "block", + "name": "obj_to_push", "size": [0.105, 0.063, 0.063], "init_pos": [0.55, 0.2, 0.3], "mass": 0.250, diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index e134c69..cde1481 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -210,6 +210,7 @@ def add_to_envs(self, additions): def load_asset(self, actor_cfg): asset_options = gymapi.AssetOptions() asset_options.fix_base_link = actor_cfg.fixed + if actor_cfg.type == "robot": asset_file = "urdf/" + actor_cfg.urdf_file asset_options.flip_visual_attachments = actor_cfg.flip_visual @@ -223,19 +224,19 @@ def load_asset(self, actor_cfg): elif actor_cfg.type == "box": noise = ( np.random.normal(loc=0, scale=self.cfg.randomization_sigma, size=3) - * self.cfg.randomize_envs + * self.cfg.randomize_envs * (actor_cfg.name == "block_to_push") ) actor_asset = self.gym.create_box( sim=self.sim, width=actor_cfg.size[0] + noise[0], height=actor_cfg.size[1] + noise[1], - depth=actor_cfg.size[2] + noise[2], + depth=actor_cfg.size[2], # + noise[2], options=asset_options, ) elif actor_cfg.type == "sphere": noise = ( np.random.normal(loc=0, scale=self.cfg.randomization_sigma, size=1) - * self.cfg.randomize_envs + * self.cfg.randomize_envs * (actor_cfg.name == "block_to_push") ) print(noise) actor_asset = self.gym.create_sphere( @@ -264,11 +265,15 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: name=actor.name, group=env_idx if actor.collision else env_idx+self.num_envs, ) + + if self.cfg.randomize_envs and actor.name == 'obj_to_push': + actor.color = np.random.rand(3) + self.gym.set_rigid_body_color( env, handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, gymapi.Vec3(*actor.color) ) props = self.gym.get_actor_rigid_body_properties(env, handle) - props[0].mass = actor.mass + props[0].mass = actor.mass + (actor.name == "block_to_push") * np.random.uniform(-0.3*actor.mass, 0.3*actor.mass) self.gym.set_actor_rigid_body_properties(env, handle, props) body_names = self.gym.get_actor_rigid_body_names(env, handle) @@ -282,9 +287,9 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: props = self.gym.get_actor_rigid_shape_properties(env, handle) for i, p in enumerate(props): - p.friction = actor.friction - p.torsion_friction = actor.friction - p.rolling_friction = actor.friction + p.friction = actor.friction + (actor.name == "block_to_push") * np.random.uniform(-0.3*actor.friction, 0.3*actor.friction) + p.torsion_friction = np.random.uniform(0.001, 0.01) + p.rolling_friction = actor.friction + (actor.name == "block_to_push") * np.random.uniform(-0.3*actor.friction, 0.3*actor.friction) if i in caster_shapes: p.friction = 0 From 043b44bd298df88800a44654cfa8636de0abf9f8 Mon Sep 17 00:00:00 2001 From: Chadi Salmi Date: Fri, 21 Apr 2023 15:53:01 +0200 Subject: [PATCH 26/26] Add noise params per actor instead of entire sim. --- conf/isaacgym/push.yaml | 2 -- examples/panda_push_server.py | 5 +++- mppiisaac/planner/isaacgym_wrapper.py | 34 +++++++++++++++++---------- 3 files changed, 25 insertions(+), 16 deletions(-) diff --git a/conf/isaacgym/push.yaml b/conf/isaacgym/push.yaml index 77d3d49..e5227e9 100644 --- a/conf/isaacgym/push.yaml +++ b/conf/isaacgym/push.yaml @@ -2,5 +2,3 @@ defaults: - base_isaacgym dt: 0.04 -randomize_envs: True -randomization_sigma: 0.005 \ No newline at end of file diff --git a/examples/panda_push_server.py b/examples/panda_push_server.py index 9cf8041..6cca143 100644 --- a/examples/panda_push_server.py +++ b/examples/panda_push_server.py @@ -67,7 +67,10 @@ def run_panda_robot(cfg: ExampleConfig): "fixed": False, "handle": None, "color": [0.2, 0.2, 1.0], - "friction": 0.2 + "friction": 0.2, + "noise_sigma_size": [0.005, 0.005, 0.0], + "noise_percentage_friction": 0.3, + "noise_percentage_mass": 0.3, } ] diff --git a/mppiisaac/planner/isaacgym_wrapper.py b/mppiisaac/planner/isaacgym_wrapper.py index cde1481..32c66b5 100644 --- a/mppiisaac/planner/isaacgym_wrapper.py +++ b/mppiisaac/planner/isaacgym_wrapper.py @@ -21,8 +21,6 @@ class IsaacGymConfig(object): viewer: bool = False num_obstacles: int = 10 spacing: float = 6.0 - randomize_envs: bool = False - randomization_sigma: float = 0.1 def parse_isaacgym_config(cfg: IsaacGymConfig) -> gymapi.SimParams: @@ -77,6 +75,9 @@ class ActorWrapper: left_wheel_joints: Optional[List[int]] = None right_wheel_joints: Optional[List[int]] = None caster_links: Optional[List[str]] = None + noise_sigma_size: Optional[List[float]] = None + noise_percentage_mass: float = 0.0 + noise_percentage_friction: float = 0.0 class IsaacGymWrapper: @@ -222,23 +223,28 @@ def load_asset(self, actor_cfg): options=asset_options, ) elif actor_cfg.type == "box": + if actor_cfg.noise_sigma_size is not None: + noise_sigma = np.array(actor_cfg.noise_sigma_size) + else: + noise_sigma = np.zeros((3, )) noise = ( - np.random.normal(loc=0, scale=self.cfg.randomization_sigma, size=3) - * self.cfg.randomize_envs * (actor_cfg.name == "block_to_push") + np.random.normal(loc=0, scale=noise_sigma, size=3) ) actor_asset = self.gym.create_box( sim=self.sim, width=actor_cfg.size[0] + noise[0], height=actor_cfg.size[1] + noise[1], - depth=actor_cfg.size[2], # + noise[2], + depth=actor_cfg.size[2] + noise[2], options=asset_options, ) elif actor_cfg.type == "sphere": + if actor_cfg.noise_sigma_size is not None: + noise_sigma = np.array(actor_cfg.noise_sigma_size) + else: + noise_sigma = np.zeros((1, )) noise = ( - np.random.normal(loc=0, scale=self.cfg.randomization_sigma, size=1) - * self.cfg.randomize_envs * (actor_cfg.name == "block_to_push") + np.random.normal(loc=0, scale=noise_sigma, size=1) ) - print(noise) actor_asset = self.gym.create_sphere( sim=self.sim, radius=actor_cfg.size[0] + noise[0], @@ -252,7 +258,7 @@ def load_asset(self, actor_cfg): return actor_asset def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: - if self.cfg.randomize_envs and actor.type != 'robot': + if actor.noise_sigma_size is not None: asset = self.load_asset(actor) pose = gymapi.Transform() @@ -266,14 +272,15 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: group=env_idx if actor.collision else env_idx+self.num_envs, ) - if self.cfg.randomize_envs and actor.name == 'obj_to_push': + if actor.noise_sigma_size: actor.color = np.random.rand(3) self.gym.set_rigid_body_color( env, handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, gymapi.Vec3(*actor.color) ) props = self.gym.get_actor_rigid_body_properties(env, handle) - props[0].mass = actor.mass + (actor.name == "block_to_push") * np.random.uniform(-0.3*actor.mass, 0.3*actor.mass) + actor_mass_noise = np.random.uniform(-actor.noise_percentage_mass*actor.mass, actor.noise_percentage_mass*actor.mass) + props[0].mass = actor.mass + actor_mass_noise self.gym.set_actor_rigid_body_properties(env, handle, props) body_names = self.gym.get_actor_rigid_body_names(env, handle) @@ -287,9 +294,10 @@ def create_actor(self, env, env_idx, asset, actor: ActorWrapper) -> int: props = self.gym.get_actor_rigid_shape_properties(env, handle) for i, p in enumerate(props): - p.friction = actor.friction + (actor.name == "block_to_push") * np.random.uniform(-0.3*actor.friction, 0.3*actor.friction) + actor_friction_noise = np.random.uniform(-actor.noise_percentage_friction*actor.friction, actor.noise_percentage_friction*actor.friction) + p.friction = actor.friction + actor_friction_noise p.torsion_friction = np.random.uniform(0.001, 0.01) - p.rolling_friction = actor.friction + (actor.name == "block_to_push") * np.random.uniform(-0.3*actor.friction, 0.3*actor.friction) + p.rolling_friction = actor.friction + actor_friction_noise if i in caster_shapes: p.friction = 0