diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json new file mode 100644 index 0000000..fb60410 --- /dev/null +++ b/.devcontainer/devcontainer.json @@ -0,0 +1,47 @@ +// For format details, see https://aka.ms/devcontainer.json. For config options, see the +// README at: https://github.com/devcontainers/templates/tree/main/src/docker-existing-docker-compose +{ + "name": "cart-pole", + + // Update the 'dockerComposeFile' list if you have more compose files or use different names. + // The .devcontainer/docker-compose.yml file contains any overrides you need/want to make. + "dockerComposeFile": ["../docker-compose.yaml"], + + // The 'service' property is the name of the service for the container that VS Code should + // use. Update this value and .devcontainer/docker-compose.yml to the real service name. + "service": "cartpole", + + // The optional 'workspaceFolder' property is the path VS Code should open by default when + // connected. This is typically a file mount in .devcontainer/docker-compose.yml + "workspaceFolder": "/cartpole" + + // Features to add to the dev container. More info: https://containers.dev/features. + // "features": {}, + + // Use 'forwardPorts' to make a list of ports inside the container available locally. + // "forwardPorts": [], + + // Uncomment the next line if you want start specific services in your Docker Compose config. + // "runServices": [], + + // Uncomment the next line if you want to keep your containers running after VS Code shuts down. + // "shutdownAction": "none", + + // Uncomment the next line to run commands after the container is created. + // "postCreateCommand": "cat /etc/os-release", + + // Configure tool-specific properties. + "customizations": { + "vscode": { + "extensions": [ + "ms-python.python", + "ms-python.vscode-pylance", + "charliermarsh.ruff", + "yzhang.markdown-all-in-one" + ] + } + } + + // Uncomment to connect as an existing user other than the container default. More info: https://aka.ms/dev-containers-non-root. + // "remoteUser": "cartpole" +} diff --git a/.devcontainer/docker-compose.yml b/.devcontainer/docker-compose.yml new file mode 100644 index 0000000..b20219a --- /dev/null +++ b/.devcontainer/docker-compose.yml @@ -0,0 +1 @@ +version: '3.9' diff --git a/.github/workflows/alt_ci.yml b/.github/workflows/alt_ci.yml deleted file mode 100644 index 2893eb1..0000000 --- a/.github/workflows/alt_ci.yml +++ /dev/null @@ -1,33 +0,0 @@ -name: Alt-CI - -on: - push: - branches: [ master ] - pull_request: - branches: [ master ] - -jobs: - test: - runs-on: ubuntu-latest - steps: - - name: Checkout - uses: actions/checkout@v2 - - name: Install Python - uses: actions/setup-python@v2 - with: { python-version: 3.9 } - - name: Cache python & requirements - uses: actions/cache@v2 - with: - path: ${{ env.pythonLocation }} - key: python|${{ env.pythonLocation }}|${{ hashFiles('requirements.txt') }} - - name: Cache pre-commit hooks - uses: actions/cache@v2 - with: - path: ~/.cache/pre-commit - key: pre-commit|${{ env.pythonLocation }}|${{ hashFiles('.pre-commit-config.yaml') }} - - name: Install requirements - run: python -m pip install -r requirements.txt - - name: Run pre-commit hooks - run: pre-commit run --all-files --show-diff-on-failure - - name: Run tests - run: pytest diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml deleted file mode 100644 index 1901b85..0000000 --- a/.github/workflows/ci.yml +++ /dev/null @@ -1,30 +0,0 @@ -name: CI - -on: - push: - branches: [ master ] - pull_request: - branches: [ master ] - -jobs: - build: - runs-on: ubuntu-latest - - steps: - - uses: actions/checkout@v2 - - name: Set up Python 3.9 - uses: actions/setup-python@v2 - with: - python-version: 3.9 - - name: Install dependencies - run: | - echo "Install python dependencies" - python3 -m pip install --upgrade pip - python3 -m pip install pylint - if [ -f requirements.txt ]; then pip install -r requirements.txt; fi - echo "PYTHONPATH=$PYTHONPATH:$GITHUB_WORKSPACE" >> $GITHUB_ENV - echo $PYTHONPATH - - name: Python linter - run: pylint --rcfile rcfile.txt $(find . -type f -iname "*\.py" -not -path "./device/*") - - name: Test simulator - run: python3 -m unittest simulator/test_* diff --git a/.github/workflows/docs.yml b/.github/workflows/docs.yml new file mode 100644 index 0000000..c4d1c6b --- /dev/null +++ b/.github/workflows/docs.yml @@ -0,0 +1,28 @@ +name: docs + +on: + push: + branches: + - master + - cart-pole-3 # TODO: Remove after merging to master + +permissions: + contents: write + +jobs: + deploy: + runs-on: self-hosted + steps: + - uses: actions/checkout@v3 + with: + fetch-depth: 0 + - uses: actions/setup-python@v4 + with: + python-version: 3.9 + # TODO: Add proper chaching + # TODO: Maybe use poetry-based action + - run: pip install mkdocs-material mkdocs-material-extensions mkdocstrings[python] mike poetry + - run: | + git config user.name github-actions + git config user.email github-actions@github.com + - run: mike deploy --push --force --update-aliases $(poetry version -s) latest diff --git a/Dockerfile b/Dockerfile new file mode 100755 index 0000000..7d939a9 --- /dev/null +++ b/Dockerfile @@ -0,0 +1,31 @@ +FROM ubuntu:22.04 + +ENV DEBIAN_FRONTEND=noninteractive +ENV SHELL /bin/bash +SHELL ["/bin/bash", "-c"] + +WORKDIR /tmp + +### COMMON + +RUN apt update -q \ + && apt install -yq --no-install-recommends \ + build-essential \ + coinor-libipopt-dev \ + git \ + python3 \ + python3-dev \ + python3-pip \ + && pip3 install --no-cache-dir -U pip \ + && rm -rf /var/lib/apt/lists/* && apt-get clean + +### POETRY + +RUN pip3 install --no-cache-dir -U poetry \ + && poetry completions bash >> ~/.bash_completion + +## PYTHON DEPENDENCIES +COPY pyproject.toml /tmp/pyproject.toml + +RUN poetry config virtualenvs.create false \ + && poetry install --no-interaction --no-ansi --no-root diff --git a/SAC/config.yaml b/SAC/config.yaml new file mode 100644 index 0000000..3117f14 --- /dev/null +++ b/SAC/config.yaml @@ -0,0 +1,34 @@ +environment: + state_size: 5 + action_size: 1 + max_action: 1 + delta: 0.1 + +trainer: + device_name: cpu + gamma: 0.99 + max_buffer_size: 10**5 + start_timesteps: 5000 + timesteps_per_epoch: 1 + batch_size: 128 + max_grad_norm: 10 + tau: 0.005 + policy_update_freq: 1 + alpha: 0.1 + +actor: + lr: 3e-4 + tau: 1 + layer_sizes: + - 256 + - 256 + - 256 + +critic: + lr_1: 3e-4 + lr_2: 3e-4 + tau: 1 + layers: + - 256 + - 256 + - 256 \ No newline at end of file diff --git a/SAC/models.py b/SAC/models.py new file mode 100644 index 0000000..2eb9344 --- /dev/null +++ b/SAC/models.py @@ -0,0 +1,87 @@ +import torch +from torch import nn +from torch.nn import functional as F + +import numpy as np + +from torch.distributions import Normal + +from replay_buffer import state_to_tensor + +DEVICE = "cuda" if torch.cuda.is_available() else "cpu" +# LOG_STD_MIN, LOG_STD_MAX = -20, 2 + +class Actor(nn.Module): + def __init__(self, state_dim, action_dim): + super().__init__() + + self.h = 2056 #change + self.action_dim = action_dim + + self.actor_model = nn.Sequential( + nn.Linear(in_features=state_dim, out_features=self.h), + nn.ReLU(), + nn.Linear(in_features=self.h, out_features=self.h), + nn.ReLU(), + nn.Linear(in_features=self.h, out_features=self.h), + nn.ReLU(), + nn.Linear(in_features=self.h, out_features=self.h), + nn.ReLU(), + nn.Linear(in_features=self.h, out_features=action_dim*2) + ) + + def apply(self, states): + m = -20 + M = 2 + states = states.to(DEVICE) + output = self.actor_model(states) + means = output[..., :self.action_dim] + var = torch.tanh(output[..., self.action_dim:]) + 1 + var = 0.5 * (M - m) * var + m + var = torch.exp(var) + normal_distr = Normal(means, var) + + actions_first = normal_distr.rsample() + actions = torch.tanh(actions_first) + log_prob = normal_distr.log_prob(actions_first) - torch.log(1 - actions**2 + 1e-6) + + #this is a more numerically stable version of the appendix C eq.21 https://arxiv.org/pdf/1801.01290.pdf + + return actions, log_prob + + def get_action(self, states): + + with torch.no_grad(): + + states = state_to_tensor(states) + actions, _ = self.apply(states) + actions = actions.cpu().detach().numpy() + + assert isinstance(actions, (list,np.ndarray)) + assert actions.max() <= 1. and actions.min() >= -1, "actions must be in the range [-1, 1]" + return actions.item() + + +class Critic(nn.Module): + + def __init__(self, state_dim, action_dim): + super().__init__() + self.h = 2056 + input_dim = state_dim + action_dim + self.critic_model = nn.Sequential( + nn.Linear(in_features=input_dim, out_features=self.h), + nn.ReLU(), + nn.Linear(in_features=self.h, out_features=self.h), + nn.ReLU(), + nn.Linear(in_features=self.h, out_features=self.h), + nn.ReLU(), + nn.Linear(in_features=self.h, out_features=1) + ) + + def get_qvalues(self, states, actions): + + batch = torch.cat([states, actions], dim=1) + qvalues = self.critic_model(batch) + + # assert len(qvalues.shape) == 1 and qvalues.shape[0] == states.shape[0] + return qvalues \ No newline at end of file diff --git a/SAC/replay_buffer.py b/SAC/replay_buffer.py new file mode 100644 index 0000000..a060ea7 --- /dev/null +++ b/SAC/replay_buffer.py @@ -0,0 +1,62 @@ +import collections +import numpy as np +import torch +import random + +from math import pi, cos, tanh, sin + +from cartpole import State, Error + + + +def state_to_tensor(state: State): + return torch.tensor([ + (state.cart_position / 0.25), + (state.cart_velocity / 5.0), + (state.cart_acceleration / 7.5), + cos(state.pole_angle), + state.pole_angle / (6 * np.pi), #important + state.pole_angular_velocity / (6 * np.pi) #change and normalize + ]) + +def make_tensor(from_state, to_state, action, reward): + return torch.concat([ + state_to_tensor(from_state), + state_to_tensor(to_state), + torch.tensor([action]), + torch.tensor([reward]), + torch.tensor([to_state.error != Error.NO_ERROR]) + ]) + + +class ReplayBuffer: + + def __init__(self, state_dim: int, maxlen: int): + self.state_dim = state_dim + self.states = torch.zeros((maxlen, self.state_dim*2 + 3)) + self.maxlen = maxlen + self.ptr = 0 + self.length = 0 + + def __len__(self): + return len(self.states) + + def add(self, from_state: State, to_state: State, action: float, reward: float): + self.states[self.ptr] = make_tensor(from_state, to_state, action, reward) + self.ptr = (self.ptr + 1) % self.maxlen + self.length = min(self.length + 1, self.maxlen) + + def sample(self, sample_size: int, device): + sample_size = min(self.length, sample_size) + sample = self.states[random.sample(range(self.length), sample_size)] + return ( + sample[:, :self.state_dim].to(device), + sample[:, self.state_dim:self.state_dim*2].to(device), + sample[:, self.state_dim*2].reshape(-1, 1).to(device), + sample[:, self.state_dim*2+1].reshape(-1, 1).to(device), + sample[:, self.state_dim*2+2].reshape(-1, 1).to(device) + ) + def get_last(self): + if len(self.states) == 0: + return None + return self.states[(self.ptr - 1) % self.maxlen] \ No newline at end of file diff --git a/SAC/train.py b/SAC/train.py new file mode 100644 index 0000000..9c8eb39 --- /dev/null +++ b/SAC/train.py @@ -0,0 +1,112 @@ +import sys +sys.path.append("/users/aizam/cart-pole/") #changeable + +from cartpole.simulator import Simulator, State, Error, Target +from cartpole import log + +from trainer import Trainer, Config + +from utils import compute_reward + +from itertools import count + +import tqdm +import torch +import numpy as np + + +N_EPOCHS = 2 +N_EPOCHS_NOISED = 5 + + +config = Config( + state_dim=6, + action_dim=1, + max_buffer_size = 25000, + device_name = 'cpu', + batch_size = 768, + actor_lr = 1e-4, + critic_lr = 1e-4, + tau = 0.005, + max_grad_norm = 10, + alpha = 0.1, #the smaller the action space, the smaller should alpha be (entropy regularization) + gamma = 0.99, + start_timesteps = 0, + timesteps_per_epoch = 1, + policy_update_freq = 1, + opt_eps = 1e-4, + min_std = 0.1, + max_std = 8, + delta = 0.02, + n_iterations=2000, + n_epochs=10, + checkpoint_freq=1000 +) + + +log.setup(log_path='training_log.mcap', level=log.Level.DEBUG) + +env = Simulator() +trainer = Trainer(log, config) + +interaction_state = State( + cart_position=0, + pole_angle=0, + cart_velocity=0, + angular_velocity=0, + ) + +reset_state = State( + cart_position=0, + pole_angle=0, + cart_velocity=0, + angular_velocity=0, + ) + +for episode in range(1, 100): + + print(interaction_state.stamp) + print(episode) + + if episode % 2 == 0: + + noised_position = np.random.uniform(low=0, high=0.15) + + noised_pole_angle = np.random.uniform(low=2, high=3.14) + + reset_state = State( + cart_position=noised_position, + pole_angle=noised_pole_angle, + cart_velocity=0, + angular_velocity=0, + ) + + interaction_state = State( + cart_position=noised_position, + pole_angle=noised_pole_angle, + cart_velocity=0, + angular_velocity=0, + ) + + + if episode % 2 != 0: + + reset_state = State( + cart_position=0, + pole_angle=3.14, + cart_velocity=0, + angular_velocity=0, + ) + + interaction_state = State( + cart_position=0, + pole_angle=3.14, + cart_velocity=0, + angular_velocity=0, + ) + + env.reset(state=interaction_state) + + trainer.train(env, interaction_state, reset_state, episode) + + diff --git a/SAC/trainer.py b/SAC/trainer.py new file mode 100644 index 0000000..97bb3ad --- /dev/null +++ b/SAC/trainer.py @@ -0,0 +1,133 @@ +from cartpole.common import State, BaseModel +from SAC.replay_buffer import ReplayBuffer, state_to_tensor +from models import Actor, Critic +from utils import play_and_record, optimize, update_target_networks + + +import torch +import torch.nn as nn + +import numpy as np + +class Scalar(BaseModel): + value: float + +class Config(BaseModel): + state_dim: int + action_dim: int + max_buffer_size: int + device_name: str + batch_size: int + actor_lr: float + critic_lr: float + tau: float + max_grad_norm: int + alpha: float + gamma: float + start_timesteps: int + timesteps_per_epoch: int + policy_update_freq: int + opt_eps: float + min_std: float + max_std: float + delta: float + n_iterations: int + checkpoint_freq: int + + + +class Trainer: + def __init__(self, logger, config): + self.logger = logger + self.config = config + self.device = torch.device(config.device_name) + + self.exp_replay = ReplayBuffer(config.state_dim, config.max_buffer_size) + + self.actor = Actor(config.state_dim, config.action_dim).to(self.device) + + self.critic1 = Critic(config.state_dim, config.action_dim).to(self.device) + self.critic2 = Critic(config.state_dim, config.action_dim).to(self.device) + + self.target_critic1 = Critic(config.state_dim, config.action_dim).to(self.device) + self.target_critic2 = Critic(config.state_dim, config.action_dim).to(self.device) + + self.target_critic1.load_state_dict(self.critic1.state_dict()) + self.target_critic2.load_state_dict(self.critic2.state_dict()) + + + self.opt_actor = torch.optim.Adam(self.actor.parameters(), lr=config.actor_lr, eps=config.opt_eps) + self.opt_critic1 = torch.optim.Adam(self.critic1.parameters(), lr=config.critic_lr, eps=config.opt_eps) + self.opt_critic2 = torch.optim.Adam(self.critic2.parameters(), lr=config.critic_lr, eps=config.opt_eps) + + + def compute_critic_target(self, rewards, next_states, is_done): + is_not_done = 1 - is_done + with torch.no_grad(): + next_actions, log_prob = self.actor.apply(next_states) + q_values_1 = self.target_critic1.get_qvalues(next_states, next_actions) + q_values_2 = self.target_critic2.get_qvalues(next_states, next_actions) + v_values = torch.min(q_values_1, q_values_2) - self.config.alpha * log_prob.sum(dim=1) + critic_target = (rewards + self.config.gamma * v_values * is_not_done).squeeze(-1) + + return critic_target + + def compute_actor_loss(self, states): + + actions, log_prob = self.actor.apply(states) + q_values_1 = self.critic1.get_qvalues(states, actions) + q_values_2 = self.critic2.get_qvalues(states, actions) + q_values = torch.min(q_values_1, q_values_2) + + assert actions.requires_grad, "actions must be differentiable with respect to policy parameters" + + actor_loss = -q_values.mean() + self.config.alpha * log_prob.mean() + return actor_loss + + + def train(self, env, interaction_state, start_state, epoch): + + for n_iterations in range(0, self.config.n_iterations, self.config.timesteps_per_epoch): + _, interaction_state = play_and_record(interaction_state, self.actor, env, self.exp_replay, self.config.delta, start_state, self.config.timesteps_per_epoch) + states, next_states, actions, rewards, is_done = self.exp_replay.sample(self.config.batch_size, self.config.device_name) + critic_target = self.compute_critic_target(rewards, next_states, is_done) + # losses + critic1_qvalues = self.critic1.get_qvalues(states, actions) + critic1_loss = (critic1_qvalues - critic_target) ** 2 + optimize("critic1", self.critic1, self.opt_critic1, critic1_loss, states, env, 10) + + critic2_qvalues = self.critic2.get_qvalues(states, actions) + critic2_loss = (critic2_qvalues - critic_target) ** 2 + optimize("critic2", self.critic2, self.opt_critic2, critic2_loss, states, env, 10) + + if n_iterations % self.config.policy_update_freq == 0: + actor_loss = self.compute_actor_loss(states) + optimize("actor", self.actor, self.opt_actor, actor_loss, states, env, 10) + + # update target networks + update_target_networks(self.critic1, self.target_critic1, self.config.tau) + update_target_networks(self.critic2, self.target_critic2, self.config.tau) + + + def train_with_new_actor(self, env, interaction_state, start_state, epoch): + + for n_iterations in range(0, self.config.n_iterations, self.config.timesteps_per_epoch): + _, interaction_state = play_and_record(interaction_state, self.actor, env, self.exp_replay, self.config.delta, start_state, self.config.timesteps_per_epoch) + states, next_states, actions, rewards, is_done = self.exp_replay.sample(self.config.batch_size, self.config.device_name) + critic_target = self.compute_critic_target(rewards, next_states, is_done) + # losses + critic1_qvalues = self.critic1.get_qvalues(states, actions) + critic1_loss = (critic1_qvalues - critic_target) ** 2 + optimize("critic1", self.critic1, self.opt_critic1, critic1_loss, states, self.config.max_grad_norm) + + critic2_qvalues = self.critic2.get_qvalues(states, actions) + critic2_loss = (critic2_qvalues - critic_target) ** 2 + optimize("critic2", self.critic2, self.opt_critic2, critic2_loss, states, self.config.max_grad_norm) + + if n_iterations % self.config.policy_update_freq == 0: + actor_loss = self.compute_actor_loss(states) + optimize("actor", self.actor, self.opt_actor, actor_loss, states, self.config.max_grad_norm) + + # update target networks + update_target_networks(self.critic1, self.target_critic1, self.config.tau) + update_target_networks(self.critic2, self.target_critic2, self.config.tau) \ No newline at end of file diff --git a/SAC/utils.py b/SAC/utils.py new file mode 100644 index 0000000..0cf93f3 --- /dev/null +++ b/SAC/utils.py @@ -0,0 +1,109 @@ +import torch +import torch.nn as nn + +import numpy as np +from math import cos + +from cartpole.common import State, BaseModel, Error +from cartpole.simulator import Target +from cartpole import log + +import time + +class Scalar(BaseModel): + value: float + +def play_and_record(initial_state, agent, env, exp_replay, delta, start_state, n_steps=10): + state = initial_state + sum_rewards = 0 + time.sleep(0.02) + + for t in range(n_steps): + + prev_state = state + env.advance(delta) + state = env.get_state() + action = agent.get_action(state) + reward = compute_reward(state, action) + + exp_replay.add(prev_state, state, action, reward.value) + + last_element = exp_replay.get_last() + if last_element is not None: + terminated = last_element[-1] + + env.set_target(Target(acceleration=action)) + + if terminated or state.stamp > 7 or np.abs(state.pole_angle) > np.pi + 0.1: + reward = Scalar(value=-1) + termination_state = state + log.publish('/cartpole/state', state, state.stamp) + log.publish('/cartpole/reward', reward, state.stamp) + state = start_state + env.reset(state=state) + time.sleep(0.02) + return reward.value, termination_state + + sum_rewards += reward.value + + log.publish('/cartpole/state', state, state.stamp) + log.publish('/cartpole/reward', reward, state.stamp) + + return sum_rewards, state + + +def optimize(name, model, optimizer, loss, state: State, env, max_grad_norm=10): + + loss = loss.mean() + optimizer.zero_grad() + loss.backward() + grad_norm = nn.utils.clip_grad_norm_(model.parameters(), max_grad_norm) + optimizer.step() + + state_stmp = env.get_state() + loss_log = Scalar(value=loss.item()) + loss_name = 'loss' + name + grad_name = 'grad_norm' + name + log.publish(loss_name, loss_log, state_stmp.stamp) + grad_norm_log = Scalar(value=grad_norm.item()) + log.publish(grad_name, grad_norm_log, state_stmp.stamp) + + + +def update_target_networks(model, target_model, tau): + for param, target_param in zip(model.parameters(), target_model.parameters()): + target_param.data.copy_(tau * param.data + (1 - tau) * target_param.data) + + +def compute_reward(state: State): + angle_reward = 1-(cos(state.pole_angle) + 0.01 * state.pole_angular_velocity**2 ) + straight_up_reward = 0.1 if cos(state.pole_angle) < 0.1 else 0 + position_reward = -state.cart_position**2 + return angle_reward + position_reward + straight_up_reward + +def play_and_record_evaluate(initial_state, agent, env, delta, start_state, n_steps=10): + # added the start_state to include diversity because we will change it + state = initial_state + sum_rewards = 0 + + for t in range(n_steps): + prev_state = state + env.advance(delta) + state = env.get_state() + action = agent.get_action(state) + reward = compute_reward(state, action) + env.set_target(Target(acceleration=action)) + + if state.error == Error.NO_ERROR: + state = start_state + env.reset(state=state) + else: + state = state + + sum_rewards += reward.value + + log.publish('/cartpole/state', state, state.stamp) + log.publish('/cartpole/reward', reward, state.stamp) + + return sum_rewards, state + \ No newline at end of file diff --git a/cartpole/__init__.py b/cartpole/__init__.py index e69de29..da2109d 100644 --- a/cartpole/__init__.py +++ b/cartpole/__init__.py @@ -0,0 +1,5 @@ +# reimport more commonly used classes + +from cartpole.common import CartPoleBase, Config, Error, State, Target, Limits, Parameters +from cartpole.eval import find_parameters +from cartpole.simulator import Simulator, SimulatorInfo diff --git a/cartpole/__main__.py b/cartpole/__main__.py new file mode 100644 index 0000000..d02a0ef --- /dev/null +++ b/cartpole/__main__.py @@ -0,0 +1,129 @@ +from cartpole.common import Config, Limits, Parameters +from cartpole.common import CartPoleBase, Error, State, Target +from cartpole.simulator import Simulator +from cartpole.eval import find_parameters + +import cartpole.log as log + +import argparse +import random +import time + + +def parse_args(): + common = argparse.ArgumentParser( + prog='cartpole', + description='cartpole control experiments' + ) + + subparsers = common.add_subparsers(title='commands', dest='command', required=True, help='command help') + + # common arguments + + common.add_argument('-S', '--simulation', action='store_true', help='simulation mode') + common.add_argument('-c', '--config', type=str, help='cartpole yaml config file') + common.add_argument('-m', '--mcap', type=str, default='', help='mcap log file') + common.add_argument('-a', '--advance', type=float, default=0.01, help='advance simulation time (seconds)') + + # eval arguments + eval = subparsers.add_parser('eval', help='system identification') + + eval.add_argument('-d', '--duration', type=float, default=10.0, help='experiment duration (seconds)') + eval.add_argument('-O', '--output', type=str, help='output yaml config file') + + return common.parse_args() + + +def evaluate(device: CartPoleBase, config: Config, args: argparse.Namespace) -> None: + log.info('parameters evaluation') + + position_margin = 0.01 + position_tolerance = 0.005 + duration = args.duration + advance = args.advance + + position_max = config.control_limit.cart_position - position_margin + velocity_max = config.control_limit.cart_velocity + acceleration_max = config.control_limit.cart_acceleration + + log.info(f'run calibration session for {duration:.2f} seconds') + device.reset() + + start = device.get_state() + state = start + + target = Target(position=0, velocity=0, acceleration=0) + states = [] + + while not state.error and state.stamp - start.stamp < duration: + state = device.get_state() + + if abs(target.position - state.cart_position) < position_tolerance: + position = random.uniform(position_max/2, position_max) + target.position = position if target.position < 0 else -position + target.velocity = random.uniform(velocity_max/2, velocity_max) + target.acceleration = random.uniform(acceleration_max/2, acceleration_max) + + log.info(f'target {target}') + device.set_target(target) + + log.publish('/cartpole/state', state, state.stamp) + log.publish('/cartpole/target', target, state.stamp) + log.publish('/cartpole/info', device.get_info(), state.stamp) + + states.append(state) + device.advance(advance) + + if args.simulation: + time.sleep(advance) # simulate real time + + log.info(f'find parameters') + parameters = find_parameters(states, config.parameters.gravity) + + log.info(f'parameters: {parameters}') + + if args.output: + log.debug(f'save config to {args.output}') + + config = config.copy(deep=True) + config.parameters = parameters + + config.to_yaml_file(args.output) + + +def main(): + args = parse_args() + + log.setup(log_path=args.mcap, level=log.Level.DEBUG) + # TODO(@dasimagin) fix this dirty hack + # wait for foxglove server to start + time.sleep(5) + + if args.mcap: + log.debug(f'mcap file: {args.mcap}') + else: + log.debug('no mcap file specified') + + if args.simulation: + log.info('simulation mode') + device = Simulator(integration_step=min(args.advance/20, 0.001)) + else: + raise NotImplementedError() + + if args.config: + log.debug(f'config file: {args.config}') + config = Config.from_yaml_file(args.config) + else: + log.warning('no config file specified, using defaults') + config = Config() + + + device.set_config(config) + + if args.command == 'eval': + evaluate(device, config, args) + else: + raise NotImplementedError() + +if __name__ == "__main__": + main() diff --git a/cartpole/actors/__init__.py b/cartpole/actors/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/cartpole/actors/demo.py b/cartpole/actors/demo.py deleted file mode 100644 index 6ab966a..0000000 --- a/cartpole/actors/demo.py +++ /dev/null @@ -1,36 +0,0 @@ -from cartpole.common.interface import State -from cartpole.sessions.actor import Actor -from cartpole.control import BalanceLQRControl, TrajectoryLQRControl, Trajectory -from logging import getLogger - -logger = getLogger(__file__) - -class DemoActor(Actor): - def __init__(self, config, **kwargs): - super().__init__(**kwargs) - logger.info("Calculating trajectory...") - init = State.home() - self.trajectory = Trajectory(config, init) - - self.balance_control = BalanceLQRControl(config) - self.trajectory_control = TrajectoryLQRControl(config, self.trajectory) - self.begin = None - self.proxy = None - logger.info("Trajectory ready") - - def __call__(self, state: State, stamp=None) -> float: - self.save_expected_state(stamp) - if stamp < self.trajectory.duration: - target = self.trajectory_control(stamp, state) - else: - target = self.balance_control(state) - return float(target) - - def save_expected_state(self, stamp): - state_expected, target_expected = self.trajectory(stamp) - ts = self.proxy._timestamp() - self.proxy._add_value('expected.cart_position', ts, float(state_expected.cart_position)) - self.proxy._add_value('expected.cart_velocity', ts, float(state_expected.cart_velocity)) - self.proxy._add_value('expected.pole_angle', ts, float(state_expected.pole_angle)) - self.proxy._add_value('expected.pole_angular_velocity', ts, float(state_expected.pole_angular_velocity)) - self.proxy._add_value('expected.target', ts, float(target_expected)) diff --git a/cartpole/common.py b/cartpole/common.py new file mode 100644 index 0000000..c2e1ee4 --- /dev/null +++ b/cartpole/common.py @@ -0,0 +1,403 @@ +import enum +import numpy +import torch + +from pydantic import BaseModel, Field +from typing import Any + +import json +import yaml + + +class Limits(BaseModel): + """ + Constraints of cart state, used for control and cartpole parametrization. + + Attributes + ---------- + cart_position: float | None + max absolute cart position (m) + cart_velocity: float | None + max absolute cart velocity (m/s) + cart_acceleration: float | None + max absolute cart acceleration (m/s^2) + """ + + cart_position: float = 0.0 + cart_velocity: float = 0.0 + cart_acceleration: float = 0.0 + + def stronger(self, other: "Limits") -> bool: + """ + Check if this limit is stronger (more restrictive) than the other. + """ + + return ( + self.cart_position <= other.cart_position + and self.cart_velocity <= other.cart_velocity + and self.cart_acceleration <= other.cart_acceleration + ) + + +class Parameters(BaseModel): + """ + CartPole dynamics parameters. + Parameters are defined and matter only for simulation. + + For more information see: https://cartpole.robotics-lab.ru/dynamics-and-control + + Attributes + ---------- + gravity: float + gravity constant (default 9.8 m/s^2) + friction_coef: float + inner system parameters + mass_coef: float + inner system parameters + """ + + @staticmethod + def make( + mass: float, + inertia: float, + length: float, + friction: float = 0.0, + gravity: float = 9.81, + ) -> "Parameters": + """ + Create parameters from physical properties. + + Parameters + ---------- + mass: float + pole mass (kg) + inertia: float + pole moment of inertia (kg*m^2) + length: float + distance from the pivot to the center of mass (m) + friction: float + friction coefficient (N*s/m) + gravity: float + gravity constant (m/s^2) + """ + + delimeter = mass * length * length + inertia + + return Parameters( + gravity=gravity, + friction_coef=friction / delimeter, + mass_coef=(mass * length) / delimeter, + ) + + gravity: float = 9.81 + friction_coef: float | None = None + mass_coef: float | None = None + + +class Config(BaseModel): + """ + CartPole configuration. + + Attributes + ---------- + hardware_limits: Limits + hardware limits + control_limits: Limits + control limits + parameters: Parameters + dynamics parameters (defined only for simulation) + """ + + hardware_limit: Limits = Limits() + control_limit: Limits = Limits() + parameters: Parameters = Parameters() + + def to_yaml(self) -> str: + """ + Convert config to yaml string. + """ + + return yaml.dump(self.dict(), indent=2) + + def to_yaml_file(self, file_path: str) -> None: + """ + Save config to yaml file. + """ + + with open(file_path, "w") as f: + f.write(self.to_yaml()) + + @staticmethod + def from_yaml(yaml_str: str) -> "Config": + """ + Load config from yaml string. + """ + + return Config.parse_obj(yaml.load(yaml_str, Loader=yaml.FullLoader)) + + @staticmethod + def from_yaml_file(file_path: str) -> "Config": + """ + Load config from yaml file. + """ + + with open(file_path, "r") as f: + return Config.from_yaml(f.read()) + + +class Error(enum.IntEnum): + """ + CartPole system error codes. + + Attributes + ---------- + NO_ERROR: + no error + NEED_RESET: + reset system before use (make homing) + CART_POSITION_OVERFLOW: + cart position is out of control limit + CART_VELOCITY_OVERFLOW: + cart velocity is out of control limit + CART_ACCELERATION_OVERFLOW: + cart acceleration is out of control limit + HARDWARE: + some hardware error (specific for real device) + """ + + NO_ERROR = 0 + NEED_RESET = 1 + CART_POSITION_OVERFLOW = 2 + CART_VELOCITY_OVERFLOW = 3 + CART_ACCELERATION_OVERFLOW = 4 + HARDWARE = 5 + + def __bool__(self) -> bool: + return self != Error.NO_ERROR + + def __repr__(self) -> str: + return str(self.value) + + +class State(BaseModel): + """ + System state. + + Attributes + ---------- + cart_position: float + cart position (m) + cart_velocity: float + cart velocity (m/s) + cart_acceleration: float + cart acceleration (m/s^2) + + pole_angle: float + absolute accumulated pole angle (rad) + pole_angular_velocity: float + pole angular velocity (rad/s) + + stamp: float + system time stamp (s) + error: Error + system error code + """ + + cart_position: float = 0.0 + cart_velocity: float = 0.0 + cart_acceleration: float = 0.0 + + pole_angle: float = 0.0 + pole_angular_velocity: float = 0.0 + + stamp: float = 0.0 + error: Error = Error.NO_ERROR + + class Config: + @staticmethod + def json_schema_extra(schema: Any, model: Any) -> None: + # make schema lightweight + schema.pop("definitions", None) + + properties = schema["properties"] + for name in properties: + properties[name].pop("title", None) + + # simplify schema for foxglove + properties["error"] = {"type": "integer", "enum": [e.value for e in Error]} + + def validate(self, config: Config) -> None: + """ + Validates state against limits. + """ + + if self.error: + return # keep error + + if abs(self.cart_position) > config.hardware_limit.cart_position: + self.error = Error.CART_POSITION_OVERFLOW + return + + if abs(self.cart_velocity) > config.hardware_limit.cart_velocity: + self.error = Error.CART_VELOCITY_OVERFLOW + return + + if abs(self.cart_acceleration) > config.hardware_limit.cart_acceleration: + self.error = Error.CART_ACCELERATION_OVERFLOW + return + + def copy(self) -> "State": + """ + Returns deep copy of the state. + """ + return State(**self.dict()) + + def as_tuple(self) -> tuple[float, float, float, float]: + """ + Returns tuple (cart_position, pole_angle, cart_velocity, pole_angular_velocity). + """ + return ( + self.cart_position, + self.pole_angle, + self.cart_velocity, + self.pole_angular_velocity, + ) + + def torch4(self) -> torch.Tensor: + """ + Returns state tuple as torch vector. + """ + return torch.tensor(self.as_tuple(), dtype=torch.float32) + + def numpy4(self) -> numpy.ndarray: + """ + Returns state tuple as numpy vector. + """ + return numpy.array(self.as_tuple(), dtype=numpy.float32) + + +class Target(BaseModel): + """ + Control command, used to set desired cart acceleration. + + 1. Only acceleration is specified, cart moves with target acceleration. + + 2. Velocity is specified, but position is not. Cart reaches velocity, with target acceleration (absolute value needed). + If acceleration is not specified, used control limit as a default. + + 3. Position is specified. Cart reaches position with target velocity/accleration, using bang-bang strategy. + If velocity/accleration is not specified (absolute value needed), use control limit as a default. + + Attributes + ---------- + position: float | None + desired cart position (m) + velocity: float | None + desired cart velocity (m/s) + acceleration: float | None + desired cart acceleration (m/s^2) + """ + + position: float | None = None + velocity: float | None = None + acceleration: float | None = None + + def acceleration_or(self, default: float) -> float: + """ + Returns acceleration or default value. + """ + return self.acceleration if self.acceleration is not None else default + + def velocity_or(self, default: float) -> float: + """ + Returns velocity or default value. + """ + return self.velocity if self.velocity is not None else default + + def validate(self, config: Config) -> None: + """ + Validates target against limits. + """ + + if self.acceleration is not None: + assert abs(self.acceleration) <= config.control_limit.cart_acceleration + + if self.velocity is not None: + assert abs(self.velocity) <= config.control_limit.cart_velocity + + if self.acceleration is not None: + assert self.acceleration >= 0 + + if self.position is not None: + assert abs(self.position) <= config.control_limit.cart_position + + if self.velocity is not None: + assert self.velocity >= 0 + if self.acceleration is not None: + assert self.acceleration >= 0 + + +class CartPoleBase: + """ + The class specifies a interface of the CartPole (device or simulation). + A pole is attached by an joint to a cart, which moves along guide axis. + The pendulum is initially at rest state. The goal is to maintain it in + upright pose by increasing and reducing cart's acceleration. + + This environment is some variation of the cart-pole problem + described by Barto, Sutton, and Anderson. + A pole is at starting position 0 with no velocity and acceleration. + """ + + def get_config(self) -> Config: + """ + Get current configuration of the device. + """ + raise NotImplementedError + + def set_config(self, config: Config) -> None: + """ + Sets new configuration for the device. Real device ignore hardware limits and parameters. + """ + raise NotImplementedError + + def reset(self, state: State = State()) -> None: + """ + Resets the device to the state. It must be called at the beginning of any session. + For real device only position may be set. + """ + raise NotImplementedError + + def get_state(self) -> State: + """ + Returns current device state. + """ + raise NotImplementedError + + def get_info(self) -> BaseModel: + """ + Returns usefull debug information as BaseModel. + """ + raise NotImplementedError + + def set_target(self, target: Target) -> State: + """ + Set desired target acceleration and returns current state. + """ + raise NotImplementedError + + def advance(self, delta: float) -> None: + """ + Advance system by delta seconds (has means only for simulation). + + Parameters: + delta: float + time step in seconds + """ + raise NotImplementedError + + def close(self) -> None: + """ + Free all allocated resources. + """ + raise NotImplementedError diff --git a/cartpole/common/__init__.py b/cartpole/common/__init__.py deleted file mode 100644 index 681612d..0000000 --- a/cartpole/common/__init__.py +++ /dev/null @@ -1,2 +0,0 @@ -from cartpole.common.interface import Config, Error, State, CartPoleBase -from cartpole.common.view import generate_pyplot_animation diff --git a/cartpole/common/interface.py b/cartpole/common/interface.py deleted file mode 100644 index 706a654..0000000 --- a/cartpole/common/interface.py +++ /dev/null @@ -1,146 +0,0 @@ -import enum -import dataclasses as dc - -import numpy as np - - -class Error(enum.IntEnum): - NO_ERROR = 0 - NEED_RESET = 1 - X_OVERFLOW = 2 - V_OVERFLOW = 3 - A_OVERFLOW = 4 - MOTOR_STALLED = 5 - ENDSTOP_HIT = 6 - - def __bool__(self) -> bool: - return self != Error.NO_ERROR - - -@dc.dataclass -class Config: - # software cart limits - max_position: float = 0.25 # m - max_velocity: float = 2.0 # m/s - max_acceleration: float = 3.5 # m/s^2 - # hardware limits - hard_max_position: float = 0.27 # m - hard_max_velocity: float = 2.5 # m/s - hard_max_acceleration: float = 5.0 # m/s^2 - # hardware flags - clamp_position: bool = False - clamp_velocity: bool = False - clamp_acceleration: bool = False - # physical params - pole_length: float = 0.3 # m - pole_mass: float = 0.118 # kg - gravity: float = 9.8 # m/s^2 - - -@dc.dataclass -class State: - cart_position: float = 0 - cart_velocity: float = 0 - pole_angle: float = 0 - pole_angular_velocity: float = 0 - error: Error = Error.NO_ERROR - cart_acceleration: float = 0 - - @staticmethod - def from_array(a): - ''' - q = (x, a, v, w) - ''' - return State(a[0], a[2], a[1], a[3]) - - @staticmethod - def home(): - return State(.0, .0, .0, .0) - - def as_tuple(self): - return ( - self.cart_position, - self.pole_angle, - self.cart_velocity, - self.pole_angular_velocity, - ) - - def as_array(self): - return np.array(self.as_tuple()) - - def as_array_4x1(self): - return self.as_array().reshape(4, 1) - - def __repr__(self): - return '(x={x:+.2f}, v={v:+.2f}, a={a:+.2f}, w={w:+.2f}, err={err})'.format( - x = self.cart_position, - v = self.cart_velocity, - a = self.pole_angle, - w = self.pole_angular_velocity, - err=self.error, - ) - - -class CartPoleBase: - ''' - Description: - Сlass implements a physical simulation of the cart-pole device. - A pole is attached by an joint to a cart, which moves along guide axis. - The pendulum is initially at rest state. The goal is to maintain it in - upright pose by increasing and reducing the cart's velocity. - Source: - This environment is some variation of the cart-pole problem - described by Barto, Sutton, and Anderson - Initial state: - A pole is at starting position 0 with no velocity and acceleration. - ''' - - def reset(self, config: Config) -> None: - ''' - Resets the device to the initial state. - The pole is at rest position and cart is centered. - It must be called at the beginning of any session. - ''' - raise NotImplementedError - - def get_state(self) -> State: - ''' - Returns current device state. - ''' - raise NotImplementedError - - def get_info(self) -> dict: - ''' - Returns usefull debug information. - ''' - raise NotImplementedError - - def get_target(self) -> float: - ''' - Returns current target acceleration. - ''' - raise NotImplementedError - - def set_target(self, target: float) -> None: - ''' - Set desired target acceleration. - ''' - raise NotImplementedError - - def advance(self, delta: float = None) -> None: - ''' - Advance the dynamic system by delta seconds. - ''' - pass - - def timestamp(self): - ''' - Current time. - ''' - raise NotImplementedError - - def close(self) -> None: - ''' - Free all allocated resources. - ''' - raise NotImplementedError diff --git a/cartpole/common/util.py b/cartpole/common/util.py deleted file mode 100644 index 21d28a4..0000000 --- a/cartpole/common/util.py +++ /dev/null @@ -1,45 +0,0 @@ -import logging -import socket -import math -import os -from contextlib import closing -import sys - -from cartpole.common.interface import State - -STEP_COUNT = 'step_count' - - -def reward(state: State) -> float: - return math.exp(-math.cos(state.pole_angle)) - - -def init_logging(): - ''' - Helper function to initialize logging. In top-level scripts (__name__ == __main__) - you should call this function as soon as possible, to ensure no logs will be printed - before logging is initialized. Only first call of this function is effective - all - later calls are ignored. - - Logging options are customizable via environment variables: - * LOGGING_FORMAT - logging format string (default: see below) - * LOGGING_LEVEL - logging level (default: INFO) - ''' - DEFAULT_FORMAT = '%(asctime)s [%(levelname)s] %(name)s :: %(message)s' - - if getattr(init_logging, '__initialized', False): - return # Already initialized - - format = os.environ.get('LOGGING_FORMAT', DEFAULT_FORMAT) - level = getattr(logging, os.environ.get('LOGGING_LEVEL', 'INFO').upper()) - kwargs = dict(format=format, level=level) - - logging.basicConfig(**kwargs) - setattr(init_logging, '__initialized', True) - - -def find_free_port(): - with closing(socket.socket(socket.AF_INET, socket.SOCK_STREAM)) as s: - s.bind(('', 0)) - s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) - return s.getsockname()[1] diff --git a/cartpole/common/view.py b/cartpole/common/view.py deleted file mode 100644 index b66dcc1..0000000 --- a/cartpole/common/view.py +++ /dev/null @@ -1,59 +0,0 @@ -import matplotlib.pyplot as plt -import matplotlib.animation as animation - -import math - - -def generate_pyplot_animation( - config, - trajectory, - trajectory_expected=None, - timestamps=None, - margin=0.1): - if trajectory_expected is not None: - assert len(trajectory) == len(trajectory_expected) - - if timestamps is not None: - assert len(trajectory) == len(timestamps) - - x_lim = config.max_position + config.pole_length + margin - y_lim = config.pole_length + margin - - fig, ax = plt.subplots(figsize=(16, 8)) - ax.set_title('CartPole') - ax.set_xlim(-x_lim, +x_lim) - ax.set_ylim(-y_lim, +y_lim) - ax.set_aspect('equal') - ax.grid(linestyle='--') - - pole, = ax.plot([], [], 'o-', lw=2, c='red') - pole_expected, = ax.plot([], [], 'o-', lw=4, c='gray', alpha=0.3) - timestamp_text = ax.text(0.05, 0.9, '', transform=ax.transAxes, fontsize=16) - - def generate_pole(state): - x = state.cart_position - a = state.pole_angle - - l = config.pole_length - - return [x, x + math.sin(a)*l], [0, -math.cos(a)*l] - - def animate(i): - pole_x, pole_y = generate_pole(trajectory[i]) - pole.set_data(pole_x, pole_y) - - if trajectory_expected: - pole_x, pole_y = generate_pole(trajectory_expected[i]) - pole_expected.set_data(pole_x, pole_y) - - if timestamps is not None: - timestamp_text.set_text(f't={timestamps[i]:.3f}s') - - return pole, pole_expected - - anim = animation.FuncAnimation(fig, animate, len(trajectory)) - plt.close(fig) - - return anim - - diff --git a/cartpole/control/__init__.py b/cartpole/control/__init__.py deleted file mode 100644 index 01a5c55..0000000 --- a/cartpole/control/__init__.py +++ /dev/null @@ -1,3 +0,0 @@ -from cartpole.control.lqr import BalanceLQRControl, TrajectoryLQRControl -from cartpole.control.trajectory import Trajectory - diff --git a/cartpole/control/drake_trajectory.py b/cartpole/control/drake_trajectory.py deleted file mode 100644 index 3ed6f08..0000000 --- a/cartpole/control/drake_trajectory.py +++ /dev/null @@ -1,77 +0,0 @@ -import pydrake - -from pydrake.solvers.mathematicalprogram import Solve -from pydrake.systems.trajectory_optimization import DirectCollocation - -from cartpole.simulator.pydrake.system import CartPoleSystem - -import math -import numpy - -def build_trajectory(config, initial_state, sample_n=100, duration=10): - system = CartPoleSystem() - context = system.CreateContext(config, initial_state) - - program = DirectCollocation( - system, - context, - num_time_samples=sample_n, - minimum_timestep=0.001, - maximum_timestep=0.1, - input_port_index=system.get_input_port().get_index()) - - program.AddEqualTimeIntervalsConstraints() - program.AddDurationBounds(0, duration) - - program.AddBoundingBoxConstraint( - initial_state.as_array(), - initial_state.as_array(), - program.initial_state()) - - target_x_max = config.config.max_position * 0.75 - - program.AddBoundingBoxConstraint( - [-target_x_max, math.pi, 0.0, 0.0], - [+target_x_max, math.pi, 0.0, 0.0], - program.final_state()) - - q = program.state() - x, a, v, w = q[0], q[1], q[2], q[3] - - program.AddConstraintToAllKnotPoints(-config.max_position <= x) - program.AddConstraintToAllKnotPoints(x <= +config.max_position) - - program.AddConstraintToAllKnotPoints(-config.max_velocity <= v) - program.AddConstraintToAllKnotPoints(v <= +config.max_velocity) - - u = program.input()[0] - program.AddConstraintToAllKnotPoints(-config.max_acceleration <= u) - program.AddConstraintToAllKnotPoints(u <= config.max_acceleration) - - program.AddRunningCost(u**2) - program.AddRunningCost(program.time()) - # program.AddFinalCost(u**2) - program.AddFinalCost(x**2) - - result = Solve(program) - assert result.is_success() - - state_trajectory = program.ReconstructStateTrajectory(result) - target_trajectory = program.ReconstructInputTrajectory(result) - - return state_trajectory, target_trajectory - - - -class Trajectory: - def __init__(self, config, initial_state, sample_n=100, max_duration=10): - states, targets = build_trajectory(config, initial_state, sample_n=sample_n, max_duration=max_duration) - self.states = states - self.targets = targets - - def sammple(self, sample_n): - time_steps = numpy.linspace(self.states.start_time(), self.states.end_time(), sample_n) - state_values = self.states.vector_values(time_steps).transpose() - target_values = self.targets.vector_values(time_steps).transpose() - - return time_steps, state_values, target_values diff --git a/cartpole/control/lqr.py b/cartpole/control/lqr.py deleted file mode 100644 index fc2f847..0000000 --- a/cartpole/control/lqr.py +++ /dev/null @@ -1,76 +0,0 @@ -from pydrake.systems.controllers import LinearQuadraticRegulator -from pydrake.systems.controllers import FiniteHorizonLinearQuadraticRegulator -from pydrake.systems.controllers import FiniteHorizonLinearQuadraticRegulatorOptions -from pydrake.systems.primitives import Linearize - -from cartpole.common import Config, Error, State -from cartpole.simulator.pydrake.system import CartPoleSystem - -import math -import numpy - -class BalanceLQRControl: - def __init__(self, config): - state = State( - cart_position = 0, - cart_velocity = 0, - pole_angle = math.pi, - pole_angular_velocity = 0 - ) - - self.q0 = state.as_array() - self.u0 = numpy.array([0]) - - system = CartPoleSystem() - context = system.CreateContext(config, self.q0) - system.get_input_port().FixValue(context, self.u0) - - # Q = numpy.diag([1, 13, 1, 4]) - # R = numpy.diag([0.18]) - Q = numpy.diag([10.0, 1, 1, 1]) - R = numpy.diag([0.5]) - - linearized = Linearize(system, context) - self.K, _ = LinearQuadraticRegulator(linearized.A(), linearized.B(), Q, R) - - def __call__(self, state): - q = state.as_array() - error = q - self.q0 - u = -self.K @ error - return u[0] - - -class TrajectoryLQRControl: - def __init__(self, config, trajectory): - Q = numpy.diag([1, 1, 1, 1]) - R = numpy.diag([1]) - - options = FiniteHorizonLinearQuadraticRegulatorOptions() - options.x0 = trajectory.states - options.u0 = trajectory.targets - options.Qf = Q - - system = CartPoleSystem() - context = system.CreateContext(config, State().as_array()) - - self.trajectory = trajectory - self.regulator = FiniteHorizonLinearQuadraticRegulator( - system, - context, - t0=options.u0.start_time(), - tf=options.u0.end_time(), - Q=Q, - R=R, - options=options - ) - - def __call__(self, stamp, state): - q = state.as_array_4x1() - q0 = self.trajectory.states.value(stamp) - u0 = self.trajectory.targets.value(stamp) - - error = q - q0 - K = self.regulator.K.value(stamp) - u = u0 - K @ error - - return u[0] diff --git a/cartpole/control/model.py b/cartpole/control/model.py deleted file mode 100644 index 481879d..0000000 --- a/cartpole/control/model.py +++ /dev/null @@ -1,30 +0,0 @@ -import numpy as np -import math - - -class Model: - def __init__(self, params): - self.params = params - - # caching - self.coef = 1.5 * self.params.pole_length - - self.A = np.array( - [[0, 0, 1, 0], - [0, 0, 0, 1], - [0, 0, 0, 0], - [0, 0, 0, 0]], - dtype=np.float32 - ) - - self.B = np.array([[0], [0], [1], [0]], dtype=np.float32) - - def linearize(self, q, u): - theta = q[1][0] - cos_theta = math.cos(theta) - sin_theta = math.sin(theta) - - self.A[3][1] = self.coef * (u[0][0]*sin_theta - self.params.gravity*cos_theta) - self.B[3][0] = -self.coef * cos_theta - - return self.A, self.B \ No newline at end of file diff --git a/cartpole/control/trajectory.py b/cartpole/control/trajectory.py deleted file mode 100644 index b5f33d4..0000000 --- a/cartpole/control/trajectory.py +++ /dev/null @@ -1,86 +0,0 @@ -import pydrake - -from pydrake.solvers.mathematicalprogram import Solve -from pydrake.systems.primitives import Linearize -from pydrake.systems.trajectory_optimization import DirectCollocation -from pydrake.trajectories import PiecewisePolynomial - -from cartpole.common import Config, Error, State -from cartpole.simulator.pydrake.system import CartPoleSystem - -import math -import numpy - - -def build_trajectory(config, initial_state, sample_n=100, max_duration=10): - system = CartPoleSystem() - context = system.CreateContext(config, initial_state.as_array()) - - program = DirectCollocation( - system, - context, - num_time_samples=sample_n, - minimum_timestep=0.001, - maximum_timestep=0.1, - input_port_index=system.get_input_port().get_index()) - - program.AddEqualTimeIntervalsConstraints() - program.AddDurationBounds(0, max_duration) - - program.prog().AddBoundingBoxConstraint( - initial_state.as_array(), - initial_state.as_array(), - program.initial_state()) - - target_x_max = config.max_position * 0.75 - - program.prog().AddBoundingBoxConstraint( - [-target_x_max, math.pi, 0.0, 0.0], - [+target_x_max, math.pi, 0.0, 0.0], - program.final_state()) - - q = program.state() - x, a, v, w = q[0], q[1], q[2], q[3] - - program.AddConstraintToAllKnotPoints(-config.max_position <= x) - program.AddConstraintToAllKnotPoints(x <= +config.max_position) - - program.AddConstraintToAllKnotPoints(-config.max_velocity <= v) - program.AddConstraintToAllKnotPoints(v <= +config.max_velocity) - - u = program.input()[0] - program.AddConstraintToAllKnotPoints(-config.max_acceleration <= u) - program.AddConstraintToAllKnotPoints(u <= config.max_acceleration) - - program.AddRunningCost(u**2) - program.AddRunningCost(program.time()) - # program.AddFinalCost(u**2) - program.AddFinalCost(x**2) - - result = Solve(program.prog()) - assert result.is_success(), 'Impossible find trajectory' - - targets = program.ReconstructInputTrajectory(result) - states = program.ReconstructStateTrajectory(result) - - return states, targets - -class Trajectory: - def __init__(self, config, initial_state, sample_n=100, max_duration=5): - states, targets = build_trajectory(config, initial_state, sample_n, max_duration) - self.states = states - self.targets = targets - self.duration = targets.end_time() - targets.start_time() - - def sample(self, sample_n): - time_steps = numpy.linspace(self.states.start_time(), self.states.end_time(), sample_n) - state_values = self.states.vector_values(time_steps).transpose() - target_values = self.targets.vector_values(time_steps).transpose() - - return time_steps, state_values, target_values - - def __call__(self, timestamp): - state = self.states.value(timestamp) - target = self.targets.value(timestamp) - - return State.from_array(state), target[0] diff --git a/cartpole/eval.py b/cartpole/eval.py new file mode 100644 index 0000000..994eb6b --- /dev/null +++ b/cartpole/eval.py @@ -0,0 +1,133 @@ +from cartpole import State, Target, Parameters + +import casadi as cs + + +def find_parameters(states, gravity=9.81) -> Parameters: + ''' + Find dynamics parameters from given control sequence and state trajectory. + Use collocation method to solve nonlinear optimization problem (Hermit-Simpson method). + + Args: + state: cartpole trajectory. + + gravity: gravity constant. + + Returns: + Estimated dynamics parameters. + ''' + + assert len(states) > 1 + + + # For more information see: + # https://cartpole.robotics-lab.ru/3.0.0/dynamics-and-control + + # declare model variables + b = cs.SX.sym('b') + k = cs.SX.sym('k') + + # state variables, use only theta and theta_dot for collocation + theta = cs.SX.sym('theta') + theta_dot = cs.SX.sym('theta_dot') + q = cs.vertcat(theta, theta_dot) + + # control variables + u = cs.SX.sym('u') + + # system dynamics + q_dot = cs.vertcat( + theta_dot, + -b * theta_dot - k * (u * cs.cos(theta) + gravity * cs.sin(theta)) + ) + + F = cs.Function('f', [q, u, b, k], [q_dot], ['q', 'u', 'b', 'k'], ['q_dot']) + + x, x0 = [], [] + x_min, x_max = [], [] + g = [] + g_min, g_max = [], [] + J = 0 + + # add decision variables + eps = 1e-6 + + b = cs.MX.sym('b') + x.append(b) + x0.append(eps) + x_min.append(0) + x_max.append(cs.inf) + + k = cs.MX.sym('k') + x.append(k) + x0.append(eps) + x_min.append(0) + x_max.append(cs.inf) + + q_prev = None + f_prev = None + s_prev = None + + for i in range(0, len(states)-1): + s = states[i] + + q = cs.MX.sym(f'q_{i:03d}', 2) + x.append(q) + x0 += [s.pole_angle, s.pole_angular_velocity] + + x_min += [-cs.inf, -cs.inf] + x_max += [cs.inf, cs.inf] + + # minimize error of predicted state with dynamics model and measured state + q_true = cs.vertcat(s.pole_angle, s.pole_angular_velocity) + J += cs.sumsqr(q - q_true) + + f = F(q, s.cart_acceleration, b, k) + + # Hermite-Simpson collocation method + if q_prev is not None and f_prev is not None and s_prev is not None: + q_c = cs.MX.sym(f'qc_{i:03d}', 2) + x.append(q_c) + x0 += [s_prev.pole_angle, s_prev.pole_angular_velocity] + x_min += [-cs.inf, -cs.inf] + x_max += [cs.inf, cs.inf] + + h = s.stamp - s_prev.stamp + f_c = F(q_c, s_prev.cart_acceleration, b, k) + + g.append(h / 6 * (f_prev + 4 * f_c + f) - (q - q_prev)) + g_min += [0, 0] + g_max += [0, 0] + + g.append((q_prev + q)/2 + h/8 * (f - f_prev) - q_c) + g_min += [0, 0] + g_max += [0, 0] + + q_prev = q + f_prev = f + s_prev = s + + # Create an NLP solver + x = cs.vertcat(*x) + g = cs.vertcat(*g) + + nlp = { + 'x': x, # decision variables + 'f': J, # objective function + 'g': g, # constraints + } + + opts = { + 'ipopt.print_level':0, + 'print_time':0 + } + + solver = cs.nlpsol('solver', 'ipopt', nlp, opts) + + # solve + solution = solver(x0=x0, lbx=x_min, ubx=x_max, lbg=g_min, ubg=g_max) + + b = float(solution['x'][0]) + k = float(solution['x'][1]) + + return Parameters(friction_coef=b, mass_coef=k, gravity=gravity) diff --git a/cartpole/log.py b/cartpole/log.py new file mode 100644 index 0000000..1cbf678 --- /dev/null +++ b/cartpole/log.py @@ -0,0 +1,791 @@ +import asyncio +import atexit +import enum +import json +import logging +import time + +from threading import Event, Thread +from foxglove_websocket.server import FoxgloveServer +from mcap.writer import CompressionType, Writer +from pydantic import BaseModel +from typing import Any, Dict + + +class Level(enum.IntEnum): + """ + Classic log levels: `UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL` + """ + + UNKNOWN = 0 + DEBUG = 1 + INFO = 2 + WARNING = 3 + ERROR = 4 + FATAL = 5 + +def pylog_level(level: Level) -> int: + """ + Convert log level from foxglove to python + """ + + if level == Level.UNKNOWN: + return logging.NOTSET + elif level == Level.DEBUG: + return logging.DEBUG + elif level == Level.INFO: + return logging.INFO + elif level == Level.WARNING: + return logging.WARNING + elif level == Level.ERROR: + return logging.ERROR + elif level == Level.FATAL: + return logging.CRITICAL + else: + raise ValueError(f'Unknown log level {level}') + + +FOXGLOVE_LOG_TOPIC = "`/log`" + +FOXGLOVE_LOG_MSG_TYPE = 'foxglove.Log' + +FOXGLOVE_LOGM_SG_SCHEMA = ''' +{ + "title": "foxglove.Log", + "description": "A log message", + "$comment": "Generated by https://github.com/foxglove/schemas", + "type": "object", + "properties": { + "timestamp": { + "type": "object", + "title": "time", + "properties": { + "sec": { + "type": "integer", + "minimum": 0 + }, + "nsec": { + "type": "integer", + "minimum": 0, + "maximum": 999999999 + } + }, + "description": "Timestamp of log message" + }, + "level": { + "title": "foxglove.Level", + "description": "Log level", + "oneOf": [ + { + "title": "UNKNOWN", + "const": 0 + }, + { + "title": "DEBUG", + "const": 1 + }, + { + "title": "INFO", + "const": 2 + }, + { + "title": "WARNING", + "const": 3 + }, + { + "title": "ERROR", + "const": 4 + }, + { + "title": "FATAL", + "const": 5 + } + ] + }, + "message": { + "type": "string", + "description": "Log message" + }, + "name": { + "type": "string", + "description": "Process or node name" + }, + "file": { + "type": "string", + "description": "Filename" + }, + "line": { + "type": "integer", + "minimum": 0, + "description": "Line number in the file" + } + } +} +''' + + +NANO: int = 1000000000 + + +def to_ns(t: float) -> int: + ''' + Convert time in seconds (float) to nanoseconds (int) + ''' + return int(t * NANO) + + +def to_stamp(t: int) -> tuple[int, int]: + ''' + Convert time in nanoseconds to (seconds, nanoseconds). + ''' + return (t // NANO, t % NANO) + + +def this_or_now(t: float|None) -> float: + ''' + Return provided time or current time + ''' + return t if t is not None else time.time() + + +class Registration(BaseModel): + name: str + channel_id: int + + +def get_pylogger(name: str, level: Level) -> logging.Logger: + """ + Create python or get existing logger. Log Level is translated from foxglove to python. + + Parameters + ---------- + name: str + logger name + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + logger = logging.getLogger(name) + logger.setLevel(pylog_level(level)) + + # naive check that logger is configured + if not logger.hasHandlers(): + handler = logging.StreamHandler() + handler.setFormatter(logging.Formatter("[%(name)s] [%(levelname)s] %(message)s")) + logger.addHandler(handler) + + return logger + + +class MCAPLogger: + """ + Logger to mcap file. + + Example + ------- + ```python + with MCAPLogger(log_path='log.mcap') as log: + obj = ... # some pydantic object + log.publish('/topic', obj, stamp) + log.info('message') + ``` + + """ + + def __init__(self, log_path: str, level: Level=Level.INFO, compress=True): + """ + Parameters + ---------- + log_path: str + path to mcap log file + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + + compress: bool + enable compression + """ + + self._pylog = get_pylogger('cartpole.mcap', level) + + self._writer = Writer( + open(log_path, "wb"), + compression=CompressionType.ZSTD if compress else CompressionType.NONE, + ) + + self._writer.start() + self._topic_to_registration: Dict[str, Registration] = {} + + # preventive topic creation + self.registration_log = self._register( + FOXGLOVE_LOG_TOPIC, + FOXGLOVE_LOG_MSG_TYPE, + FOXGLOVE_LOGM_SG_SCHEMA) + + def __enter__(self): + return self + + def _register(self, topic_name: str, name: str, schema: str) -> Registration: + if topic_name in self._topic_to_registration: + cached = self._topic_to_registration[topic_name] + assert cached.name == name, f'Topic {topic_name} registered with {cached.name}' + return cached + + schema_id = self._writer.register_schema( + name=name, + encoding="jsonschema", + data=schema.encode()) + + channel_id = self._writer.register_channel( + schema_id=schema_id, + topic=topic_name, + message_encoding="json") + + cached = Registration(name=name, channel_id=channel_id) + self._topic_to_registration[topic_name] = cached + self._pylog.debug('id=%i topic=\'%s\', type=\'%s\'', channel_id, topic_name, name) + + return cached + + def _register_class(self, topic_name: str, cls: Any) -> Registration: + name = cls.__name__ + assert issubclass(cls, BaseModel), 'Required pydantic model, but got {name}' + return self._register(topic_name, name, json.dumps(cls.model_json_schema())) + + def publish(self, topic_name: str, obj: BaseModel, stamp: float) -> None: + """ + Publish object to topic. + + Parameters: + ----------- + topic_name: + topic name + obj: Any + object to dump (pydantic model) + stamp: float + timestamp in nanoseconds (float) + """ + + registation = self._register_class(topic_name, type(obj)) + self._writer.add_message( + channel_id=registation.channel_id, + log_time=to_ns(stamp), + data=obj.model_dump_json().encode(), + publish_time=to_ns(stamp), + ) + + def log(self, msg: str, stamp: float, level: Level) -> None: + """ + Print message to topic `/log`. + + Parameters: + ----------- + msg: str + message to print + stamp: float + timestamp in nanoseconds (float) + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + sec, nsec = to_stamp(stamp) + stamp_ns = to_ns(stamp) + + obj = { + "timestamp": {"sec": sec, "nsec": nsec}, + "level": int(level), + "message": msg, + "name": "cartpole", + "file": "/dev/null", + "line": 0 + } + + self._writer.add_message( + channel_id=self.registration_log.channel_id, + log_time=stamp_ns, + data=json.dumps(obj).encode(), + publish_time=stamp_ns) + + def debug(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `DEBUG` level. + """ + self.log(msg, stamp, Level.DEBUG) + + def info(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `INFO` level. + """ + self.log(msg, stamp, Level.INFO) + + def warning(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `WARNING` level. + """ + self.log(msg, stamp, Level.WARNING) + + def error(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `ERROR` level. + """ + self.log(msg, stamp, Level.ERROR) + + def fatal(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `FATAL` level. + """ + self.log(msg, stamp, Level.FATAL) + + def close(self): + """ + Free log resources. + """ + self._writer.finish() + + def __exit__(self, exc_type, exc_value, traceback): + self.close() + + +async def _foxglove_async_entrypoint(queue: asyncio.Queue, stop: Event, level: Level) -> None: + logger = get_pylogger('cartpole.foxglove', level) + + async with FoxgloveServer("0.0.0.0", 8765, "CartPole", logger=logger) as server: + topic_to_registration = {} + + async def register(topic_name, name, schema) -> Registration: + if topic_name in topic_to_registration: + cached = topic_to_registration[topic_name] + assert cached.name == name, f'Topic {topic_name} registered with {cached.name}' + return cached + + spec = { + "topic": topic_name, + "encoding": "json", + "schemaName": name, + "schema": schema, + } + + channel_id = await server.add_channel(spec) + cached = Registration(name=name, channel_id=channel_id) + topic_to_registration[topic_name] = cached + + logger.debug('id=%i topic=\'%s\', type=\'%s\'', channel_id, topic_name, name) + return cached + + + async def register_class(topic_name, cls) -> Registration: + name = cls.__name__ + assert issubclass(cls, BaseModel), f'Required pydantic model, but got {name}' + return await register(topic_name, name, cls.model_json_schema()) + + # preventive topic creation + registration_log = await register( + FOXGLOVE_LOG_TOPIC, + FOXGLOVE_LOG_MSG_TYPE, + FOXGLOVE_LOGM_SG_SCHEMA) + + while not stop.is_set(): + try: + topic_name, stamp, obj = await asyncio.wait_for(queue.get(), timeout=0.2) + + if topic_name == FOXGLOVE_LOG_TOPIC: + # special logic for logs + assert isinstance(obj, str), f'Expected string, but got {type(obj)}' + registration = registration_log + sec, nsec = to_stamp(stamp) + + msg = { + "timestamp": {"sec": sec, "nsec": nsec}, + "level": int(level), + "message": obj, + "name": "cartpole", + "file": "/dev/null", + "line": 0 + } + + data = json.dumps(msg).encode() + else: + registration = await register_class(topic_name, type(obj)) + data = obj.model_dump_json().encode() + + await server.send_message(registration.channel_id, to_ns(stamp), data) + + except asyncio.TimeoutError: + pass + + +async def _foxglove_async_wrapping( + input_queue: asyncio.Queue, + stop: Event, + exception_queue: asyncio.Queue, + level: int) -> None: + try: + await _foxglove_async_entrypoint(input_queue, stop, level) + except Exception as e: + await exception_queue.put(e) + + +def foxglove_main( + loop: asyncio.AbstractEventLoop, + input_queue: asyncio.Queue, + stop: Event, + exception_queue: asyncio.Queue, + level: int) -> None: + asyncio.set_event_loop(loop) + loop.run_until_complete(_foxglove_async_wrapping(input_queue, stop, exception_queue, level)) + + +class FoxgloveWebsocketLogger: + """ + Logger to foxglove websocket, messages are available in real time. + Class will start new thread with asyncio event loop. + + Example + ------- + ``` + with FoxgloveWebsocketLogger() as log: + obj = ... # some pydantic object + log.publish('/topic', obj, stamp) + log.info('message') + ``` + """ + + def __init__(self, level: int = Level.INFO): + """ + Parameters + ---------- + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + self._loop = asyncio.new_event_loop() + self._input_queue = asyncio.Queue() + self._exception_queue = asyncio.Queue() + self._stop = Event() + + args = (self._loop, self._input_queue, self._stop, self._exception_queue, level) + + self._foxlgove_thread = Thread( + target=foxglove_main, + name='foxglove_main_loop', + daemon=True, + args=args) + + self._foxlgove_thread.start() + + def __enter__(self): + return self + + def publish(self, topic_name: str, obj: BaseModel, stamp: float) -> None: + """ + Publish object to topic. + + Parameters + ---------- + topic_name: str + topic name + obj: BaseModel + object to dump (pydantic model) + stamp: float + timestamp in nanoseconds (float) + """ + + if not (self._loop.is_running() and self._foxlgove_thread.is_alive()): + if not self._exception_queue.empty(): + raise self._exception_queue.get_nowait() + + raise AssertionError('Foxglove logger is not running') + + item = (topic_name, stamp, obj) + asyncio.run_coroutine_threadsafe(self._input_queue.put(item), self._loop) + + def log(self, msg: str, stamp: float, level: int) -> None: + """ + Print message to topic `/log`. + + Parameters + ---------- + msg: str + message to print + stamp: float + timestamp in nanoseconds (float) + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + self.publish("`/log`", msg, stamp) + + def debug(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `DEBUG` level. + """ + self.log(msg, stamp, Level.DEBUG) + + def info(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `INFO` level. + """ + self.log(msg, stamp, Level.INFO) + + def warning(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `WARNING` level. + """ + self.log(msg, stamp, Level.WARNING) + + def error(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `ERROR` level. + """ + self.log(msg, stamp, Level.ERROR) + + def fatal(self, msg: str, stamp: float) -> None: + """ + Print message to topic `/log` with `FATAL` level. + """ + self.log(msg, stamp, Level.FATAL) + + def close(self): + """ + Free log resources. + """ + + self._stop.set() + self._foxlgove_thread.join() + + def __exit__(self, exc_type, exc_value, traceback): + self.close() + + +class Logger: + """ + Compound Logger class that logs to console, foxglove and mcap. + + Example + ------- + ``` + with Logger(log_path='log.mcap', level=INFO) as log: + obj = ... # some pydantic object + + log.publish('/topic', obj) + log.info('message') + ``` + """ + + def __init__(self, log_path: str = '', level: Level = Level.INFO): + """ + Parameters + ---------- + log_path: str + path to mcap log file, if not provided, no mcap log will be created + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + self._pylog = get_pylogger('cartpole', level) + self._foxglove_log = FoxgloveWebsocketLogger() + self._mcap_log = None + + if log_path: + self._mcap_log = MCAPLogger(log_path, level=level) + + def publish(self, topic_name: str, obj: BaseModel, stamp: float) -> None: + """ + Parameters + ---------- + topic_name: str + topic name + obj: BaseModel + pydantic object + stamp: float + timestamp in nanoseconds (float), if not provided, current time used + """ + + if self._mcap_log: + self._mcap_log.publish(topic_name, obj, stamp) + + self._foxglove_log.publish(topic_name, obj, stamp) + + def log(self, msg: str, stamp: float, level: Level = Level.INFO) -> None: + """ + Print message to console and topic `/log`. + + Parameters + ---------- + msg: str + message to print + stamp: float + timestamp in nanoseconds (float), if not provided, current time used + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + self._pylog.log(pylog_level(level), f'{stamp:.3f}: {msg}') + self._foxglove_log.log(msg, stamp, level) + + if self._mcap_log: + self._mcap_log.log(msg, stamp, level) + + def debug(self, msg: str, stamp: float) -> None: + """ + Print message to console and topic `/log` with `DEBUG` level. + """ + self.info(msg, stamp, Level.DEBUG) + + def info(self, msg: str, stamp: float) -> None: + """ + Print message to console and topic `/log` with `INFO` level. + """ + self.log(msg, stamp, Level.INFO) + + def warning(self, msg: str, stamp: float) -> None: + """ + Print message to console and topic `/log` with `WARNING` level. + """ + self.log(msg, stamp, Level.WARNING) + + def error(self, msg: str, stamp: float) -> None: + """ + Print message to console and topic `/log` with `ERROR` level. + """ + self.log(msg, stamp, Level.ERROR) + + def fatal(self, msg: str, stamp: float) -> None: + """ + Print message to console and topic `/log` with `FATAL` level. + """ + self.log(msg, stamp, Level.FATAL) + + def close(self): + """ + Free log resources. + """ + + self._foxglove_log.close() + if self._mcap_log: + self._mcap_log.close() + + def __exit__(self): + self.close() + + +__logger = None + + +def setup(log_path: str = '', level: Level = Level.INFO) -> None: + """ + Setup gloval logger. + + Parameters + ---------- + log_path: str + path to mcap log file, if not provided, no mcap log will be created + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + global __logger + close() + __logger = Logger(log_path=log_path, level=level) + + +def close(): + """ + Close global logger + """ + + global __logger + + if __logger: + __logger.close() + __logger = None + + +atexit.register(close) + + +def get_logger() -> Logger: + """ + Get global logger instance + """ + + global __logger + if not __logger: + setup() + + return __logger + + +def publish(topic_name: str, obj: BaseModel, stamp: float|None = None) -> None: + """ + Publish object to topic of global logger. + If logger is not set, it will be created with default settings. + + Parameters + ---------- + topic_name: str + topic name + obj: BaseModel + pydantic model + stamp: float + timestamp in nanoseconds (float), if not provided, current time used + """ + + get_logger().publish(topic_name, obj, this_or_now(stamp)) + + +def log(msg: str, stamp: float|None = None, level: Level = Level.INFO) -> None: + """ + Print message to console and topic `/log`. + If logger is not set, it will be created with default settings. + + Parameters + ---------- + msg: str + message to print + stamp: float + timestamp in nanoseconds (float), if not provided, current time used + level: Level + log level (`UNKNOWN`, `DEBUG`, `INFO`, `WARNING`, `ERROR`, `FATAL`) + """ + + get_logger().log(msg, this_or_now(stamp), level) + + +def debug(msg: str, stamp: float|None = None) -> None: + """ + Print message to console and topic `/log` with `DEBUG` level. + If logger is not set, it will be created with default settings. + """ + log(msg, stamp, Level.DEBUG) + + +def info(msg: str, stamp: float|None = None) -> None: + """ + Print message to console and topic `/log` with `INFO` level. + If logger is not set, it will be created with default settings. + """ + log(msg, stamp, Level.INFO) + + +def warning(msg: str, stamp: float|None = None) -> None: + """ + Print message to console and topic `/log` with `WARNING` level. + If logger is not set, it will be created with default settings. + """ + log(msg, stamp, Level.WARNING) + + +def error(msg: str, stamp: float|None = None) -> None: + """ + Print message to console and topic `/log` with `ERROR` level. + If logger is not set, it will be created with default settings. + """ + log(msg, stamp, Level.ERROR) + + +def fatal(msg: str, stamp: float|None = None) -> None: + """ + Print message to console and topic `/log` with `FATAL` level. + If logger is not set, it will be created with default settings. + """ + log(msg, stamp, Level.FATAL) diff --git a/cartpole/lqr.py b/cartpole/lqr.py new file mode 100644 index 0000000..2ddf31f --- /dev/null +++ b/cartpole/lqr.py @@ -0,0 +1,96 @@ +from cartpole.common import Actor, Config, Limits, Parameters, State, Target +from pydantic import BaseModel +from scipy.linalg import solve_continuous_are + +import numpy as np + + +def clamp(x, min_x, max_x): + return min(max_x, max(min_x, x)) + +class LQRBalancerParams(BaseModel): + ''' + LQR parameters. + + Q matrix: + * cart_position_cost + * pole_angle_cost + * cart_velocity_cost + * pole_angular_velocity_cost + + R matrix: + * cart_acceleration_cost + ''' + + cart_position_cost: float = 0.0 + cart_velocity_cost: float = 0.0 + cart_acceleration_cost: float = 0.0 + + pole_angle_cost: float = 0.0 + pole_angular_velocity_cost: float = 0.0 + +class LQRBalancer(Actor): + ''' + LQR-based pole balancer actor at the unstable equilibrium point. + + Equlibrium point: + * cart_position = 0 + * pole_angle = PI + * cart_velocity = 0 + * pole_angular_velocity = 0 + + For more information see: + https://en.wikipedia.org/wiki/Linear-quadratic_regulator + ''' + + def __init__(self, config: Config, lqr_params: LQRBalancerParams): + self._config = config + self._lqr_params = lqr_params + + k = config.parameters.mass_coef + b = config.parameters.friction_coef + g = config.parameters.gravity + + A = np.array([ + [0, 0, 1, 0], + [0, 0, 0, 1], + [0, 0, 0, 0], + [0, k*g, 0, -b], + ]) + + B = np.array([[0], [0], [1], [k]]) + + Q = np.diag([ + params.cart_position_cost, + params.pole_angle_cost, + params.cart_velocity_cost, + params.pole_angular_velocity_cost, + ]) + + R = np.array([ + [params.cart_acceleration_cost] + ]) + + P = solve_continuous_are(A, B, Q, R) + + self.control = -np.linalg.inv(R) @ B.T @ P + self.target = State( + cart_position=0, + cart_velocity=0, + pole_angle=np.pi, + pole_angular_velocity=0, + ) + + def __call__(self, state: State) -> Target: + ''' + Calculate control action for the given state. + ''' + + error = state.numpy4() - taget.numpy4() + + acceleration = clamp( + self.control @ error, + -self._config.control_limit.cart_acceleration, + +self._config.control_limit.cart_acceleration) + + return Target(acceleration=acceleration) diff --git a/cartpole/sessions/__init__.py b/cartpole/sessions/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/cartpole/sessions/actor.py b/cartpole/sessions/actor.py deleted file mode 100644 index bb73d97..0000000 --- a/cartpole/sessions/actor.py +++ /dev/null @@ -1,12 +0,0 @@ -from cartpole.common.interface import State - - -class Actor: - '''Base class for cartpole control algorithms''' - - def __init__(self, **_): - '''Implement this to use extra params (kwargs) for your algorithm''' - pass - - def __call__(self, state: State, stamp: float = None) -> float: - raise NotImplementedError diff --git a/cartpole/sessions/collector.py b/cartpole/sessions/collector.py deleted file mode 100644 index 03ddd77..0000000 --- a/cartpole/sessions/collector.py +++ /dev/null @@ -1,321 +0,0 @@ -import copy -import dataclasses as dc -import json -import logging -from pathlib import Path - -import numpy as np -import inspect -import string -import threading -import time -from contextlib import contextmanager -from collections import defaultdict -from io import StringIO -from typing import Callable, List, Dict, Type, Tuple, Union -import dacite - -from cartpole.common.interface import CartPoleBase, Config, State -from cartpole.common.util import init_logging -from cartpole.sessions.actor import Actor - - -LOGGER = logging.getLogger(__name__) -HEX_DIGITS = list(string.digits + string.ascii_lowercase[:6]) - - -def generate_id(size: int = 6): - return ''.join(np.random.choice(HEX_DIGITS, size=size, replace=True)) - - -class Units: - METERS = 'm' - METERS_PER_SECOND = 'm/s' - METERS_PER_SECOND_SQUARED = 'm/s^2' - RADIANS = 'rad' - RADIANS_PER_SECOND = 'rad/s' - UNKNOWN = '?' - - -@dc.dataclass -class SessionData: - @dc.dataclass - class SessionMeta: - session_id: str = dc.field(default_factory=generate_id) - name: str = None - start_timestamp: int = None - duration: int = None - device_class: str = None - device_config: Config = None - actor_class: str = None - actor_config: dict = None - - @dc.dataclass - class Log: - timestamp: int - message: str - - @dc.dataclass - class Value: - id: str - name: str - unit: str - x: List[float] = dc.field(default_factory=list, repr=False) - y: List[float] = dc.field(default_factory=list, repr=False) - - @dc.dataclass - class Group: - name: str - values: List[str] = dc.field(default_factory=list) - - @dc.dataclass - class Style: - name: str - # todo - - @dc.dataclass - class TimeTrace: - action: str - start_timestamp: int - end_timestamp: int = None - - meta: SessionMeta = dc.field(default_factory=SessionMeta) - values: Dict[str, Value] = dc.field(default_factory=dict) - groups: List[Group] = dc.field(default_factory=list) - logs: List[Log] = dc.field(default_factory=list) - time_traces: List[TimeTrace] = dc.field(default_factory=list) - - # def __post_init__(self) -> None: - # V = SessionData.Value - # values = [ - # V(id='state.position', name='position', unit=Units.METERS), - # V(id='state.velocity', name='velocity', unit=Units.METERS_PER_SECOND), - # V(id='state.acceleration', name='acceleration', unit=Units.METERS_PER_SECOND_SQUARED), - # V(id='state.pole_angle', name='angle', unit=Units.RADIANS), - # V(id='state.pole_velocity', name='angle', unit=Units.RADIANS_PER_SECOND), - # V(id='target.acceleration', name='acceleration', unit=Units.RADIANS_PER_SECOND), - # ] - # self.values = {v.id: v for v in values} - # self.groups = [ - # # todo - # ] - - @classmethod - def load(cls, path: Union[str, Path]) -> 'SessionData': - with open(path) as file: - raw_data = json.load(file) - parse_config = dacite.Config(check_types=False) - return dacite.from_dict(SessionData, raw_data, parse_config) - - -class CollectorProxy(CartPoleBase): - LOGGING_FORMAT = ( - '%(created)f [%(levelname)s] %(name)s (%(filename)s:%(lineno)d) :: %(message)s' - ) - HUMAN_LOGGING_FORMAT = '%(asctime)s [%(levelname)s] %(name)s :: %(message)s' - DEFAULT_SAVE_PATH = 'data/sessions' - - def __init__( - self, - cart_pole: CartPoleBase, - actor_class: Type[Actor], - actor_config: dict, - reset_callbacks: List[Callable] = None, - close_callbacks: List[Callable] = None, - ) -> None: - self.cart_pole = cart_pole - self.actor_class = actor_class - self.actor_config = actor_config - self.data: SessionData = None - self.reset_callbacks = reset_callbacks or [] - self.close_callbacks = close_callbacks or [] - - self._locks = defaultdict(threading.Lock) - self._consumed_offset = defaultdict(int) - self._started_flag = threading.Event() - self._available_values = threading.Semaphore(0) - self._start_perf_timestamp = None - - def _timestamp(self): - return time.perf_counter_ns() // 1000 - self._start_perf_timestamp - - def save(self, path=None) -> Path: - if path is None: - path = Path(self.DEFAULT_SAVE_PATH) / f'{self.data.meta.session_id}.json' - path = Path(path) - path.parent.mkdir(parents=True, exist_ok=True) - with open(path, 'w') as f: - json.dump(dc.asdict(self.data), f) - LOGGER.info('Saved session %s to %s', self.data.meta.session_id, path) - return path - - @contextmanager - def time_trace(self, action=None): - if action is None: - stack = inspect.stack() - action = stack[1][3] if stack[1][3] != '__enter__' else stack[2][3] - trace = SessionData.TimeTrace(action=action, start_timestamp=self._timestamp()) - yield trace - trace.finish_timestamp = self._timestamp() - self.data.time_traces.append(trace) - - def _add_value(self, key, x, y): - with self._locks[key]: - if key not in self.data.values: - self.data.values[key] = SessionData.Value( - id=key, name=key, unit=Units.UNKNOWN - ) - value = self.data.values[key] - value.x.append(x) - value.y.append(y) - - if self._consumed_offset[key] == len(value.x) - 1: - self._available_values.release() - - def _init_logging(self): - init_logging() - self._logging_stream = StringIO() - self._logging_handler = logging.StreamHandler() - self._logging_handler.setStream(self._logging_stream) - self._logging_handler.setLevel(logging.DEBUG) - self._logging_handler.setFormatter(logging.Formatter(self.LOGGING_FORMAT)) - logging.getLogger().addHandler(self._logging_handler) - - def _cleanup_logging(self): - logging.getLogger().removeHandler(self._logging_handler) - self._logging_handler.flush() - - log_lines = self._logging_stream.getvalue().splitlines(keepends=False) - timestamp = 0 - for line in log_lines: - try: - time, message = line.split(' ', 1) - timestamp = int(float(time) * 1000000) - self.data.logs.append(SessionData.Log(timestamp=timestamp, message=message)) - except ValueError: # on float conversion - if len(self.data.logs) > 0: - self.data.logs[-1].message += '\n' + message - - self._logging_stream.close() - LOGGER.debug("Collected %s log messages", len(log_lines)) - - def reset(self, config: Config) -> None: - self.data = SessionData(meta=SessionData.SessionMeta( - device_class=self.cart_pole.__class__.__name__, - device_config=config, - actor_class=self.actor_class.__name__, - actor_config=self.actor_config, - )) - self._available_values = threading.Semaphore(0) - self._init_logging() - - self.cart_pole.reset(config) - for callback in self.reset_callbacks: - callback() - self.data.meta.start_timestamp = time.time() - self._start_perf_timestamp = time.perf_counter_ns() // 1000 - self._started_flag.set() - - def get_state(self) -> State: - with self.time_trace() as trace: - state = self.cart_pole.get_state() - - for field in dc.fields(state): - key = f'state.{field.name}' - value = getattr(state, field.name) - if value is None: - continue - - self._add_value(key, trace.start_timestamp, value) - - LOGGER.info(f"Get state: {state}") - return state - - def get_info(self) -> dict: - with self.time_trace(): - return self.cart_pole.get_info() - - def get_target(self) -> float: - with self.time_trace(): - return self.cart_pole.get_target() - - def set_target(self, target: float) -> None: - with self.time_trace() as trace: - key = 'target.acceleration' - self._add_value(key, trace.start_timestamp, target) - LOGGER.info(f"Set target: {target}") - return self.cart_pole.set_target(target) - - def timestamp(self): - return self.cart_pole.timestamp() - - def close(self) -> None: - with self.time_trace(): - self.cart_pole.close() - self.data.meta.duration = self._timestamp() - for callback in self.close_callbacks: - callback() - self._cleanup_logging() - # self.save() - self._started_flag.clear() - - def meta(self) -> dict: - if not self._started_flag.is_set(): - raise RuntimeError('Session has not started yet') - return dc.asdict(self.data) - - def consume_value(self) -> Tuple[dict, bool]: - while True: - if not self._started_flag.is_set(): - raise ValueError('Session has finished') - if self._available_values.acquire(timeout=1.0): - break - for key, value in self.data.values.items(): - offset = self._consumed_offset[key] - if offset == len(value.x): - continue - - with self._locks[key]: - vc = copy.deepcopy(value) - vc.x = vc.x[offset:] - vc.y = vc.y[offset:] - self._consumed_offset[key] = len(value.x) - return dc.asdict(vc) - - -if __name__ == '__main__': - class FakeCartPole(CartPoleBase): - def reset(self, config: Config) -> None: - pass - - def get_state(self) -> State: - return State(position=1) - - def set_target(self, target: float) -> None: - pass - - def close(self) -> None: - pass - - class FakeActor(Actor): - pass - - logging.getLogger().setLevel(logging.DEBUG) - c = CollectorProxy(FakeCartPole(), FakeActor, {}) - print() - c.reset(Config()) - time.sleep(2) - c.set_target(1) - time.sleep(2) - c.set_target(2) - time.sleep(1) - c.set_target(3) - - print(c._available_values._value) - print(c.consume_value()) - print(c._available_values._value) - - c.close() - c.reset(Config()) - time.sleep(5) - c.close() diff --git a/cartpole/sessions/runner.py b/cartpole/sessions/runner.py deleted file mode 100644 index c127a65..0000000 --- a/cartpole/sessions/runner.py +++ /dev/null @@ -1,47 +0,0 @@ -from cartpole.common.interface import CartPoleBase -import logging -from typing import Type -from cartpole.sessions.actor import Actor -from cartpole.sessions.collector import CollectorProxy -from web_view import server - - -LOGGER = logging.getLogger(__name__) - - -class Runner: - def __init__( - self, - cart_pole: CartPoleBase, - cart_pole_config: dict, - actor_class: Type[Actor], - actor_config: dict, - ) -> None: - self.proxy = CollectorProxy(cart_pole, actor_class, actor_config) - self.cart_pole_config = cart_pole_config - self.actor_class = actor_class - self.actor_config = actor_config - - def run(self, max_iterations: int = -1) -> None: - try: - self.proxy.reset(self.cart_pole_config) - self._loop(max_iterations) - except Exception: - LOGGER.exception('Aborting run due to error') - finally: - self.proxy.close() - LOGGER.info('Run finished') - - def start_server(self) -> None: - server.run_server(self.proxy) - - def _loop(self, max_iterations: int) -> None: - actor = self.actor_class(**self.actor_config) - current_iteration = 0 - while current_iteration != max_iterations: - with self.proxy.time_trace('iteration'): - state = self.proxy.get_state() - target = actor(state) - self.proxy.set_target(target) - self.proxy.make_step() - current_iteration += 1 diff --git a/cartpole/simulator.py b/cartpole/simulator.py new file mode 100644 index 0000000..8ad9e2f --- /dev/null +++ b/cartpole/simulator.py @@ -0,0 +1,261 @@ +from cartpole.common import ( + CartPoleBase, + Config, + Error, + Limits, + Parameters, + State, + Target, +) + +from pydantic import BaseModel +from typing import Any + +import numpy + + +def sgn(x: float) -> int: + if x > 0: + return 1 + elif x < 0: + return -1 + else: + return 0 + + +def snap_zero(x: float, eps: float) -> float: + return 0 if abs(x) < eps else x + + +class SimulatorInfo(BaseModel): + """ + Simulator info. + + Attributes + ---------- + step_count: int + number of simulation steps + integration_count: int + number of integration steps + """ + + step_count: int = 0 + integration_count: int = 0 + + +class Simulator(CartPoleBase): + """ + CartPole simulator (integration implemented using RK4 method). + + For more information see: https://cartpole.robotics-lab.ru/dynamics-and-control + """ + + def __init__(self, integration_step: float = 0.001): + """ + Create simulator with some default config. + + Parameters + ---------- + integration_step: float + integration time step (s) + """ + + # set default config + self._config = Config( + hardware_limit=Limits( + cart_position=0.5, cart_velocity=2.0, cart_acceleration=5.0 + ), + control_limit=Limits(), + parameters=Parameters(g=9.81, b=0, k=0.3), + ) + + self._state = State(error=Error.NEED_RESET) + self._target = Target(velocity=0) + + self._integration_step = integration_step + self._integration_count = 0 + self._step_count = 0 + + def get_config(self) -> Config: + """ + Return current config. + """ + return self._config + + def set_config(self, config: Config) -> None: + """ + Set new config. In case of invalid config, AssertionError is raised. + """ + + assert config.control_limit.stronger(config.hardware_limit) + + assert config.parameters.friction_coef is not None + assert config.parameters.friction_coef >= 0 + + assert config.parameters.mass_coef is not None + assert config.parameters.mass_coef > 0 + + self._config = config + + def _eval_acceleration_by_velocity( + self, velocity: float, eps: float = 1e-6 + ) -> float: + err = velocity - self._state.cart_velocity + + a = self._target.acceleration_or(self._config.control_limit.cart_acceleration) + if abs(err) < a * self._integration_step: + return snap_zero(err / self._integration_step, eps) + + return sgn(err) * a + + def _eval_cart_acceleration(self, eps: float = 1e-6) -> float: + if self._target.position is not None: + a = self._target.acceleration_or( + self._config.control_limit.cart_acceleration + ) + v = self._target.velocity_or(self._config.control_limit.cart_velocity) + err = self._target.position - self._state.cart_position + + # print(f'_eval_cart_acceleration err={err}, v={v}, a={a}, state_v={self._state.cart_velocity}') + if abs(err) < 1e-3: + return self._eval_acceleration_by_velocity(0) + if sgn(err) != sgn(self._state.cart_velocity): + # stoppping to change direction + return self._eval_acceleration_by_velocity(sgn(err) * v) + else: + # bang-bang strategy + a_brake = self._state.cart_velocity**2 / (2 * abs(err)) + # print(f'a_brake = {a_brake}, a = {a}') + if a_brake >= a: + return self._eval_acceleration_by_velocity(0) + else: + return self._eval_acceleration_by_velocity(sgn(err) * v) + + if self._target.velocity is not None: + return self._eval_acceleration_by_velocity(self._target.velocity, eps) + + if self._target.acceleration is not None: + return self._target.acceleration + + raise Exception("At least one of the target is required") + + def _derivative(self, s: numpy.ndarray, a: float) -> numpy.ndarray: + """ + Calculate derivative of the given state (used for integration). + + Parameters + ---------- + s: numpy.ndarray + state vector + a: float + cart acceleration (m/s^2) + + Returns + ------- + :numpy.ndarray + derivative of the given state + """ + + result = numpy.zeros(4) + + b = self._config.parameters.friction_coef + k = self._config.parameters.mass_coef + g = self._config.parameters.gravity + + result[0] = s[2] + result[1] = s[3] + result[2] = a + result[3] = -b * s[3] - k * (a * numpy.cos(s[1]) + g * numpy.sin(s[1])) + + return result + + def reset(self, state: State = State()) -> None: + """ + Reset simulator to the given state. + """ + + self._state = state + self._target = Target(velocity=0) + + self._count = 0 + self._integration_count = 0 + + def get_state(self) -> State: + """ + Return current state. + """ + + return self._state + + def get_info(self) -> SimulatorInfo: + """ + Return current simulator info. + """ + + return SimulatorInfo( + step_count=self._step_count, integration_count=self._integration_count + ) + + def set_target(self, target: Target) -> State: + """ + Set control target and return current state. + """ + + self._target = target + + if not self._state.error: + self._state.cart_acceleration = self._eval_cart_acceleration() + self._state.validate(self._config) + + return self.get_state() + + def advance(self, delta: float) -> None: + """ + Make simulation step of the given length. + For integration, RK4 method is used. + + Parameters + ---------- + delta: float + length of the simulation step (s) + """ + + if self._state.error: + return + + s = self._state.numpy4() + h = self._integration_step + h_2 = h / 2 + + integration_step_n = int(delta / h) + + for _ in range(integration_step_n): + a = self._eval_cart_acceleration() + + k1 = self._derivative(s, a) + k2 = self._derivative(s + k1 * h_2, a) + k3 = self._derivative(s + k2 * h_2, a) + k4 = self._derivative(s + k3 * h, a) + + s += (k1 + 2 * k2 + 2 * k3 + k4) * h / 6 + + self._integration_count += 1 + + self._state = State( + cart_position=s[0], + cart_velocity=s[2], + cart_acceleration=a, + pole_angle=s[1], + pole_angular_velocity=s[3], + stamp=self._integration_step * self._integration_count, + ) + + self._state.validate(self._config) + + self._step_count += 1 + + def close(self) -> None: + """ + Clear any resources used by the simulator. + """ + pass diff --git a/cartpole/simulator/__init__.py b/cartpole/simulator/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/cartpole/simulator/pydrake/__init__.py b/cartpole/simulator/pydrake/__init__.py deleted file mode 100644 index 30d34e1..0000000 --- a/cartpole/simulator/pydrake/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from cartpole.simulator.pydrake.simulator import CartPoleSimulator diff --git a/cartpole/simulator/pydrake/simulator.py b/cartpole/simulator/pydrake/simulator.py deleted file mode 100644 index 140dae0..0000000 --- a/cartpole/simulator/pydrake/simulator.py +++ /dev/null @@ -1,121 +0,0 @@ -from pydrake.systems.analysis import Simulator - -from cartpole.common import CartPoleBase, Error, State -from cartpole.simulator.pydrake.system import CartPoleSystem - -import logging -import numpy - -log = logging.getLogger('simulator') - -def clamp(value, limit): - if value > limit: - return limit, True - - if value < -limit: - return -limit, True - - return value, False - -class CartPoleSimulator(CartPoleBase): - ''' - Description: - Сlass implements a physical simulation of the cart-pole device. - A pole is attached by an joint to a cart, which moves along guide axis. - The pendulum is initially at rest state. The goal is to maintain it in - upright pose by increasing and reducing the cart's velocity. - Source: - This environment is some variation of the cart-pole problem - described by Barto, Sutton, and Anderson - Initial state: - A pole is at starting position 0 with no velocity and acceleration. - Motor simulation: - Current implementation is specified for stepper motor. - It is controlled by discrete velocity changes every time step. - The target is desired acceleration of cart. - Technical details: - Each environment runs its own isolated pybullet physics engine. - ''' - - def __init__(self): - self.system = CartPoleSystem() - self.context = self.system.CreateDefaultContext() - self.simulator = Simulator(self.system, self.context) - self.config = None - self.error = Error.NEED_RESET # Formally, we need reset env to reset error. - self.target_acceleration = 0 - - def reset_to(self, config, state): - self.config = config - self.context = self.system.CreateContext(config, state.as_array()) - self.simulator = Simulator(self.system, self.context) - - self.error = Error.NO_ERROR - self.target_acceleration = 0 - self.system.get_input_port().FixValue(self.context, numpy.array([0])) - - def reset(self, config): - self.reset_to(config, State.home()) - - def get_state(self): - return State.from_array( - self.context.get_continuous_state_vector() - ) - - def get_target(self): - return self.target_acceleration - - def get_config(self): - assert self.config - return self.config - - def set_target(self, target): - if self.error: - log.warning('set target, error=%s', self.error) - return - - config = self.get_config() - - self.target_acceleration, clamped = clamp(target, config.hard_max_acceleration) - self.system.get_input_port().FixValue(self.context, numpy.array([target])) - - if clamped: - self.error = Error.A_OVERFLOW - return - - log.debug('set acc=%.2f', target) - - def validate(self): - state = self.get_state() - config = self.get_config() - - if abs(state.cart_position) > config.hard_max_position: - self.error = Error.X_OVERFLOW - return False - - if abs(state.cart_velocity) > config.hard_max_velocity: - self.error = Error.V_OVERFLOW - return False - - return True - - def advance(self, delta): - if self.error: - log.warning('advance, error=%i', self.error) - return - - self.simulator.AdvanceTo(self.context.get_time() + delta) - - if not self.validate(): - return - - def timestamp(self): - return self.context.get_time() - - def get_info(self): - return { - 'time': self.context.GetTime(), - } - - def close(self): - pass \ No newline at end of file diff --git a/cartpole/simulator/pydrake/system.py b/cartpole/simulator/pydrake/system.py deleted file mode 100644 index f510f9d..0000000 --- a/cartpole/simulator/pydrake/system.py +++ /dev/null @@ -1,73 +0,0 @@ -from pydrake.math import cos, sin -from pydrake.systems.framework import BasicVector_, LeafSystem_ -from pydrake.systems.scalar_conversion import TemplateSystem - -import numpy - -@TemplateSystem.define("CartPoleSystem") -def CartPoleSystem_(T): - """ - Parameters: - g - gravity - l – pole length - - Input: - u - target cart acceleration - - State: - x - cart position - a - pole angle - v - cart velocity - w - pole angular velocity - """ - - class Impl(LeafSystem_[T]): - def _construct(self, converter=None): - LeafSystem_[T].__init__(self, converter=converter) - - parameter_default = BasicVector_[T]([9.8, 0.3]) - self.parameter_index = self.DeclareNumericParameter(parameter_default) - - self.state_index = self.DeclareContinuousState(4) - self.DeclareStateOutputPort('q', self.state_index) - - self.input_index = self.DeclareVectorInputPort('u', 1) - - def _construct_copy(self, other, converter=None): - Impl._construct(self, converter=converter) - - def DoCalcTimeDerivatives(self, context, derivatives): - parameter = context.get_numeric_parameter(self.parameter_index) - g = parameter[0] - l = parameter[1] - - q = context.get_continuous_state_vector() - x = q[0] - a = q[1] - v = q[2] - w = q[3] - - u = self.get_input_port().Eval(context)[0] - - d = derivatives.get_mutable_vector() - d.SetAtIndex(0, v) - d.SetAtIndex(1, w) - d.SetAtIndex(2, u) - d.SetAtIndex(3, -(u * cos(a) + g * sin(a)) / l) - - def CreateContext(self, config, q): - context = self.CreateDefaultContext() - context.SetTime(0) - - params = context.get_mutable_numeric_parameter(self.parameter_index) - params.SetFromVector( - numpy.array([config.gravity, config.pole_length]) - ) - - context.SetContinuousState(q) - - return context - - return Impl - -CartPoleSystem = CartPoleSystem_[float] \ No newline at end of file diff --git a/cartpole/simulator/pytorch/__init__.py b/cartpole/simulator/pytorch/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/cartpole/simulator/pytorch/config.py b/cartpole/simulator/pytorch/config.py deleted file mode 100644 index 0d88531..0000000 --- a/cartpole/simulator/pytorch/config.py +++ /dev/null @@ -1,120 +0,0 @@ -""" -Defines configuration of the system - its limits and physical parameters -""" -from dataclasses import dataclass - -from torch import pi - - -@dataclass -class SystemLimits: - """ - Represents system limits - - Fields - ------ - `max_abs_position` : float - Maximum absolute position of the cart, so the real - position belongs to (-max_abs_position, max_abs_position). - Measured in meters. - - `max_abs_velocity` : float - Maximum absolute velocity of the cart. - Measured in m/s (meters per second). - - `max_abs_angular_velocity` : float - Maximum angular velocity of a pole. - Measured in rad/s (radians per second). - - `max_abs_acceleration` : float - Maximum absolute acceleration of the cart. - Measured in m/s^2 (meters per second squared). - """ - - max_abs_position: float = 0.25 - max_abs_velocity: float = 25.0 - max_abs_angular_velocity: float = 6.0 * pi - max_abs_acceleration: float = 7 - - -@dataclass -class DiscretizationParameters: - """ - This class contains the parameters used for discretization - of state space and time. - - Each field except `simulation_step_n` and `dynamics_steps_per_input - defines the number of samples for each dimension. - `cart_position = 50` would mean that we take 50 equidistant points - from `[-max_abs_position, max_abs_position]`. - - `simulation_step_n` stores the discretization of input times. - Value of `100` would mean that we can change out input 100 times a second. - - `integration_step_n` : int - Shows how many times we calculate dynamics of the system during - one simulation timestep. - We assume the input is the same during the timestep. - Value of 10 would mean that we update the state of the system - 10 times before adjusting the input. - """ - - cart_position: int = 50 - pole_angle: int = 21 - cart_velocity: int = 50 - pole_angular_velocity: int = 126 - cart_acceleration: int = 35 - - simulation_step_n: int = 100 - integration_step_n: int = 10 - - -@dataclass -class SystemParameters: - """ - Represents physical parameters of the system - - Fields - ------ - `pole_length` : float - Length of the pole in meters. - - `pole_mass` : float - Mass of the pole in kg. - - `cart_mass` : float - Mass of the cart in kg. - - `gravity` : float - Gravitational constant, shows the gravitational pull. - Measured in m/s^2 (meters per second squared). - """ - - pole_length: float = 0.3 - pole_mass: float = 0.118 - cart_mass: float = 0 - gravity: float = 9.807 - - -@dataclass -class SystemConfiguration: - """ - Contains physical parameters of the system and its limits. - - Fields - ------ - `parameters` : SystemParameters - Physical parameters of the system. - - `limits` : SystemLimits - Limits of the system, such as maximum position, etc. - - `discretization` : DiscretizationParameters - Parameters of the system which are used for discretization of - continuos space and time. - Basically contains the number of pieces we split each dimension in. - """ - - parameters: SystemParameters = SystemParameters() - limits: SystemLimits = SystemLimits() - discretization: DiscretizationParameters = DiscretizationParameters() diff --git a/cartpole/simulator/pytorch/discreditizer.py b/cartpole/simulator/pytorch/discreditizer.py deleted file mode 100644 index 4bb9985..0000000 --- a/cartpole/simulator/pytorch/discreditizer.py +++ /dev/null @@ -1,145 +0,0 @@ -""" -This module contains Discreditizer class which is responsible for -discreditizing state space (positions, pole angles, velocities and angular -velocities) and action space (cart accelerations). -""" - - -from dataclasses import dataclass - -import torch -from torch import DoubleTensor - -from .config import SystemConfiguration - - -@dataclass -class Discreditizer: - """ - Discreditizes state space (positions, pole angles, velocities and angular - velocities) and action space (cart accelerations) according to the config. - - After discretization, stores the results. - """ - - config: SystemConfiguration - - cart_accelerations: DoubleTensor = None # type: ignore - _all_states: DoubleTensor = None # type: ignore - - def __post_init__(self) -> None: - """ - Generates all states from configuration. - """ - positions = torch.linspace( # type: ignore - start=-self.config.limits.max_abs_position, - end=self.config.limits.max_abs_position, - steps=self.config.discretization.cart_position, - dtype=torch.float64, - ) - angles = torch.linspace( # type: ignore - start=0.0, - end=2 * torch.pi, - steps=self.config.discretization.pole_angle, - dtype=torch.float64, - ) - velocities = torch.linspace( # type: ignore - start=-self.config.limits.max_abs_velocity, - end=self.config.limits.max_abs_velocity, - steps=self.config.discretization.cart_velocity, - dtype=torch.float64, - ) - angular_velocities = torch.linspace( # type: ignore - start=-self.config.limits.max_abs_angular_velocity, - end=self.config.limits.max_abs_angular_velocity, - steps=self.config.discretization.pole_angular_velocity, - dtype=torch.float64, - ) - self.cart_accelerations = torch.linspace( # type: ignore - start=-self.config.limits.max_abs_acceleration, - end=self.config.limits.max_abs_acceleration, - steps=self.config.discretization.cart_acceleration, - dtype=torch.float64, - ) - - # Generate all possible states tensor - positions, angles, velocities, angular_velocities = torch.meshgrid( - [ - positions, - angles, - velocities, - angular_velocities, - ], - indexing="ij", - ) - - self._all_states = torch.vstack( # type: ignore - [ - positions.flatten(), - angles.flatten(), - velocities.flatten(), - angular_velocities.flatten(), - ] - ) - - @property - def space_size(self) -> int: - """ - Returns the total number of states - - Returns - ------- - int - """ - return self._all_states.shape[1] - - @property - def cart_positions(self) -> DoubleTensor: - """ - Returns - ------- - DoubleTensor - 1xN Tensor with cart positions. - """ - return self._all_states[0] # type: ignore - - @property - def pole_angles(self) -> DoubleTensor: - """ - Returns - ------- - DoubleTensor - 1xN Tensor with pole angles. - """ - return self._all_states[1] # type: ignore - - @property - def cart_velocities(self) -> DoubleTensor: - """ - Returns - ------- - DoubleTensor - 1xN Tensor with cart velocities. - """ - return self._all_states[2] # type: ignore - - @property - def pole_angular_velocities(self) -> DoubleTensor: - """ - Returns - ------- - DoubleTensor - 1xN Tensor with pole angular velocities. - """ - return self._all_states[3] # type: ignore - - @property - def all_states(self) -> DoubleTensor: - """ - Returns - ------- - DoubleTensor - 4xN Tensor storing cart positions, pole angles, cart velocities - and pole angular velocities. - """ - return self._all_states diff --git a/cartpole/simulator/pytorch/learning_context.py b/cartpole/simulator/pytorch/learning_context.py deleted file mode 100644 index 3ff3f17..0000000 --- a/cartpole/simulator/pytorch/learning_context.py +++ /dev/null @@ -1,73 +0,0 @@ -""" -This module contains a MultiSystemLearningContext which is a container -for all of the data which is used to train a model which -works with batches (multiple systems at a time). -""" - -from dataclasses import dataclass -from typing import Callable - -import torch -from torch import DoubleTensor, LongTensor - -from .config import SystemConfiguration -from .discreditizer import Discreditizer -from .state import MultiSystemState - -CostFunction = Callable[[DoubleTensor], DoubleTensor] - - -@dataclass -class MultiSystemLearningContext: - """ - A container for all the data which is used to train a model which - works with batches (multiple systems at a time). - """ - - states_cost_fn: CostFunction - inputs_cost_fn: CostFunction - config: SystemConfiguration - batch_state: MultiSystemState - discreditizer: Discreditizer - - def update_batch(self, batch_size: int) -> None: - """ - Generates a new batch and updates the batch multistate. - - Parameters - ---------- - batch_size : int - Size of the batch. - - Raises - ------ - ValueError - If `batch_size` was less than 1 or greater than - the total number of states. - """ - total_states = self.discreditizer.space_size - - if not (0 < batch_size <= total_states): - raise ValueError("Invalid batch size") - - batch: LongTensor = torch.randint( - low=0, - high=total_states, - size=(batch_size,), # type: ignore - ) # type: ignore - - self.batch_state = MultiSystemState.create_from_batch( - self.discreditizer.all_states, - batch, - ) - - @property - def batch_size(self) -> int: - """ - Returns the size of the current batch. - - Returns - ------- - int - """ - return self.batch_state.size diff --git a/cartpole/simulator/pytorch/state.py b/cartpole/simulator/pytorch/state.py deleted file mode 100644 index f225786..0000000 --- a/cartpole/simulator/pytorch/state.py +++ /dev/null @@ -1,215 +0,0 @@ -""" -This module contains 2 important dataclasses: -- `State` which represents the state of one system -- `MultiSystemState` which holds states of multiple systems. -The latter one is usually a batch. -""" - - -from dataclasses import dataclass -from typing import Collection - -from numpy import pi -from torch import DoubleTensor, LongTensor - - -@dataclass -class State: - """ - Represents state of the system. - - Fields - ------ - `cart_position` : float - Position of a cart along X axis. - Measured in meters. - When the cart is in the "home state", the position is `0`. - - `pole_angle` : float - Angle of the pole with respect to inverted Y axis. - Measured in radians, always belongs to interval `[0, 2*pi)`. - When the pole is stable (hanging down), the angle is `0`. - - `cart_velocity` : float - Velocity of the cart along X axis. - Measured in m/s (meters per second). - - `angular_velocity` : float - Angular velocity of the pole in counter-clockwise direction. - Measured in rad/s (radians per second). - """ - - cart_position: float - pole_angle: float - cart_velocity: float - angular_velocity: float - - def __post_init__(self) -> None: - self.pole_angle %= 2 * pi - - @staticmethod - def home() -> "State": - """ - Returns initial state of the system, where all the fields are set to 0. - - Returns - ------- - State - initial state of the system - """ - return State(0, 0, 0, 0) - - @staticmethod - def target() -> "State": - """ - Target (ideal) state of the system. - - Returns - ------- - State - Ideal state of the system - """ - return State( - cart_position=0, - pole_angle=pi, - cart_velocity=0, - angular_velocity=0, - ) - - def as_tensor(self) -> DoubleTensor: - """ - Returns current state as a 1x4 tensor - - Returns - ------- - DoubleTensor - 1x4 Tensor containing `cart_position`, - `pole_angle`, `cart_velocity` and `angular_velocity` - """ - return DoubleTensor( - [ - self.cart_position, - self.pole_angle, - self.cart_velocity, - self.angular_velocity, - ] - ) - - @staticmethod - def from_collection(arr: Collection[float]) -> "State": - """ - Creates a State object from an array of length 4. - - Parameters - ---------- - arr : Collection[float] - List/Array/Tensor containing `cart_position`, `pole_angle`, - `cart_velocity` and `angular_velocity`. - - Returns - ------- - State - State created from the collection. - - Raises - ------ - ValueError - If length of `arr` is not equal to 4. - """ - if len(arr) != 4: - raise ValueError("Length of collection should be 4") - return State( - cart_position=arr[0], # type: ignore - pole_angle=arr[1], # type: ignore - cart_velocity=arr[2], # type: ignore - angular_velocity=arr[3], # type: ignore - ) - - -@dataclass -class MultiSystemState: - """ - A class to represent states of multiple systems at a time. - """ - - _state_space: DoubleTensor - """ - 4xN tensor, where N is the number of systems - - `_state_space[0]` is a 1xN DoubleTensor containing cart positions - - `_state_space[1]` is a 1xN DoubleTensor containing pole angles - - `_state_space[2]` is a 1xN DoubleTensor containing cart velocities - - `_state_space[3]` is a 1xN DoubleTensor containing angular velocities - """ - - @staticmethod - def home(systems_num: int) -> "MultiSystemState": - """ - Initializes a MultiSystemState with home states. - - Parameters - ---------- - systems_num : int - Number of systems to simulate. - - Returns - ------- - MultiSystemState - """ - data = DoubleTensor(size=(4, systems_num)) - home_state = State.home().as_tensor() - - for i in range(systems_num): - data[:, i] = home_state - - return MultiSystemState(_state_space=data) # type: ignore - - @staticmethod - def create_from_batch( - all_states: DoubleTensor, - batch: LongTensor, - ) -> "MultiSystemState": - """ - Constructs a MultiSystemState from a sample of a state space. - - Parameters - ---------- - all_states : DoubleTensor - The state space (4xN DoubleTensor). - batch : IntTensor - A vector of integers containing the indexes of states - we want to simulate. - - Returns - ------- - MultiSystemState - """ - state_space = all_states[:, batch] - return MultiSystemState(_state_space=state_space) # type: ignore - - @property - def size(self) -> int: - """ - Returns the number of systems in current state - - Returns - ------- - int - The number of systems in current state - """ - return self._state_space.shape[1] - - @property - def states(self) -> DoubleTensor: - """ - Returns all states - - Returns - ------- - DoubleTensor - 4xN tensor, where N is the number of systems - - `state_space[0]` is a 1xN DoubleTensor containing cart positions - - `state_space[1]` is a 1xN DoubleTensor containing pole angles - - `state_space[2]` is a 1xN DoubleTensor containing cart velocities - - `state_space[3]` is a 1xN DoubleTensor containing angular velocities - """ - return self._state_space diff --git a/cartpole/simulator/pytorch/system.py b/cartpole/simulator/pytorch/system.py deleted file mode 100644 index a0de7e9..0000000 --- a/cartpole/simulator/pytorch/system.py +++ /dev/null @@ -1,268 +0,0 @@ -""" -This module contains CartPoleMultiSystem class. The systems data is stored -in a `MultiSystemLearningContext` and the system itself only performs -neccessary calculations for multiple CartPole systems at a time. -It provides a "functional" interface which allows us to change contexts -on fly if needed. - -It supports evaluating best inputs for a given set of states and also -evaluating new states (after inputs are applied). -""" - - -from dataclasses import dataclass - -import torch -from torch import DoubleTensor, cos, sin - -from cartpole.common import CartPoleBase -from cartpole.common import Error - -from .config import SystemConfiguration -from .discreditizer import Discreditizer -from .learning_context import MultiSystemLearningContext -from .state import MultiSystemState, State - - -class CartPoleMultiSystem: - """ - Provides a "functional" interface to evaluate best inputs and new states - (after applying inputs to given ones). - The systems data is stored - in a `MultiSystemLearningContext` and the system itself only performs - neccessary calculations for multiple CartPole systems at a time. - """ - - @staticmethod - def eval_transitions( - context: MultiSystemLearningContext, inputs: DoubleTensor - ) -> None: - """ - Calculates new states and writes them in-place. - - Parameters - ---------- - context : MultiSystemLearningContext - inputs : DoubleTensor - A 1xN tensor containing input cart accelerations. - """ - # Current state - cur_st = context.batch_state.states - steps: int = context.config.discretization.integration_step_n - # dynamics delta time - d_time: float = 1 / (steps * context.config.discretization.simulation_step_n) - - # Gravitational constant - grav: float = context.config.parameters.gravity - pole_len: float = context.config.parameters.pole_length - - def compute_derivative(state: DoubleTensor): - # FIXME : Use 2 pre-allocated arrays instead of creating new ones - ang = state[1] - return torch.vstack( - ( - state[2], - state[3], - inputs, - -1.5 / pole_len * (inputs * cos(ang) + grav * sin(ang)), - ) - ) - - for _ in range(steps): - # Evaluate derivatives - ds1 = compute_derivative(cur_st) # type: ignore - ds2 = compute_derivative(cur_st + ds1 * d_time) # type: ignore - cur_st += (ds1 + ds2) / 2 * d_time # type: ignore - - @staticmethod - def eval_transition_costs( - context: MultiSystemLearningContext, - inputs: DoubleTensor, - ) -> DoubleTensor: - """ - Evaluates new states cost and action costs. - - Parameters - ---------- - context : MultiSystemLearningContext - inputs : DoubleTensor - The inputs applied - - Returns - ------- - DoubleTensor - 1xK Tensor containing total cost of applying - i-th action to i-th state. - """ - states_cost = context.states_cost_fn(context.batch_state.states) - inputs_cost = context.inputs_cost_fn(inputs) - - return states_cost + inputs_cost # type: ignore - - @staticmethod - def get_best_accelerations(context: MultiSystemLearningContext) -> DoubleTensor: - """ - Returns best input for each state. - - Parameters - ---------- - context : MultiSystemLearningContext - Returns - ------- - DoubleTensor - 1xK Tensor with best inputs for all the states. - """ - best_costs: DoubleTensor = torch.full( - size=(context.batch_size,), - fill_value=torch.inf, - dtype=torch.float64, - ) # type: ignore - best_inputs: DoubleTensor = torch.zeros( - size=(context.batch_size,), - dtype=torch.float64, - ) # type: ignore - - for acc in context.discreditizer.cart_accelerations: - inputs: DoubleTensor = torch.full( - size=(context.batch_size,), - fill_value=acc, # type: ignore - dtype=torch.float64, - ) # type: ignore - - CartPoleMultiSystem.eval_transitions(context, inputs) - costs = CartPoleMultiSystem.eval_transition_costs( - context, - inputs, - ) - - # Define a mask which says if i-th cost was better than current one - rng = range(context.batch_size) - - better_mask = [costs[i] < best_costs[i] for i in rng] - - # update minimum costs - best_costs = torch.minimum(best_costs, costs) # type: ignore - # update best inputs - best_inputs[better_mask] = acc - - return best_inputs - - -@dataclass(init=False) -class CartPoleSystem(CartPoleBase): - """ - Description: - Сlass implements a physical simulation of the cart-pole device. - A pole is attached by an joint to a cart, which moves along guide axis. - The pendulum is initially at rest state. The goal is to maintain it in - upright pose by increasing and reducing the cart's velocity. - Source: - This environment is some variation of the cart-pole problem - described by Barto, Sutton, and Anderson - Initial state: - A pole is at starting position 0 with no velocity and acceleration. - """ - - _context: MultiSystemLearningContext - _current_input: float = 0 - _config: SystemConfiguration = SystemConfiguration() - _current_time: float = 0 - _error: Error = Error.NO_ERROR - - def _setup_context( - self, - state: State, - ) -> None: - batch_state = state.as_tensor().reshape(4, -1) - batch_ms_state = MultiSystemState(batch_state) # type: ignore - self._context = MultiSystemLearningContext( - states_cost_fn=None, # type: ignore - inputs_cost_fn=None, # type: ignore - config=self._config, - discreditizer=Discreditizer(self._config), - batch_state=batch_ms_state, - ) - - def reset(self, config: SystemConfiguration) -> None: - """ - Resets the device to the initial state. - The pole is at rest position and cart is centered. - It must be called at the beginning of any session. - """ - self._setup_context(State.home()) - - self._config = config - self._current_time = 0 - - def reset_to_state(self, config: SystemConfiguration, state: State) -> None: - self._setup_context(state) - - self._config = config - self._current_time = 0 - - def get_state(self) -> State: - """ - Returns current device state. - """ - state_tensor = self._context.batch_state.states.flatten() - return State.from_collection(state_tensor) # type: ignore - - def get_info(self) -> dict: - """ - Returns usefull debug information. - """ - raise NotImplementedError - - def get_target(self) -> float: - """ - Returns current target acceleration. - """ - return self._current_input - - def set_target(self, target: float) -> None: - """ - Set desired target acceleration. - """ - max_target = self._config.limits.max_abs_acceleration - if not -max_target <= target <= max_target: - self._error = Error.A_OVERFLOW - return - - self._current_input = target - - def advance(self, delta: float) -> None: - """ - Advance the dynamic system by delta seconds. - """ - if self._error != Error.NO_ERROR: - print(f"Error occurred: {self._error}. Simulation is stopped") - return - - max_x = self._config.limits.max_abs_position - max_v = self._config.limits.max_abs_velocity - - sim_steps = self._config.discretization.simulation_step_n - for _ in range(int(delta * sim_steps)): - CartPoleMultiSystem.eval_transitions( - context=self._context, - inputs=torch.full( - size=(1,), - fill_value=self._current_input, # type: ignore - dtype=torch.float64, - ), - ) - - # Check that all the limits are ok - state = self._context.batch_state.states[:, 0] - if not -max_x <= state[0] <= max_x: - self._error = Error.X_OVERFLOW - if not -max_v <= state[1] <= max_v: - self._error = Error.V_OVERFLOW - - self._current_time += delta - - def timestamp(self) -> float: - """ - Current time. - """ - return self._current_time diff --git a/default_config.yaml b/default_config.yaml new file mode 100644 index 0000000..16ffe4d --- /dev/null +++ b/default_config.yaml @@ -0,0 +1,12 @@ +control_limit: + cart_position: 0.15 + cart_velocity: 2.0 + cart_acceleration: 3.0 +hardware_limit: + cart_position: 0.20 + cart_velocity: 3.0 + cart_acceleration: 5.0 +parameters: + friction_coef: 0.30 + gravity: 9.81 + mass_coef: 5 diff --git a/docker-compose.yaml b/docker-compose.yaml new file mode 100644 index 0000000..db87e79 --- /dev/null +++ b/docker-compose.yaml @@ -0,0 +1,39 @@ +version: "3.9" + +services: + cartpole: + container_name: "${CONTAINER_NAME:-cartpole}" + image: registry.robotics-lab.ru/cartpole:0.4.0 + privileged: true + entrypoint: "/bin/bash -c 'trap : TERM INT; sleep infinity & wait'" + working_dir: /cartpole + build: + dockerfile: Dockerfile + context: . + tags: + - registry.robotics-lab.ru/cartpole:0.4.0 + x-bake: + platforms: + - linux/arm64 + - linux/amd64 + cache-from: + - type=registry,ref=registry.robotics-lab.ru/cartpole:cache-arm64 + - type=registry,ref=registry.robotics-lab.ru/cartpole:cache-amd64 + cache-to: + - type=registry,ref=registry.robotics-lab.ru/cartpole:cache-arm64,mode=max + - type=registry,ref=registry.robotics-lab.ru/cartpole:cache-amd64,mode=max + environment: + - PYTHONPATH=/cartpole + volumes: + - "${PWD}:/cartpole" + - "/dev:/dev" + ports: + - "8765:8765" + - "8888:8888" + - "8000:8000" + networks: + - default + +networks: + default: + name: "${CONTAINER_NAME:-cartpole}" diff --git a/docs/Makefile b/docs/Makefile index 2597ede..73e7b34 100644 --- a/docs/Makefile +++ b/docs/Makefile @@ -1,21 +1,26 @@ .PHONY: all all: \ - cart_pole_pdf \ radial_cart_pole_svg \ - classic_cart_pole_svg \ + linear_cart_pole_svg \ + radial_cart_pole_helper_svg \ build_dir: mkdir -p build -cart_pole_pdf: build_dir - cd tex && pdflatex -output-directory ../build derivation_cart_pole.tex - cp build/derivation_cart_pole.pdf cart_pole.pdf - -classic_cart_pole_svg: build_dir - latex -output-directory build tex/classic_cart_pole.tex - dvisvgm --no-fonts build/classic_cart_pole.dvi -o svg/classic_cart_pole.svg +linear_cart_pole_svg: build_dir + latex -output-directory build tex/linear_cart_pole.tex + dvisvgm --no-fonts build/linear_cart_pole.dvi -o svg/linear_cart_pole.svg radial_cart_pole_svg: build_dir latex -output-directory build tex/radial_cart_pole.tex - dvisvgm --no-fonts build/radial_cart_pole.dvi -o svg/radial_cart_pole.svg \ No newline at end of file + dvisvgm --no-fonts build/radial_cart_pole.dvi -o svg/radial_cart_pole.svg + +radial_cart_pole_helper_svg: build_dir + latex -output-directory build tex/radial_cart_pole_helper.tex + dvisvgm --no-fonts build/radial_cart_pole_helper.dvi -o svg/radial_cart_pole_helper.svg + + +clean: + rm -rf build + cd tex && latexmk -CA diff --git a/docs/cart_pole.pdf b/docs/cart_pole.pdf index a30963c..c002378 100644 Binary files a/docs/cart_pole.pdf and b/docs/cart_pole.pdf differ diff --git a/docs/controller_protocol.md b/docs/controller_protocol.md deleted file mode 100644 index 9e5bd31..0000000 --- a/docs/controller_protocol.md +++ /dev/null @@ -1,140 +0,0 @@ -# CartPole Controller Protocol - -- [Overview](#overview) -- [Variables](#variables) - - [Config group](#config) - - [State group](#state) - - [Target group](#target) - - [Error codes](#error-codes-enum) -- [Commands](#commands) - - [Get variable](#get-group-key1-key2-) - - [Set variable](#set-group-key1val1-key2val2-) - - [Reset](#reset) - -## Overview - -This document defines communication protocol between higher-level SBC ("brain") -and lower-level MCU ("controller"). Brain operates with high-level commands like -"go to x=0.1m", "accelerate to v=0.5m/s", "get current pole angle". Controller -is responsible for translating these commands to underlying hardware (stepper -motor, encoder, endstop switches etc.). Controller also implements safety checks -to prevent incorrect brain commands from damaging the device (e.g. when the brain -asks for x=10m when max allowed x is 1m). - -Communication is performed through serial connection, using plain-text messages -with ASCII encoding. This allows easy (de)serialization and ability to manually -debug the device. A message is the smallest protocol entity that can be sent or -received. Messages are separated by UNIX-style "\n" delimiter. Protocol follows -a "request-reply" strategy, where the brain only sends requests, and the controller -only sends replies to those requests. Request-reply pairs (also called “commands”) -are described in a separate section below. There are several types of replies, -which can be determined by message prefix: - -- `+ ` - Successful request. `` is a response payload. -- `! ` - Request failed. `` is an error description. -- `# ` - Debug message. Could be ignored and/or logged. -- `~` - Request in progress. This message is sent to prevent timeouts. - -The main rule of a command is that it must eventually return either successful (`+`) or unsuccessful (`!`) response. -If it takes a long time to process a command (e.g. homing), the controller should send multiple `~` messages to -prevent a timeout. The brain can consider a fatal communication error in two cases: - -- After sending a request, there’s no `+`, `!` or `~` replies for longer than 1 second. -- After sending a request, there’s multiple `~` replies, but no `+` or `!` reply for longer than 30 seconds. - -If a fatal error is detected, the best thing the brain can do is to hard-reset the controller. -Hopefully, that can be done by re-opening the serial connection. In order for this to work, -the serial adapter must have DTR/RTS output connected to MCU reset pin. - -## Variables - -### Config - -| KEY | TYPE | DEFAULT | RANGE | COMMENT | -|----------|--------------|---------|---------------|------------------------------------------| -| MAX_X | m, float | 0 | [0, HW_MAX_X] | Max cart position (X=0 is center) | -| MAX_V | m/s, float | 0.5 | [0, HW_MAX_V] | Max cart velocity | -| MAX_A | m/s^2, float | 1.0 | [0, HW_MAX_A] | Max cart acceleration | -| HW_MAX_X | m, float | 0 | - | [READONLY] Max allowed cart position | -| HW_MAX_V | m/s, float | TBD | - | [READONLY] Max allowed cart velocity | -| HW_MAX_A | m/s^2, float | TBD | - | [READONLY] Max allowed cart acceleration | -| CLAMP_X  | flag, bool | FALSE | true/false | Round X to allowed range without errors | -| CLAMP_V | flag, bool | FALSE | true/false | Round V to allowed range without errors | -| CLAMP_A | flag, bool | FALSE | true/false | Round A to allowed range without errors | - -Notes about `HW_*` variables: -- `HW_MAX_X` is updated after the homing procedure. -- `HW_MAX_V` and `HW_MAX_A` are hardcoded values, determined by stress-tests. It’s recommended to -always set `MAX_V` and `MAX_A` slightly lower than `HW_MAX_V` and `HW_MAX_A`. Otherwise, the device -operation may be unstable (probably, `MOTOR_STALLED` error will be raised at some point). - -### State - -| KEY | TYPE | DEFAULT | RANGE | COMMENT | -|---------|--------------|---------|-------|------------------------------------------------| -| X | m, float | 0 | - | [READONLY] Current cart position | -| V | m/s, float | 0 | - | [READONLY] Current cart velocity | -| A | m/s^2, float | 0 | - | [READONLY] Current cart acceleration | -| POLE_X | rad, float | 0 | - | [READONLY] Current pole angle | -| POLE_V | rad/s, float | 0 | - | [READONLY] Current pole angular velocity | -| ERRCODE | enum, int | 1 | - | [READONLY] Current error code (see enum below) | - - -### Target - -| KEY | TYPE | DEFAULT | RANGE | COMMENT | -|-----|--------------|---------|-----------------|--------------------------| -| X | m, float | 0 | [-MAX_A, MAX_X] | Target cart position | -| V | m/s, float | 0 | [-MAX_V, MAX_V] | Target cart velocity | -| A | m/s^2, float | 0 | [-MAX_A, MAX_A] | Target cart acceleration | - -Note: validation logic of `X`, `V` and `A` variables depends on `CLAMP_*` flags. If set, invalid -values are silently clamped to allowed range. Otherwise, corresponding `*_OVERFLOW` error is raised. - -### Error codes (enum): - -| KEY | INT | COMMENT | -|---------------|-----|-----------------------------------------------------------------------| -| NO_ERROR | 0 | This is fine (no errors, motion is allowed) | -| NEED_RESET | 1 | Device needs homing (see reset command) | -| X_OVERFLOW | 2 | Current or target position was out of allowed range | -| V_OVERFLOW | 3 | Current or target velocity was out of allowed range | -| A_OVERFLOW | 4 | Current or target acceleration was out of allowed range | -| MOTOR_STALLED | 5 | Stepper driver detected motor failure (TMC’s StallGuard is triggered) | -| ENDSTOP_HIT | 6 | One of endstops is triggered during movement | - -## Commands - -### `get [key1 key2 ...]` -Returns values for given keys in the form of space-separated "key=value" pairs. If no keys are specified, returns all keys from given group. -``` ->>> get config max_x -<<< + max_x=123.456 ->>> get state non_existent_key -<<< ! No such key: non_existent_key ->>> get target -<<< + x=123 v=456 a=789 -``` - -### `set [key1=val1 key2=val2 ...]` -Updates values of given keys and returns them back (format matches "get" command). -``` ->>> set state x=123 -<<< ! This key is readonly ->>> set config max_v=1.0 max_a=2.0 -<<< + max_v=1.0 max_a=2.0 ->>> config set max_v=1000 -<<< ! Value out of range: 1000 > 10 [at max_v=1000] -``` - -### `reset` -Performs homing procedure and resets all variables. This command may take a long time to complete, -so it will periodically send keepalive `~` messages. After completion, returns the word "ok". -``` ->>> reset -<<< ~ -<<< ~ -<<< ~ -<<< ~ -<<< + ok -``` diff --git a/docs/dynamics.md b/docs/dynamics.md new file mode 100644 index 0000000..494918d --- /dev/null +++ b/docs/dynamics.md @@ -0,0 +1,206 @@ +# Dynamics +## Linear CartPole + +A cart with mass $m_c$ moves along the $x$-axis, so its center $C$ has coordinates $(x, 0)^T$. +A pole with mass $m_p$ is attached to the cart with a hinge at point $C$, +and rotates around with viscous friction. +The pole's center of mass is at $P$, moment of inertia is $I_p$. +The angle of rotation is denoted as $\theta$, measured counterclockwise from the axis $-y$. +A force $f_x$ is applied to the cart and the force of gravity $g$ acts on the pole. + +
+ ![Linear CartPole](svg/linear_cart_pole.svg){width="75%"} +
+ +$$ +\begin{align} + & C = \begin{pmatrix} + x \\ 0 + \end{pmatrix} + && \dot{C} = \begin{pmatrix} + \dot{x} \\ 0 + \end{pmatrix} \\ + & P = \begin{pmatrix} + x + l \sin \theta \\ - l \cos \theta + \end{pmatrix} + && \dot{P} = \begin{pmatrix} + \dot{x} + l \dot{\theta} \cos \theta \\ l \dot{\theta} \sin \theta + \end{pmatrix} +\end{align} +$$ + +The kinetic energy of the cart is + +$$ +\begin{align} + T_c = \frac{1}{2} m_c \begin{Vmatrix} + \dot{C} + \end{Vmatrix}_2^2 = \frac{1}{2} m_c \dot{x}^2. +\end{align} +$$ + +As a result energy of the whole system is following + +$$ +\begin{align} + T & = T_c + T_p = \frac{1}{2} \dot{x}^2 (m_c + m_p) + m_p \dot{x} l \dot{\theta} \cos \theta + + \frac{1}{2} \dot{\theta}^2 \left( m_p l^2 + I_p \right); \\ + U & = \underbrace{U_c}_{0} + U_p = -m_p gl \cos \theta. +\end{align} +$$ + +To find the dynamics of system, let's use the Euler-Lagrange differential equation, where $L = T - U$, $q = (x, \theta)^T$ and $Q$ is the generalized force. +In our case, we have deal with two forces: motor force $f_x$ and viscous friction $f_{\theta}(\theta, \dot{\theta}) = -\mu \dot{\theta}$. + +$$ +\begin{align} + Q &= \frac{d}{dt} \frac{dL}{d\dot{q}} - \frac{dL}{dq} = \begin{pmatrix} f_x \\ f_{\theta} \end{pmatrix} +\end{align} +$$ + +!!! abstract "Motion equations" + $$ + \begin{align} + m_p \ddot{x} l \cos \theta + \ddot{\theta} \left(m_p l^2 + I_p\right) + m_p g l \sin \theta &= f_{\theta}(\theta, \dot{\theta}) \\ + \ddot{x}(m_c + m_p) + m_p l \ddot{\theta} \cos \theta - m_p l \dot{\theta}^2 \sin \theta &= f_{x}. + \end{align} + $$ + +??? note "Derivation" + $$ + \begin{equation} + L = \frac{1}{2} \dot{x}^2 (m_c + m_p) + m_p \dot{x} l \dot{\theta} \cos \theta + + \frac{1}{2} \dot{\theta}^2 \left( m_p l^2 + I_p \right) + m_p gl \cos \theta. + \end{equation} + $$ + + $$ + \begin{align} + \frac{dL}{d\theta} & = - m_p \dot{x} l \dot{\theta} \sin \theta - m_p gl \sin \theta \\ + \frac{dL}{d\dot{\theta}} & = m_p \dot{x} l \cos \theta + \left(m_p l^2 + I_p\right) \dot{\theta} \\ + \frac{d}{dt} \frac{dL}{d\dot{\theta}} & = + m_p \ddot{x} l \cos \theta - m_p \dot{x} l \dot{\theta} \sin \theta + \left(m_p l^2 + I_p\right) \ddot{\theta} \\ + \frac{d}{dt} \frac{dL}{d\dot{\theta}} - \frac{dL}{d\theta} & = + m_p \ddot{x} l \cos \theta + \left(m_p l^2 + I_p\right) \ddot{\theta} + m_p g l \sin \theta \\ + \end{align} + $$ + + $$ + \begin{align} + \frac{dL}{dx} & = 0 \\ + \frac{dL}{d\dot{x}} & = (m_c + m_p) \dot{x} + m_p l \dot{\theta} \cos \theta \\ + \frac{d}{dt} \frac{dL}{d\dot{x}} & = + (m_c + m_p) \ddot{x} + m_p l \ddot{\theta} \cos \theta - m_p l \dot{\theta}^2 \sin \theta \\ + \frac{d}{dt} \frac{dL}{d\dot{x}} - \frac{dL}{dx} & = + (m_c + m_p) \ddot{x} + m_p l \ddot{\theta} \cos \theta - m_p l \dot{\theta}^2 \sin \theta. \\ + \end{align} + $$ + +### Acceleration control + +Let's make the assumption that the motor can generate any force necessary for the cart to reach acceleration in $[-a, a]$ on a fixed cart velocity range. +This fact allows us to consider the cart acceleration as a control input and significantly simplify the equations of motion + +$$ +\begin{align} + \left(m_p l^2 + I_p\right) \ddot{\theta} &= f_{\theta}(\theta, \dot{\theta}) + - m_p \ddot{x} l \cos \theta - m_p g l \sin \theta \\ + \ddot{x} &= u, \quad u \in [-a, a]. +\end{align} +$$ + +But for practice it's more convenient to use another form + +$$ +\begin{align*} + \left(m_p l^2 + I_p\right) \ddot{\theta} &= -\mu\dot{\theta} - m_p \ddot{x} l \cos \theta - m_p g l \sin \theta \\ + \ddot{\theta} &= -\frac{\mu}{\left(m_p l^2 + I_p\right)}\dot{\theta} + - \frac{\ddot{x} \cos \theta - g \sin \theta}{l + \frac{I_p}{m_p l}}. \\ +\end{align*} +$$ + +Since all parameters do not change over time, we can greatly simplify the motion equations. + +!!! abstract "Motion equations" + $$ + \begin{align} + \ddot{\theta} &= -b\dot{\theta} - k \big(\ddot{x} \cos \theta - g \sin \theta\big) \\ + \ddot{x} &= u, \quad u \in [-a, a]. + \end{align} + $$ + +## Radial CartPole + +Linear CartPole is classic kinematic scheme, +but it requires a lot of space, periodical homing (return cart to the initial pose ) and etc. +Radial CartPole is a modification, which allows to avoid problems, keeping the same motion equations. +In case of radial version cart moves along the circle with radius $r$. + +
+ ![Radial CartPole](svg/radial_cart_pole.svg){ width="75%"} +
+ +Pole's mass $m_p$, moment of inertian $I_p$ and distance from hinge to center of mass $l_p$ are known again. +But instead of position $x$ there is angle $\phi$ (in some sense $x = r\phi$) and control input is radial acceleration $\ddot{\phi}$. +Also, as shown in previous section, we can consider mass of cart is zero. + +Actually, after some calculations we can get the same motion equations as for classic version, +but linear variables are replaced by angular ones + +$$ +\begin{align} + \left(m_p l^2 + I_p\right) \ddot{\theta} &= + f_{\theta}(\theta, \dot{\theta}) - m_p r \ddot{\phi} l \cos \theta - m_p g l \sin \theta \\ + \ddot{\phi} &= u, \quad u \in [u_{min}, u_{max}]. +\end{align} +$$ + +!!! abstract "Dynamics equation" + $$ + \begin{align} + \ddot{\theta} &= -b\dot{\theta} - k\big(r \ddot{\phi} \cos \theta - g \sin \theta\big) \\ + \ddot{\phi} &= u, \quad u \in [u_{min}, u_{max}]. + \end{align} + $$ + +??? note "Derivation" + Note that $T_p^r = \frac{1}{2}I_p\dot{\theta}^2$ and $T_p^t = \frac{1}{2}m_p \begin{Vmatrix} \dot{P} \end{Vmatrix}_2^2$. + To calculate $\begin{Vmatrix} \dot{P} \end{Vmatrix}_2^2$, consider the coordinates system plane, + which is attached to the cart and tangent to the circle (pole fully lies in that plane). + +
+ ![Linear CartPole](svg/radial_cart_pole_helper.svg){width="50%"} +
+ + $$ + \begin{align} + \begin{Vmatrix} \dot{P} \end{Vmatrix}_2^2 = \left(\underbrace{\dot{\phi} r + + \dot{\theta} l_p \cos \theta }_{\dot{x}'}\right)^2 + + \left(\underbrace{\dot{\theta} l_p \sin \theta}_{\dot{y}'} \right)^2 + = \dot{\phi}^2 r^2 + 2 \dot{\phi} \dot{\theta} r l_p \cos \theta + \dot{\theta}^2 l_p^2. + \end{align} + $$ + + Bellow rest of the calculations are shown + + $$ + \begin{align} + T_p &= \frac{1}{2}I_p\dot{\theta}^2 + \frac{1}{2}m_p\left(\dot{\phi}^2 r^2 + + 2 \dot{\phi} \dot{\theta} r l_p \cos \theta + \dot{\theta}^2 l_p^2\right) \\ + U_p &= - m_p g l_p \cos \theta \\ + L = T_p - U_p &= \frac{1}{2} I_p \dot{\theta}^2 + \frac{1}{2} m_p \left(\dot{\phi}^2 r^2 + + 2 \dot{\phi} \dot{\theta} r l_p \cos \theta + \dot{\theta}^2 l_p^2\right) + m_p g l_p \cos \theta + \end{align} + $$ + + $$ + \begin{align} + \frac{dL}{d\theta} & = - m_p l_p (r \dot{\phi} \dot{\theta} \sin \theta + g \sin \theta) \\ + \frac{dL}{d\dot{\theta}} & = I_p \dot{\theta} + m_p l_p (\dot{\phi} r \cos \theta + l_p \dot{\theta}) \\ + \frac{d}{dt} \frac{dL}{d\dot{\theta}} & = + I_p \ddot{\theta} + m_p l_p (r \ddot{\phi} \cos \theta + l_p \ddot{\theta} - r \dot{\phi} \dot{\theta} \sin \theta) \\ + \frac{d}{dt} \frac{dL}{d\dot{\theta}} - \frac{dL}{d\theta} & = + \ddot{\theta} (I_p + m_p l_p^2) + m_p l_p (r \ddot{\phi} \cos \theta + g \sin \theta) = 0. + \end{align} + $$ + diff --git a/docs/index.md b/docs/index.md new file mode 100644 index 0000000..c817c9f --- /dev/null +++ b/docs/index.md @@ -0,0 +1,28 @@ +# Overview + +CartPole is an educational project of [the robotics group](https://cs.hse.ru/robotics) (HSE/FCS). +It is designed to learn the basics of optimal control and reinforcement learning. +The environment is a variation of famous control problem, +where a pole is attached by a joint to a cart, moving along a axis. +Some motor drives the cart with acceleration as control input. +The goal is to swing up the pole and maintain it in unstable equilibrium state. +You can follow our progress on [YouTube](https://youtube.com/playlist?list=PLR1nN_AQOO9yAG5CHOA4l2x3j89t-3PYf). + +
+ ![Image title](linear-cartpole-render.png) +
Linear CartPole
+
+ +Linear CartPole is classic kinematic scheme, but it requires a lot of space, periodical homing (return cart to the initial pose) and etc. +Radial CartPole is a modification, which allows to avoid these problems, keeping the same motion equations. +In case of radial version cart moves along the circle with radius $r$. Yoy can see the difference on the pictures below. + +=== "Linear" + ![CartPole](svg/linear_cart_pole.svg) + +=== "Radial" + ![RadialCartPole](svg/radial_cart_pole.svg) + + + + diff --git a/docs/js/mathjax.js b/docs/js/mathjax.js new file mode 100644 index 0000000..3e4adde --- /dev/null +++ b/docs/js/mathjax.js @@ -0,0 +1,16 @@ +// https://squidfunk.github.io/mkdocs-material/reference/math + +window.MathJax = { + tex: { + inlineMath: [["\\(", "\\)"]], + displayMath: [["\\[", "\\]"]], + processEscapes: true, + processEnvironments: true + }, + options: { + ignoreHtmlClass: ".*|", + processHtmlClass: "arithmatex" + } +}; + +document$.subscribe(() => {MathJax.typesetPromise()}) diff --git a/docs/lib_fixes.md b/docs/lib_fixes.md deleted file mode 100644 index dc68ea4..0000000 --- a/docs/lib_fixes.md +++ /dev/null @@ -1,33 +0,0 @@ -# Manual fixes to libs - -### MPU6050 - -In lib `MPU6050`: - -In file `MPU6050.h` at line `45` change - -```cpp -#include -``` - -to - -```cpp -#ifdef __AVR__ -#include -#else -#include -#endif -``` - -In file `I2Cdev.cpp` at line `300` change - -```cpp -for (uint8_t k = 0; k < length; k += min(length, BUFFER_LENGTH)) { -``` - -to - -```cpp -for (uint8_t k = 0; k < length; k += min(static_cast(length), BUFFER_LENGTH)) { -``` \ No newline at end of file diff --git a/docs/linear-cartpole-render.png b/docs/linear-cartpole-render.png new file mode 100644 index 0000000..fe85318 Binary files /dev/null and b/docs/linear-cartpole-render.png differ diff --git a/docs/model.ipynb b/docs/model.ipynb deleted file mode 100644 index 3c40ae8..0000000 --- a/docs/model.ipynb +++ /dev/null @@ -1,164 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Overview\n", - "The environment is some variation of the cart-pole problem described by Barto, Sutton, and Anderson. A pole is attached by an joint to a cart, which moves along guide axis. Some stepper drives the cart. The motor is controlled by discrete velocity changing. The control target is desired acceleration of the cart.\n", - "\n", - "The cart starts at the middle with no velocity and acceleration. The pole is initially at rest state. The goal is to swing up the pole and maintain it in upright pose by increasing and reducing the cart's velocity.\n", - "\n", - "![schema](https://raw.githubusercontent.com/dasimagin/cart_pole/master/docs/model.svg)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Energy\n", - "Let's look at the dynamics of the entire system. The kinetic energy of cart is trivial\n", - "$$T_c = \\frac{m_c}{2}\\dot{x}^2.$$\n", - "\n", - "The potential energy of pole is depend on current angle $\\theta$ only\n", - "$$U_p = -m_p g\\frac{l}{2}\\cos\\theta.$$\n", - "\n", - "Let's split energy at rotational and translational parts, where $I$ is moment of inertia and $v_{pc}$ – velocity of mass center.\n", - "\n", - "$$T^r_p = \\frac{I\\dot{\\theta}^2}{2}, ~ I=\\frac{1}{12}m_p l^2$$\n", - "\n", - "$$T^t_p = \\frac{m_p v^2_{pc}}{2}, ~ v^2_{pc} = \\dot{x}^2_{pc} + \\dot{y}^2_{pc}$$\n", - "\n", - "It is convenient to decompose the velocity of mass center into $x$ and $y$ axes' components (keep in mind that the pole moves with the cart along axe).\n", - "\n", - "$$\\dot{x}_{pc} = \\dot{x} + \\frac{l}{2}\\dot{\\theta}\\cos\\theta, ~ \\dot{y}_{pc} = \\frac{l}{2}\\dot{\\theta}\\sin\\theta.$$\n", - "\n", - "Have some math magic and get \n", - "\n", - "$$\n", - "T_p =\n", - "T^r_p + T^t_p =\n", - "\\frac{m_p}{2} \\cdot \\frac{l^2 \\dot{\\theta}^2}{12} +\n", - "\\frac{m_p}{2} \\cdot \\big[\n", - " \\dot{x}^2 +\n", - " \\frac{l^2 \\dot{\\theta}^2}{4} +\n", - " l \\dot{x} \\dot {\\theta}\\cos\\theta\n", - "\\big].\n", - "$$\n", - "\n", - "So, for pole's kinetic energy we have\n", - "$$T_p = \\frac{m_p}{2} \\big[\\dot{x}^2 + \\frac{l^2 \\dot{\\theta}^2}{3} + l\\dot{x}\\dot{\\theta}\\cos\\theta \\big].$$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Dynamics\n", - "To learn the dynamics of the system we use the Euler–Lagrange differential equation\n", - "\n", - "$$\\frac{dL}{dt} \\frac{\\partial L} {\\partial \\dot{q}} - \\frac{L}{\\partial q} = Q,$$\n", - "\n", - "where $L = T_c + T_p - U_p$, $Q$ – the generalized force and $q=(x, \\theta)^T$. If we have control force $u$ along $x$ axe than \n", - "\n", - "$$\n", - "\\begin{align*}\n", - "(m_p + m_c)\\ddot{x} + \\frac{m_p l}{2} \\Big[ \\ddot{\\theta} \\cos \\theta - \\dot{\\theta}^2 \\sin \\theta \\Big] &= f_x \\\\\n", - "\\frac{m_p l}{2} \\Big[ \\frac{2}{3} \\ddot{\\theta}l + \\ddot{x} \\cos \\theta + gsin\\theta \\Big] &= 0. \\\\\n", - "\\end{align*}\n", - "$$\n", - "\n", - "Bellow you can find all needed partial derivative.\n", - "\n", - "$$\n", - "\\begin{align*}\n", - " \\frac{\\partial L}{\\partial x} &= 0, \\\\\n", - " \\frac{\\partial L}{\\partial \\dot{x}} &= (m_c + m_p)\\dot{x} + \\frac{m_p l}{2} \\dot{\\theta}\\cos\\theta \\\\\n", - " \\frac{dL}{dt} \\frac{\\partial L}{\\partial \\dot{x}} &= (m_c + m_p)\\ddot{x} +\n", - " \\frac{m_p l}{2} \\big[ \n", - " \\ddot{\\theta}\\cos\\theta - \\dot{\\theta}^2\\sin\\theta\n", - " \\big] \\\\\n", - "\\end{align*} \n", - "$$\n", - "\n", - "
\n", - "\n", - "$$\n", - "\\begin{align*}\n", - " \\frac{\\partial L}{\\partial \\theta} &= \\frac{m_p l}{2} \\Big[\n", - " \\dot{x} \\dot{\\theta}\\sin\\theta - g\\sin\\theta\n", - " \\Big] \\\\\n", - " \\frac{\\partial L}{\\partial \\dot{\\theta}} &= \\frac{m_p l}{2} \\Big[\n", - " \\frac{2}{3}l\\dot{\\theta} + \\dot{x} \\cos\\theta \n", - " \\Big] \\\\\n", - " \\frac{dL}{dt} \\frac{\\partial L}{\\partial \\dot{\\theta}} &= \\frac{m_p l}{2} \\Big[\n", - " \\frac{2}{3}l\\ddot{\\theta} + \\ddot{x} \\cos\\theta - \\dot{x}\\dot{\\theta} \\sin \\theta\n", - " \\Big]. \\\\\n", - "\\end{align*}\n", - "$$\n", - "\n", - "In standard, manipulator equation form:\n", - "$$M(q)\\ddot{q} + C(q, \\dot{q})q = \\tau_g(q) + Bu$$\n", - "All matrices you can find below\n", - "\n", - "$$\n", - "\\begin{align*}\n", - "M(q) &= \\begin{bmatrix}\n", - "(m_c + m_p) & \\frac{m_p l}{2} \\cos\\theta \\\\\n", - "\\frac{m_p l}{2} \\cos\\theta & \\frac{m_p l^2}{3} \\\\\n", - "\\end{bmatrix},\n", - "&C(q, \\dot{q}) = \\begin{bmatrix}\n", - "0 & -\\frac{m_p l}{2} \\dot{\\theta} \\sin\\theta \\\\\n", - "0 & 0 \\\\\n", - "\\end{bmatrix}, \\\\\n", - "\\tau_g(q) &= \\begin{bmatrix}\n", - "0 \\\\\n", - "-\\frac{m_p l}{2} g \\sin\\theta \\\\\n", - "\\end{bmatrix},\n", - "&B = \\begin{bmatrix}\n", - "1 & 0 \\\\\n", - "0 & 0 \\\\\n", - "\\end{bmatrix},\n", - "u = \\begin{bmatrix}\n", - "f_x \\\\\n", - "0 \\\\\n", - "\\end{bmatrix}. \\\\\n", - "\\end{align*}\n", - "$$" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3.10.8 64-bit", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.10.8" - }, - "vscode": { - "interpreter": { - "hash": "97cc609b13305c559618ec78a438abc56230b9381f827f22d070313b9a1f3777" - } - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/docs/quickstart.md b/docs/quickstart.md new file mode 100644 index 0000000..6abe631 --- /dev/null +++ b/docs/quickstart.md @@ -0,0 +1,72 @@ +# Quickstart + +## Enviroment +Python is main language of project. So, students may learn control theory and make experiments faster and easier. +Firstly, you need checkout repo and prepare enviroment. + +```bash +git clone https://github.com/robotics-laboratory/cart-pole.git +``` + +We have a built container with all dependencies, use it for development and testing +(you need to have [docker](https://docs.docker.com/get-docker/) and [docker-compose](https://docs.docker.com/compose/install/) installed). Run in root of repo following commands. + +Pull latest actual image ```docker compose pull```, that you may start devcontainer in VSCode or run it manually. + +```bash +# enter to container +docker exec -it cartpole bash +``` + +Repo folder is mounted as `/cartpole` dir, so you can edit files in your favorite IDE. +We highly recommend to use `VS Code`, since we provide everything for comfortable development. +After you set up your environment, you can run tests to check that everything is OK. + +```bash +pytest tests +``` + +Also there are some environment variables, which may be useful for you: + +- `$CONTAINER_NAME` - name of container (default is `cartpole`) + +If you want to use your own python environment, you can install all dependencies manually, using [poetry](https://python-poetry.org/). + +```bash +# check poetry config +poetry config --list + +# install all depencies to .venv folder +poetry install + +# run tests to check that everithing is OK +poetry run pytest tests +``` + +## Foxglove +For visualization of real time data we use [foxglove studio](https://foxglove.dev/). +We strongly suggest to use our [instance](http://foxglove.robotics-lab.ru), but you may also setup server with our specific fixes by yourself (more information [here](https://github.com/robotics-laboratory/foxglove)). +In Foxglove Studio select `Open connection` than `Foxglove WebSocket` and enter `ws://localhost:8765` (use your port) in address field. + +## Logging +We have convinient logging system, it may show data in real time and replay saved data in [mcap](https://mcap.dev/) format. + +```python title="examples/log.py" +--8<-- "examples/log.py" +``` + +## Simulation +For development and testing of control algorithms, we provide CartPole simulator, which fully implemntet CartPoleBase [interface](/cartpole/common.py). +The simulation is carried out by numerical integration of parameterized dynamic system (more information [here](/docs/cart_pole.pdf)). +Also simulator may be used to train ML agents. + +```python title="examples/simulatio.py" +--8<-- "examples/simulation.py" +``` + +## Docs +You can build and run docs server locally. + +```bash +mkdocs serve -a 0.0.0.0:8000 +``` diff --git a/docs/reference/common.md b/docs/reference/common.md new file mode 100644 index 0000000..e1706d6 --- /dev/null +++ b/docs/reference/common.md @@ -0,0 +1,5 @@ +# Interface + +::: cartpole.common + handler: python + diff --git a/docs/reference/log.md b/docs/reference/log.md new file mode 100644 index 0000000..df42c0d --- /dev/null +++ b/docs/reference/log.md @@ -0,0 +1,10 @@ +# Logging + +::: cartpole.log + handler: python + options: + filters: [ + '!to_ns', '!to_stamp', '!this_or_now', '!pylog_level', '!get_pylogger' + ] + + diff --git a/docs/reference/simulator.md b/docs/reference/simulator.md new file mode 100644 index 0000000..551fbda --- /dev/null +++ b/docs/reference/simulator.md @@ -0,0 +1,5 @@ +# Simulation + +::: cartpole.simulator + handler: python + diff --git a/docs/sessions.md b/docs/sessions.md deleted file mode 100644 index d1aed42..0000000 --- a/docs/sessions.md +++ /dev/null @@ -1,29 +0,0 @@ -# How to record sessions - -```python -from cartpole.device.wire_interface import WireInterface, DeviceConfig, DeviceTarget -from collector import CollectorProxy -from cartpole.device import CartPoleDevice -import logging - - -def main(): - wire = WireInterface('COM4') - cartpole = CartPoleDevice(wire, target_key='acceleration') - p = CollectorProxy(cartpole) - p.reset(DeviceConfig(debug_led=True, max_velocity=1.0, max_acceleration=3)) - p.start() - - # CONTROL THE DEVICE HERE - - p.cart_pole.interface.set(DeviceTarget(position=0)) - p.stop() - p.cart_pole.interface.set(DeviceConfig(debug_led=False)) - - -if __name__ == '__main__': - FORMAT = '%(asctime)s [%(levelname)s] %(name)s :: %(message)s' - logging.basicConfig(format=FORMAT) - logging.getLogger().setLevel(logging.DEBUG) - main() -``` diff --git a/docs/svg/classic_cart_pole.svg b/docs/svg/classic_cart_pole.svg deleted file mode 100644 index bfc2e78..0000000 --- a/docs/svg/classic_cart_pole.svg +++ /dev/null @@ -1,322 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/docs/svg/linear_cart_pole.svg b/docs/svg/linear_cart_pole.svg new file mode 100644 index 0000000..9e1302d --- /dev/null +++ b/docs/svg/linear_cart_pole.svg @@ -0,0 +1,334 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/docs/svg/radial_cart_pole.svg b/docs/svg/radial_cart_pole.svg index 0cd8fe3..f01ccfb 100644 --- a/docs/svg/radial_cart_pole.svg +++ b/docs/svg/radial_cart_pole.svg @@ -1,135 +1,122 @@ - - + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + + - - - - - - - - - - - - - - + + + + + + - + - - - - - - - - - - - + + + - - + + - + - - - - - - - - - - - + + + - - + + - + - + - + - + - + - + - + - + @@ -138,14 +125,14 @@ - - - + + + - - + + @@ -154,22 +141,22 @@ - + - + - + - + - + - + @@ -178,13 +165,13 @@ - - - + + + - + @@ -193,22 +180,22 @@ - + - + - + - + - + - + @@ -217,14 +204,14 @@ - - - + + + - - + + @@ -233,15 +220,15 @@ - + - + - + @@ -249,13 +236,13 @@ - - - + + + - + @@ -264,15 +251,15 @@ - + - + - + @@ -280,13 +267,13 @@ - - - + + + - + @@ -295,120 +282,118 @@ - - - - - - - - - - - + + + - + - + - - - + + + - + - - + + - - - - - - - - - - - + + + - + - - - + + + - + + + + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - - + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + diff --git a/docs/svg/radial_cart_pole_helper.svg b/docs/svg/radial_cart_pole_helper.svg new file mode 100644 index 0000000..c0b4943 --- /dev/null +++ b/docs/svg/radial_cart_pole_helper.svg @@ -0,0 +1,148 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/docs/tex/classic_cart_pole.tex b/docs/tex/classic_cart_pole.tex deleted file mode 100644 index 10ebf9b..0000000 --- a/docs/tex/classic_cart_pole.tex +++ /dev/null @@ -1,53 +0,0 @@ -\documentclass[dvisvgm,tikz]{standalone} - -\usepackage{tikz} - -\begin{document} -\begin{tikzpicture} - % world - \draw[->, thick] (-1,3.1) -- (15,3.1) node[right] {\Large $x$}; - \draw[-, thick] (7,0.5) -- (7,5.7); - - % hull - \filldraw[red!100!black, fill=white, line width=5] (3.5,1.2) rectangle (10.5,5.0); - - % y axis help - \draw[-, dashed] (7,1.2) -- (7,5.0); - - % stick - \begin{scope}[rotate around={150:(7, 3.1)}] - \filldraw[green!80!black, fill=green!80!black] (6.75, 3.4) rectangle (7.25, -6); - - % C - \filldraw[fill=blue] (7, 3.1) circle [radius=0.1]; - \draw[blue] (7.2, 2.8) node {\Large $C$}; - - % P - \filldraw[fill=blue] (7, -1.3) circle [radius=0.1]; - \draw[blue] (7, -1.7) node {\Large $P$}; - - % l - \draw[<->, thick, black] (7,3) -- (7, -1.2) node[midway,above] {\large $l$}; - \end{scope} - - % f_x - \draw[<-, thick, blue!70!black] (4.3,3.1) -- (6.9, 3.1) node[midway,above] {\large $f_x$}; - - % g - \draw[->, thick, blue!70!black] (9.2, 6.81) -- (9.2, 5.2) node[midway,right] {\large $g$}; - - % \theta - \draw[->, thick, orange!70!black] (7, 2.4) arc [start angle=-90, end angle=60, radius=0.7]; - \fill[->, opacity=0.2, orange!70!black] (7, 3.1) -- (7, 2.4) arc [start angle=-90, end angle=60, radius=0.7]; - \draw[thick, orange!70!black] (7.8, 2.8) node {\large $\theta$}; - - % m_C - \draw[red!60!black] (5, 5.3) node {\large $m_C$}; - - % m_P - \draw[green!40!black] (10.6, 10.5) node {\large $m_P$}; - - % formula - \draw (2,9) node[fill=yellow!30, draw, rounded corners] {\LARGE $\ddot{\theta} = - \frac{\ddot{x} \cos \theta + g \sin \theta}{l + \frac{I_p}{m_pl}}$}; -\end{tikzpicture} -\end{document} \ No newline at end of file diff --git a/docs/tex/derivation_cart_pole.tex b/docs/tex/derivation_cart_pole.tex deleted file mode 100644 index 19d8f97..0000000 --- a/docs/tex/derivation_cart_pole.tex +++ /dev/null @@ -1,180 +0,0 @@ -\documentclass[unicode]{article} - -\usepackage[utf8]{inputenc} -\usepackage{standalone} -\usepackage{color} -\usepackage{amsmath} -\usepackage{graphics} -\usepackage[colorlinks,urlcolor=blue]{hyperref} -\usepackage{tikz} -\usepackage{tikz-3dplot} -\usetikzlibrary{decorations.pathreplacing,calligraphy} - -\textheight=26cm -\textwidth=18cm -\oddsidemargin=-1cm -\topmargin=-2.5cm - -\newcommand{\pmat}[1]{\begin{pmatrix}#1\end{pmatrix}} - -\begin{document} - -\section{Classic Cart Pole} - -\subsection{Dynamic} - -\begin{center} - \input{classic_cart_pole.tex} -\end{center} - -Coordinates of points and their derivatives -\begin{align*} - & C = \pmat{x \\ 0}; & &\dot{C} = \pmat{\dot{x} \\ 0}; \\ - & P = \pmat{x + l \sin \theta \\ - l \cos \theta}; & &\dot{P} = \pmat{\dot{x} + l \dot{\theta} \cos \theta \\ l \dot{\theta} \sin \theta}; -\end{align*} - -Then the kinetic energy of the carriage is -\[ - T_C = \frac{1}{2} m_c \begin{Vmatrix} - \dot{C} - \end{Vmatrix}_2^2 = \frac{1}{2} m_c \dot{x}^2 -\] - - -Kinetic energy of the pendulum -\begin{align*} - T_p & = T^t_p + T^r_p = \\ - & = \frac{1}{2} m_p \begin{Vmatrix}\dot{P}\end{Vmatrix}_2^2 + \frac{1}{2}I_p\dot{\theta}^2 = \\ - & = \frac{1}{2} m_p (\dot{x} + l \dot{\theta} \cos \theta )^2 + \frac{1}{2} m_p (l \dot{\theta} \sin \theta)^2 + \frac{1}{2}I_p\dot{\theta}^2 = \\ - & = \frac{1}{2} m_p \dot{x}^2 + m_p \dot{x} l \dot{\theta} \cos \theta + \frac{1}{2} \dot{\theta}^2 \left( m_p l^2 + I_p \right) \\ -\end{align*} - -Then the kinetic and potential energy of the whole system -\begin{align*} - T & = T_c + T_p = \\ - & = \frac{1}{2} m_c \dot{x}^2 + \frac{1}{2} m_p \dot{x}^2 + m_p \dot{x} l \dot{\theta} \cos \theta + \frac{1}{2} \dot{\theta}^2 \left( m_p l^2 + I_p \right) \\ - & = \frac{1}{2} \dot{x}^2 (m_c + m_p) + m_p \dot{x} l \dot{\theta} \cos \theta + \frac{1}{2} \dot{\theta}^2 \left( m_p l^2 + I_p \right) \\ - & \\ - U & = \underbrace{U_c}_{0} + U_p = -m_p gl \cos \theta \\ -\end{align*} - -To calculate the dynamics of the system we will use the Euler-Lagrange differential equation -\[ - \frac{d}{dt} \frac{dL}{d\dot{q}} - \frac{dL}{dq} = Q -\] -where \( L = T - U \), \(Q\) is the generalized force and \(q = \pmat{x \\ \theta}\). From this we derive the equation of motion - -\[ - \begin{cases} - m_p \ddot{x} l \cos \theta + \ddot{\theta} \left(m_p l^2 + I_p\right) + m_p g l \sin \theta = 0 \\ - \ddot{x}(m_c + m_p) + m_p l \ddot{\theta} \cos \theta - m_p l \dot{\theta}^2 \sin \theta = f_{x} - \end{cases} -\] - -A more detailed calculation is below - -\[ - L = \frac{1}{2} \dot{x}^2 (m_c + m_p) + m_p \dot{x} l \dot{\theta} \cos \theta + \frac{1}{2} \dot{\theta}^2 \left( m_p l^2 + I_p \right) + m_p gl \cos \theta -\] - -\begin{align*} - \frac{dL}{d\theta} & = - m_p \dot{x} l \dot{\theta} \sin \theta - m_p gl \sin \theta \\ - \frac{dL}{d\dot{\theta}} & = m_p \dot{x} l \cos \theta + \dot{\theta} \left(m_p l^2 + I_p\right) \\ - \frac{d}{dt} \frac{dL}{d\dot{\theta}} & = m_p \ddot{x} l \cos \theta - m_p \dot{x} l \dot{\theta} \sin \theta + \ddot{\theta} \left(m_p l^2 + I_p\right) \\ - \frac{d}{dt} \frac{dL}{d\dot{\theta}} - \frac{dL}{d\theta} & = m_p \ddot{x} l \cos \theta - m_p \dot{x} l \dot{\theta} \sin \theta + \ddot{\theta} \left(m_p l^2 + I_p\right) + m_p \dot{x} l \dot{\theta} \sin \theta + m_p gl \sin \theta = \\ - & = m_p \ddot{x} l \cos \theta + \ddot{\theta} \left(m_p l^2 + I_p\right) + m_p g l \sin \theta \\ - & \\ - \frac{dL}{dx} & = 0 \\ - \frac{dL}{d\dot{x}} & = \dot{x}(m_c + m_p) + m_p l \dot{\theta} \cos \theta \\ - \frac{d}{dt} \frac{dL}{d\dot{x}} & = \ddot{x}(m_c + m_p) + m_p l \ddot{\theta} \cos \theta - m_p l \dot{\theta}^2 \sin \theta \\ - \frac{d}{dt} \frac{dL}{d\dot{x}} - \frac{dL}{dx} & = \ddot{x}(m_c + m_p) + m_p l \ddot{\theta} \cos \theta - m_p l \dot{\theta}^2 \sin \theta \\ -\end{align*} - -\subsection{Controlling acceleration} - -Convert the second equation in the resulting system - -\[ - \begin{cases} - m_p \ddot{x} l \cos \theta + \ddot{\theta} \left(m_p l^2 + I_p\right) + m_p g l \sin \theta = 0 \\ - \ddot{x} = \frac{f_{x} - m_p l \ddot{\theta} \cos \theta + m_p l \dot{\theta}^2 \sin \theta}{m_c + m_p} - \end{cases} -\] - -Consider that we can obtain any such \(f_x\) at any time that \(\ddot{x}\) can take any value from \([-a, a]\). Then the second equality does not make sense further, instead we can consider the first one - -\[ - m_p \ddot{x} l \cos \theta + \ddot{\theta} \left(m_p l^2 + I_p\right) + m_p g l \sin \theta = 0 -\] -\[ - \ddot{\theta} = - \frac{m_p \ddot{x} l \cos \theta + m_p g l \sin \theta}{m_p l^2 + I_p} = - \frac{\ddot{x} \cos \theta + g \sin \theta}{l + \frac{I_p}{m_pl}} -\] - -It turns out that the equation of motion is described by this equation, where \(\ddot{x}\) is given by any in the segment \([-a, a]\). - -\subsection{Friction} -The friction affecting \(\ddot{x}\) is not considered, since it is given by any number from the segment \([-a, a]\). One can introduce friction on \(\ddot{\theta}\) of the general form \(f(\theta, \dot{\theta})\) (for example, linear from angular velocity \(f(\theta, \dot{\theta}) = \mu \dot{\theta}\), where \(\mu\) is a constant), then the equation of motion rewrites as -\[ - \ddot{\theta} = - \frac{\ddot{x} \cos \theta + g \sin \theta}{l + \frac{I_p}{m_pl}} + f(\theta, \dot{\theta}) -\] - -\newpage -\section{Radial Cart Pole} - -\begin{center} - \input{radial_cart_pole.tex} -\end{center} - -In this problem, too, we consider that we control \(\ddot{\phi}\) instead of \(f_{\phi}\) at once, which means that the Euler-Lagrange can be derived only by the coordinate \(\theta\) - -\[ - \frac{d}{dt} \frac{dL}{d\dot{\theta}} - \frac{dL}{d\theta} = 0 -\] - -After calculating all the components we obtain the equation - -\[ - \ddot{\theta} = - \frac{\ddot{\phi} r \cos \theta + g\sin \theta}{l_p + \frac{I_p}{m_p l_p}} -\] - -A more detailed calculation - -\[ - T_r = \frac{1}{2}\dot{\phi}^2(I_r + m_rl_r^2) -\] -\[ - T_p = T_p^t + T_p^c -\] - -Note that \(T_p^c = \frac{1}{2}I_p\dot{\theta}^2\) and \(T_p^t = \frac{1}{2}m_p\begin{Vmatrix} \dot{P} \end{Vmatrix}_2^2\). To calculate \(\begin{Vmatrix} \dot{P} \end{Vmatrix}_2^2\), consider the system with respect to the coordinate system in the figure below -\begin{center} - \input{radial_cart_pole_helper.tex} -\end{center} -velocity \(\begin{Vmatrix} \dot{P} \end{Vmatrix}_2^2\) is decomposed by the coordinates \(y\) and \(z\), we get that -\[ - \begin{Vmatrix} \dot{P} \end{Vmatrix}_2^2 = \left(\underbrace{\dot{\phi} r + \dot{\theta} l_p \cos \theta }_{\dot{y}}\right)^2 + \left(\underbrace{\dot{\theta} l_p \sin \theta}_{\dot{z}} \right)^2 = \dot{\phi}^2 r^2 + 2 \dot{\phi} \dot{\theta} r l_p \cos \theta + \dot{\theta}^2 l_p^2 -\] - -It remains to do the trivial calculations -\[ - T_p = \frac{1}{2}I_p\dot{\theta}^2 + \frac{1}{2}m_p\left(\dot{\phi}^2 r^2 + 2 \dot{\phi} \dot{\theta} r l_p \cos \theta + \dot{\theta}^2 l_p^2\right) -\] -\[ - T = T_r + T_p = \frac{1}{2}\dot{\phi}^2(I_r + m_rl_r^2) + \frac{1}{2}I_p\dot{\theta}^2 + \frac{1}{2}m_p\left(\dot{\phi}^2 r^2 + 2 \dot{\phi} \dot{\theta} r l_p \cos \theta + \dot{\theta}^2 l_p^2\right) -\] -\[ - U = \left( \underbrace{U_r}_{0} + U_p \right) = - m_p g l_p \cos \theta -\] -\[ - L = T - U = \frac{1}{2}\dot{\phi}^2(I_r + m_rl_r^2) + \frac{1}{2} I_p \dot{\theta}^2 + \frac{1}{2} m_p \left(\dot{\phi}^2 r^2 + 2 \dot{\phi} \dot{\theta} r l_p \cos \theta + \dot{\theta}^2 l_p^2\right) + m_p g l_p \cos \theta -\] -\begin{align*} - \frac{dL}{d\theta} & = - m_p l_p (r \dot{\phi} \dot{\theta} \sin \theta + g \sin \theta) \\ - \frac{dL}{d\dot{\theta}} & = I_p \dot{\theta} + m_p l_p (\dot{\phi} r \cos \theta + l_p \dot{\theta}) \\ - \frac{d}{dt} \frac{dL}{d\dot{\theta}} & = I_p \ddot{\theta} + m_p l_p (r \ddot{\phi} \cos \theta + l_p \ddot{\theta} - r \dot{\phi} \dot{\theta} \sin \theta) \\ - \frac{d}{dt} \frac{dL}{d\dot{\theta}} - \frac{dL}{d\theta} & = - I_p \ddot{\theta} + m_p l_p (r \ddot{\phi} \cos \theta + l_p \ddot{\theta} - r \dot{\phi} \dot{\theta} \sin \theta) + m_p l_p (r \dot{\phi} \dot{\theta} \sin \theta + g \sin \theta) = \\ - & = I_p \ddot{\theta} + m_p l_p (r \ddot{\phi} \cos \theta + l_p \ddot{\theta}) + m_p l_p g \sin \theta = \\ - & = \ddot{\theta} (I_p + m_p l_p^2) + m_p l_p (r \ddot{\phi} \cos \theta + g \sin \theta) = 0 -\end{align*} -\end{document} \ No newline at end of file diff --git a/docs/tex/linear_cart_pole.tex b/docs/tex/linear_cart_pole.tex new file mode 100644 index 0000000..5bb809a --- /dev/null +++ b/docs/tex/linear_cart_pole.tex @@ -0,0 +1,62 @@ +\documentclass[dvisvgm,tikz]{standalone} + +\usepackage{amsmath} +\usepackage{mathpazo} +\usepackage[utf8]{inputenc} +\usepackage{graphics} +\usepackage[colorlinks,urlcolor=blue]{hyperref} +\usepackage{standalone} +\usepackage{svg} +\usepackage{tikz} + +\usetikzlibrary{arrows.meta,decorations.pathreplacing,calligraphy} +\special{background White} + +\begin{document} +\begin{tikzpicture}[>=stealth] + % world + \draw[->, thick] (-1,3.1) -- (15,3.1) node[right] {\Large $x$}; + \draw[-, thick] (7,0.5) -- (7,5.7); + + % hull + \filldraw[red!100!black, fill=white, line width=5] (4.0,1.7) rectangle (10.0,4.5); + + % y axis help + \draw[-, dashed] (7,1.2) -- (7,5.0); + + % stick + \begin{scope}[rotate around={150:(7, 3.1)}] + \filldraw[green!80!black, fill=green!80!black] (6.8, 3.4) rectangle (7.2, -6); + + % C + \node[circle, fill=blue, opacity=0.6, scale=0.5, label={above left:{\textcolor{blue}{$C$}}}] at (7, 3.1) {}; + + % P + \node[circle, fill=blue, opacity=0.6, scale=0.5, label={above left:{\textcolor{blue}{$P$}}}] at (7, -1.3) {}; + + % l + \draw[<->, thick, black] (7,3) -- (7, -1.2) node[midway,above] {\large $l$}; + \end{scope} + + % f_x + \draw[<-, thick, blue!70!black] (4.3,3.1) -- (6.9, 3.1) node[midway,above] {\large $f_x$}; + + % g + \draw[->, thick, blue!70!black] (9.2, 6.81) -- (9.2, 5.2) node[midway,right] {\large $g$}; + + % \theta + \draw[->, thick, orange!70!black] (7, 2.4) arc [start angle=-90, end angle=60, radius=0.7]; + \fill[->, opacity=0.2, orange!70!black] (7, 3.1) -- (7, 2.4) arc [start angle=-90, end angle=60, radius=0.7]; + \draw[thick, orange!70!black] (7.8, 2.8) node {\large $\theta$}; + + % m_C + \draw[red!60!black] (5, 2.3) node {\large $m_c$}; + + % m_P + \draw[green!40!black] (10.6, 10.5) node {\large $m_p$}; + + % formula + \draw (4,8) node[fill=yellow!30, draw, rounded corners] {\Large $\ddot{\theta} = -b\dot{\theta} - k \big(\ddot{x} \cos \theta + g \sin \theta\big)$}; + \draw (2,4) node[fill=yellow!30, draw, rounded corners] {\Large $\ddot{x} = u$}; +\end{tikzpicture} +\end{document} diff --git a/docs/tex/logo.png b/docs/tex/logo.png new file mode 100644 index 0000000..e6db7e7 Binary files /dev/null and b/docs/tex/logo.png differ diff --git a/docs/tex/radial_cart_pole.tex b/docs/tex/radial_cart_pole.tex index 77a7bc5..4d51588 100644 --- a/docs/tex/radial_cart_pole.tex +++ b/docs/tex/radial_cart_pole.tex @@ -1,15 +1,25 @@ -\documentclass[dvisvgm]{standalone} - +\documentclass[dvisvgm,tikz]{standalone} + +\usepackage{amsmath} +\usepackage{mathpazo} +\usepackage[utf8]{inputenc} +\usepackage{graphics} +\usepackage[colorlinks,urlcolor=blue]{hyperref} +\usepackage{standalone} +\usepackage{svg} \usepackage{tikz} \usepackage{tikz-3dplot} -\usetikzlibrary{decorations.pathreplacing,calligraphy} +\usetikzlibrary{arrows.meta,decorations.pathreplacing,calligraphy} + +\usetikzlibrary{arrows.meta} +\special{background White} \begin{document} % camera params \tdplotsetmaincoords{70}{110} -\begin{tikzpicture}[tdplot_main_coords, scale = 10] +\begin{tikzpicture}[tdplot_main_coords, scale = 10, >=stealth] % EPSILON \pgfmathsetmacro{\e}{0.001} @@ -67,7 +77,6 @@ \draw[dashed, canvas is zx plane at y=\a] (-180-\beta:0) -- (-180-\beta:\thetarad); \draw[canvas is zx plane at y=\a, orange!70!black] ({(-180-\beta)/2}:\thetarad+0.02) node {$\theta$}; - % red-green right angle \draw[canvas is yz plane at x=0] (\a-\rs,0) -- (\a-\rs,\rs) -- (\a, \rs); @@ -81,6 +90,7 @@ \draw[orange!70!black] ({(80+\alpha)/2}:\phirad+0.05) node {$\phi$}; % formula - \draw (0.0,0.4,0.6) node[fill=yellow!30, draw, rounded corners] {\LARGE $\ddot{\theta} = - \frac{\ddot{\phi} r \cos \theta + g\sin \theta}{l_p + \frac{I_p}{m_p l_p}}$}; + \draw (0.0,0.4,0.5) node[fill=yellow!30, draw, rounded corners] {\large $\ddot{\theta} = - b\dot{\theta} - k \big( \ddot{\phi} r \cos \theta + g\sin \theta \big) $}; + \draw (0.0,0.21,0.35) node[fill=yellow!30, draw, rounded corners] {\large $\ddot{\phi} = u$}; \end{tikzpicture} -\end{document} \ No newline at end of file +\end{document} diff --git a/docs/tex/radial_cart_pole_helper.tex b/docs/tex/radial_cart_pole_helper.tex index 39c162f..4318b3b 100644 --- a/docs/tex/radial_cart_pole_helper.tex +++ b/docs/tex/radial_cart_pole_helper.tex @@ -1,85 +1,76 @@ \documentclass[dvisvgm,tikz]{standalone} - + +\usepackage{amsmath} +\usepackage{mathpazo} +\usepackage[utf8]{inputenc} +\usepackage{graphics} +\usepackage[colorlinks,urlcolor=blue]{hyperref} +\usepackage{standalone} +\usepackage{svg} \usepackage{tikz} \usepackage{tikz-3dplot} -\usetikzlibrary{decorations.pathreplacing,calligraphy} + +\usetikzlibrary{arrows.meta,decorations.pathreplacing,calligraphy} +\special{background White} \begin{document} % camera params \tdplotsetmaincoords{70}{110} - -\begin{tikzpicture}[tdplot_main_coords, scale = 10] + +\begin{tikzpicture}[tdplot_main_coords, scale = 10, >=stealth] % EPSILON \pgfmathsetmacro{\e}{0.001} - + % rotate sticks params \pgfmathsetmacro{\alpha}{-30} \pgfmathsetmacro{\beta}{-40} - + % first stick params \pgfmathsetmacro{\a}{0.8} \pgfmathsetmacro{\aext}{0.1} \pgfmathsetmacro{\phirad}{0.15} - + % second stick params \pgfmathsetmacro{\b}{0.5} \pgfmathsetmacro{\bext}{0.1} \pgfmathsetmacro{\thetarad}{0.08} - + % right angles size \pgfmathsetmacro{\rs}{0.03} - + % world axis params - \draw[->] (0,0,0) -- (1,0,0) node[anchor=north east]{\large $x$}; - \draw[->] (0,0,0) -- (0,1,0) node[anchor=north west]{\large $y$}; - \draw[->] (0,0,0) -- (0,0,0.7) node[anchor=south]{\large $z$}; - + \draw[-] (0,0,0) -- (1,0,0); + \draw[-] (0,0,0) -- (0,1,0); + \draw[-] (0,0,0) -- (0,0,0.4); + \draw[dashed, canvas is xy plane at z=0] (\a,0) arc[start angle=0, end angle=90, radius=\a]; - + \tdplotsetrotatedcoords{\alpha}{\beta}{0} \begin{scope}[tdplot_rotated_coords] - % l_r - \draw[pen colour={gray}, line width=0.8, decorate, decoration = {calligraphic brace, raise=5, amplitude=4}] (0, 0, 0.002) -- (0, {(\a - \aext)/2 - 0.02}, 0.002); - \draw[gray] (0, {(\a - \aext)/4}, 0.06) node {$l_r$}; - - % r - \draw[pen colour={gray}, line width=0.8, decorate, decoration = {calligraphic brace, raise=5, amplitude=4}] (0, {\a - 0.02}, -0.002) -- (0, 0, -0.002); - \draw[gray] (0, \a / 2, -0.06) node {$r$}; - - % l_p - \draw[pen colour={gray}, line width=0.8, decorate, decoration = {calligraphic brace, raise=5, amplitude=4}] (0.02, \a, 0.01) -- (0.02, \a, {\b/2 - 0.01}); - \draw[gray] (0.09, \a, {\b/4 - 0.01}) node {$l_p$}; - % red stick \draw[line width=3, color=red!100!black] (0, -\aext, 0) -- (0, \a, 0); \path[canvas is zx plane at y={(\a-\aext)/2}] (0,0,0) node[color=blue, circle, fill, inner sep=2]{}; - \draw[blue, canvas is zx plane at y={(\a-\aext)/2}] (0.04, -0.02) node {\Large $R$}; - + \draw[blue, canvas is zx plane at y={(\a-\aext)/2}] (0.04, -0.02) node {\Large \(R\)}; + % green stick \draw[line width=3, color=green!80!black] (0, \a, -\bext) -- (0, \a, \b+\bext); \path[canvas is zx plane at y=\a] ({\b/2},0) node[color=blue, circle, fill, inner sep=2]{}; - \draw[blue, canvas is zx plane at y=\a] ({\b/2 + 0.01}, 0.03) node {\Large $P$}; - - % theta angle - \draw[<-, thick, orange!70!black, canvas is zx plane at y=\a] (\thetarad, 0) arc [start angle=0, end angle=-180-\beta, radius=\thetarad]; - \fill[<-, orange!70!black, opacity=0.2, canvas is zx plane at y=\a] (0, 0) -- (\thetarad, 0) arc [start angle=0, end angle=-180-\beta, radius=\thetarad]; - \draw[dashed, canvas is zx plane at y=\a] (-180-\beta:0) -- (-180-\beta:\thetarad); - \draw[canvas is zx plane at y=\a, orange!70!black] ({(-180-\beta)/2}:\thetarad+0.02) node {$\theta$}; - - - % red-green right angle - \draw[canvas is yz plane at x=0] (\a-\rs,0) -- (\a-\rs,\rs) -- (\a, \rs); - - % green right angle - \draw[canvas is zx plane at y=\a] (-180-\beta:\rs) -- (-135-\beta:{sqrt(2)*\rs}) -- (-90-\beta:\rs); + \draw[blue, canvas is zx plane at y=\a] ({\b/2 + 0.01}, 0.03) node {\Large \(P\)}; + \end{scope} + + % axes + \tdplotsetrotatedcoords{\alpha}{0}{0} + \begin{scope}[tdplot_rotated_coords] + % x' + \draw[->, canvas is xz plane at y=\a] (0.2, 0) -- (-0.2, 0) node[anchor= west]{$x'$}; + + % y' + \draw[->, canvas is xz plane at y=\a] (0, -0.2) -- (0, 0.2) node[anchor= west]{$y'$}; \end{scope} - + % phi angle \draw[->, thick, orange!70!black] (\phirad, 0) arc [start angle=0, end angle=90+\alpha, radius=\phirad]; \fill[->, opacity=0.2, orange!70!black] (0, 0) -- (\phirad, 0) arc [start angle=0, end angle=90+\alpha, radius=\phirad]; - \draw[orange!70!black] ({(80+\alpha)/2}:\phirad+0.05) node {$\phi$}; - - % formula - \draw (0.0,0.4,0.6) node[fill=yellow!30, draw, rounded corners] {\LARGE $\ddot{\theta} = - \frac{\ddot{\phi} r \cos \theta + g\sin \theta}{l_p + \frac{I_p}{m_p l_p}}$}; -\end{tikzpicture} -\end{document} \ No newline at end of file + \draw[orange!70!black] ({(80+\alpha)/2}:\phirad+0.05) node {\(\phi\)}; + \end{tikzpicture} +\end{document} diff --git a/examples/foxglove_log.py b/examples/foxglove_log.py new file mode 100644 index 0000000..3310a4c --- /dev/null +++ b/examples/foxglove_log.py @@ -0,0 +1,26 @@ +import cartpole.log as log + +from pydantic import BaseModel + +import random +import time + + +# message must be inherited from BaseModel +class RandMsg(BaseModel): + dist: str = 'uniform(0, 1)' + value: float = 0.0 + +foxglove = log.FoxgloveWebsocketLogger(log.DEBUG) + +for i in range(100): + stamp = time.time() + x = random.uniform(0, 1) + + # publish message, timestamp is optional (default is current time) + foxglove.publish('/random', RandMsg(value=x), stamp) + + # print message to console and log (see /log topic) + foxglove.info(f'publish {x:.2f}', stamp) + + time.sleep(0.2) diff --git a/examples/log.py b/examples/log.py new file mode 100644 index 0000000..63f5a46 --- /dev/null +++ b/examples/log.py @@ -0,0 +1,30 @@ + +import cartpole.log as log + +from pydantic import BaseModel + +import random +import time + +# all messages must be inherited from BaseModel +class RandMsg(BaseModel): + dist: str = 'uniform(0, 1)' + value: float = 0.0 + +# define log file name +log.setup(log_path='log_example.mcap', level=log.DEBUG) + +# messages are available in real time in foxglove (websocket mode) +for i in range(10): + value = random.uniform(0, 1) + + # publish message, timestamp is optional (default is current time) + log.publish('/random', RandMsg(value=value)) + + # print message to console and log (see /log topic) + log.info(f'publish {value:.2f}') + + # add some delay for demo purposes + time.sleep(0.2) + + diff --git a/examples/mcap_log.py b/examples/mcap_log.py new file mode 100644 index 0000000..e91cd47 --- /dev/null +++ b/examples/mcap_log.py @@ -0,0 +1,24 @@ +import cartpole.log as log + +from pydantic import BaseModel + +import random +import time + + +# message must be inherited from BaseModel +class RandMsg(BaseModel): + dist: str = 'uniform(0, 1)' + value: float = 0.0 + +mcap = log.MCAPLogger('log_example.mcap', log.DEBUG) + +for i in range(10): + stamp = time.time() + x = random.uniform(0, 1) + + # publish message, timestamp is optional (default is current time) + mcap.publish('/random', RandMsg(value=x), stamp) + + # print message to console and log (see /log topic) + mcap.info(f'publish {x:.2f}', stamp) diff --git a/examples/simulation.py b/examples/simulation.py new file mode 100644 index 0000000..a556ad8 --- /dev/null +++ b/examples/simulation.py @@ -0,0 +1,30 @@ +from cartpole import Error, State +from cartpole import Simulator +from cartpole import log + +import time + +# set simulation step as 0.05 seconds +delta = 0.05 + +# setup logging (look at mcap logs after simulation) +log.setup(log_path='simulation_example.mcap') + +# create simulator with default config +cartpole = Simulator() + +# reset simulator to initial state +cartpole.reset(state=State(cart_position=0, pole_angle=2)) + +# run simulation +for _ in range(1000): + # use for loggin simulation time instead of real time + state = cartpole.get_state() + + # log system state and simulator info + log.publish('/cartpole/state', state, state.stamp) + + # make simulation step + cartpole.advance(delta) + time.sleep(delta) + diff --git a/layouts/default.json b/layouts/default.json new file mode 100644 index 0000000..b8cb682 --- /dev/null +++ b/layouts/default.json @@ -0,0 +1,88 @@ +{ + "configById": { + "RawMessages!3ix6wfo": { + "diffEnabled": false, + "diffMethod": "custom", + "diffTopicPath": "", + "showFullMessageForDiff": false, + "topicPath": "/cartpole/info" + }, + "Plot!c57nav": { + "title": "Cart", + "paths": [ + { + "value": "/cartpole/state.cart_position", + "enabled": true, + "timestampMethod": "receiveTime" + }, + { + "value": "/cartpole/state.cart_velocity", + "enabled": true, + "timestampMethod": "receiveTime" + }, + { + "value": "/cartpole/state.cart_acceleration", + "enabled": true, + "timestampMethod": "receiveTime" + } + ], + "minYValue": -3, + "maxYValue": 3, + "showXAxisLabels": false, + "showYAxisLabels": true, + "showLegend": false, + "legendDisplay": "floating", + "showPlotValuesInLegend": false, + "isSynced": true, + "xAxisVal": "timestamp", + "sidebarDimension": 240, + "followingViewWidth": 7 + }, + "Plot!2myeztf": { + "title": "Pole", + "paths": [ + { + "value": "/cartpole/state.pole_angle", + "enabled": true, + "timestampMethod": "receiveTime" + }, + { + "value": "/cartpole/state.pole_angular_velocity", + "enabled": true, + "timestampMethod": "receiveTime" + } + ], + "showXAxisLabels": false, + "showYAxisLabels": true, + "showLegend": false, + "legendDisplay": "floating", + "showPlotValuesInLegend": false, + "isSynced": true, + "xAxisVal": "timestamp", + "sidebarDimension": 240, + "followingViewWidth": 7 + }, + "CartPole Panel.CartPole Panel!3hli21y": {} + }, + "globalVariables": {}, + "userNodes": {}, + "linkedGlobalVariables": [], + "playbackConfig": { + "speed": 1 + }, + "layout": { + "direction": "row", + "first": { + "first": { + "first": "RawMessages!3ix6wfo", + "second": "Plot!c57nav", + "direction": "column" + }, + "second": "Plot!2myeztf", + "direction": "column", + "splitPercentage": 65.14522821576763 + }, + "second": "CartPole Panel.CartPole Panel!3hli21y", + "splitPercentage": 38.66090712742981 + } +} \ No newline at end of file diff --git a/layouts/log_example.json b/layouts/log_example.json new file mode 100644 index 0000000..79b8ee9 --- /dev/null +++ b/layouts/log_example.json @@ -0,0 +1,43 @@ +{ + "configById": { + "Plot!3l785jp": { + "title": "Uniform", + "paths": [ + { + "value": "/random.value", + "enabled": true, + "timestampMethod": "receiveTime" + } + ], + "minYValue": -0.1, + "maxYValue": 1.1, + "showXAxisLabels": true, + "showYAxisLabels": true, + "showLegend": true, + "legendDisplay": "floating", + "showPlotValuesInLegend": true, + "isSynced": true, + "xAxisVal": "timestamp", + "sidebarDimension": 240, + "followingViewWidth": 10 + }, + "RawMessages!29nyppp": { + "diffEnabled": false, + "diffMethod": "custom", + "diffTopicPath": "", + "showFullMessageForDiff": false, + "topicPath": "/random" + } + }, + "globalVariables": {}, + "userNodes": {}, + "linkedGlobalVariables": [], + "playbackConfig": { + "speed": 1 + }, + "layout": { + "direction": "row", + "first": "RawMessages!29nyppp", + "second": "Plot!3l785jp" + } +} \ No newline at end of file diff --git a/mkdocs.yml b/mkdocs.yml new file mode 100644 index 0000000..a5b5e5c --- /dev/null +++ b/mkdocs.yml @@ -0,0 +1,81 @@ +site_name: CartPole +site_url: https://robotics-laboratory.github.io/cart-pole/ +repo_url: https://github.com/robotics-laboratory/cart-pole/ +repo_name: robotics-laboratory/cart-pole + +nav: + - Quickstart: quickstart.md + - Dynamics: dynamics.md + - Reference: + - reference/common.md + - reference/log.md + - reference/simulator.md + +theme: + name: material + palette: + primary: deep orange + features: + - content.code.copy + - content.tabs.link + +extra: + version: + default: latest + provider: mike + +markdown_extensions: + - admonition + - attr_list + - def_list + - md_in_html + - pymdownx.details + - pymdownx.highlight: + anchor_linenums: true + line_spans: __span + pygments_lang_class: true + - pymdownx.inlinehilite + - pymdownx.snippets + - pymdownx.superfences + - pymdownx.tabbed: + alternate_style: true + - pymdownx.arithmatex: + generic: true + - pymdownx.emoji: + emoji_index: !!python/name:materialx.emoji.twemoji + emoji_generator: !!python/name:materialx.emoji.to_svg + - pymdownx.superfences: + custom_fences: + - name: mermaid + class: mermaid + format: !!python/name:pymdownx.superfences.fence_code_format + - toc: + toc_depth: 2 + + +extra_css: + - https://tikzjax.com/v1/fonts.css + +extra_javascript: + - js/mathjax.js + - https://polyfill.io/v3/polyfill.min.js?features=es6 + - https://cdn.jsdelivr.net/npm/mathjax@3/es5/tex-mml-chtml.js + - https://tikzjax.com/v1/tikzjax.js + +plugins: + - search + - mkdocstrings: + default_handler: python + handlers: + python: + options: + allow_inspection: false + docstring_section_style: spacy + docstring_style: numpy + heading_level: 2 + line_length: 100 + members_order: source + show_bases: false + show_root_heading: true + show_signature_annotations: true + show_source: true diff --git a/poetry.lock b/poetry.lock deleted file mode 100644 index 1455854..0000000 --- a/poetry.lock +++ /dev/null @@ -1,2541 +0,0 @@ -[[package]] -name = "anyio" -version = "3.6.2" -description = "High level compatibility layer for multiple asynchronous event loop implementations" -category = "dev" -optional = false -python-versions = ">=3.6.2" - -[package.dependencies] -idna = ">=2.8" -sniffio = ">=1.1" - -[package.extras] -doc = ["packaging", "sphinx-autodoc-typehints (>=1.2.0)", "sphinx-rtd-theme"] -test = ["contextlib2", "coverage[toml] (>=4.5)", "hypothesis (>=4.0)", "mock (>=4)", "pytest (>=7.0)", "pytest-mock (>=3.6.1)", "trustme", "uvloop (<0.15)", "uvloop (>=0.15)"] -trio = ["trio (>=0.16,<0.22)"] - -[[package]] -name = "appnope" -version = "0.1.3" -description = "Disable App Nap on macOS >= 10.9" -category = "main" -optional = false -python-versions = "*" - -[[package]] -name = "argon2-cffi" -version = "21.3.0" -description = "The secure Argon2 password hashing algorithm." -category = "dev" -optional = false -python-versions = ">=3.6" - -[package.dependencies] -argon2-cffi-bindings = "*" - -[package.extras] -dev = ["cogapp", "coverage[toml] (>=5.0.2)", "furo", "hypothesis", "pre-commit", "pytest", "sphinx", "sphinx-notfound-page", "tomli"] -docs = ["furo", "sphinx", "sphinx-notfound-page"] -tests = ["coverage[toml] (>=5.0.2)", "hypothesis", "pytest"] - -[[package]] -name = "argon2-cffi-bindings" -version = "21.2.0" -description = "Low-level CFFI bindings for Argon2" -category = "dev" -optional = false -python-versions = ">=3.6" - -[package.dependencies] -cffi = ">=1.0.1" - -[package.extras] -dev = ["cogapp", "pre-commit", "pytest", "wheel"] -tests = ["pytest"] - -[[package]] -name = "asttokens" -version = "2.1.0" -description = "Annotate AST trees with source code positions" -category = "main" -optional = false -python-versions = "*" - -[package.dependencies] -six = "*" - -[package.extras] -test = ["astroid (<=2.5.3)", "pytest"] - -[[package]] -name = "attrs" -version = "22.1.0" -description = "Classes Without Boilerplate" -category = "dev" -optional = false -python-versions = ">=3.5" - -[package.extras] -dev = ["cloudpickle", "coverage[toml] (>=5.0.2)", "furo", "hypothesis", "mypy (>=0.900,!=0.940)", "pre-commit", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "sphinx", "sphinx-notfound-page", "zope.interface"] -docs = ["furo", "sphinx", "sphinx-notfound-page", "zope.interface"] -tests = ["cloudpickle", "coverage[toml] (>=5.0.2)", "hypothesis", "mypy (>=0.900,!=0.940)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "zope.interface"] -tests-no-zope = ["cloudpickle", "coverage[toml] (>=5.0.2)", "hypothesis", "mypy (>=0.900,!=0.940)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins"] - -[[package]] -name = "backcall" -version = "0.2.0" -description = "Specifications for callback functions passed in to an API" -category = "main" -optional = false -python-versions = "*" - -[[package]] -name = "beautifulsoup4" -version = "4.11.1" -description = "Screen-scraping library" -category = "dev" -optional = false -python-versions = ">=3.6.0" - -[package.dependencies] -soupsieve = ">1.2" - -[package.extras] -html5lib = ["html5lib"] -lxml = ["lxml"] - -[[package]] -name = "bleach" -version = "5.0.1" -description = "An easy safelist-based HTML-sanitizing tool." -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -six = ">=1.9.0" -webencodings = "*" - -[package.extras] -css = ["tinycss2 (>=1.1.0,<1.2)"] -dev = ["Sphinx (==4.3.2)", "black (==22.3.0)", "build (==0.8.0)", "flake8 (==4.0.1)", "hashin (==0.17.0)", "mypy (==0.961)", "pip-tools (==6.6.2)", "pytest (==7.1.2)", "tox (==3.25.0)", "twine (==4.0.1)", "wheel (==0.37.1)"] - -[[package]] -name = "cffi" -version = "1.15.1" -description = "Foreign Function Interface for Python calling C code." -category = "main" -optional = false -python-versions = "*" - -[package.dependencies] -pycparser = "*" - -[[package]] -name = "colorama" -version = "0.4.6" -description = "Cross-platform colored terminal text." -category = "main" -optional = false -python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,!=3.6.*,>=2.7" - -[[package]] -name = "contourpy" -version = "1.0.6" -description = "Python library for calculating contours of 2D quadrilateral grids" -category = "main" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -numpy = ">=1.16" - -[package.extras] -bokeh = ["bokeh", "selenium"] -docs = ["docutils (<0.18)", "sphinx (<=5.2.0)", "sphinx-rtd-theme"] -test = ["Pillow", "flake8", "isort", "matplotlib", "pytest"] -test-minimal = ["pytest"] -test-no-codebase = ["Pillow", "matplotlib", "pytest"] - -[[package]] -name = "cycler" -version = "0.11.0" -description = "Composable style cycles" -category = "main" -optional = false -python-versions = ">=3.6" - -[[package]] -name = "dacite" -version = "1.6.0" -description = "Simple creation of data classes from dictionaries." -category = "main" -optional = false -python-versions = ">=3.6" - -[package.extras] -dev = ["black", "coveralls", "mypy", "pylint", "pytest (>=5)", "pytest-cov"] - -[[package]] -name = "debugpy" -version = "1.6.3" -description = "An implementation of the Debug Adapter Protocol for Python" -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "decorator" -version = "5.1.1" -description = "Decorators for Humans" -category = "main" -optional = false -python-versions = ">=3.5" - -[[package]] -name = "defusedxml" -version = "0.7.1" -description = "XML bomb protection for Python stdlib modules" -category = "dev" -optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" - -[[package]] -name = "drake" -version = "1.10.0" -description = "Model-based design and verification for robotics" -category = "main" -optional = true -python-versions = ">=3.8" - -[package.dependencies] -matplotlib = "*" -meshcat = "*" -numpy = "*" -pydot = "*" -PyYAML = "*" - -[[package]] -name = "entrypoints" -version = "0.4" -description = "Discover and load entry points from installed packages." -category = "dev" -optional = false -python-versions = ">=3.6" - -[[package]] -name = "exceptiongroup" -version = "1.0.4" -description = "Backport of PEP 654 (exception groups)" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.extras] -test = ["pytest (>=6)"] - -[[package]] -name = "executing" -version = "1.2.0" -description = "Get the currently executing AST node of a frame, and other information" -category = "main" -optional = false -python-versions = "*" - -[package.extras] -tests = ["asttokens", "littleutils", "pytest", "rich"] - -[[package]] -name = "fastjsonschema" -version = "2.16.2" -description = "Fastest Python implementation of JSON schema" -category = "dev" -optional = false -python-versions = "*" - -[package.extras] -devel = ["colorama", "json-spec", "jsonschema", "pylint", "pytest", "pytest-benchmark", "pytest-cache", "validictory"] - -[[package]] -name = "fonttools" -version = "4.38.0" -description = "Tools to manipulate font files" -category = "main" -optional = false -python-versions = ">=3.7" - -[package.extras] -all = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "fs (>=2.2.0,<3)", "lxml (>=4.0,<5)", "lz4 (>=1.7.4.2)", "matplotlib", "munkres", "scipy", "skia-pathops (>=0.5.0)", "sympy", "uharfbuzz (>=0.23.0)", "unicodedata2 (>=14.0.0)", "xattr", "zopfli (>=0.1.4)"] -graphite = ["lz4 (>=1.7.4.2)"] -interpolatable = ["munkres", "scipy"] -lxml = ["lxml (>=4.0,<5)"] -pathops = ["skia-pathops (>=0.5.0)"] -plot = ["matplotlib"] -repacker = ["uharfbuzz (>=0.23.0)"] -symfont = ["sympy"] -type1 = ["xattr"] -ufo = ["fs (>=2.2.0,<3)"] -unicode = ["unicodedata2 (>=14.0.0)"] -woff = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "zopfli (>=0.1.4)"] - -[[package]] -name = "idna" -version = "3.4" -description = "Internationalized Domain Names in Applications (IDNA)" -category = "dev" -optional = false -python-versions = ">=3.5" - -[[package]] -name = "importlib-metadata" -version = "5.0.0" -description = "Read metadata from Python packages" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -zipp = ">=0.5" - -[package.extras] -docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)"] -perf = ["ipython"] -testing = ["flake8 (<5)", "flufl.flake8", "importlib-resources (>=1.3)", "packaging", "pyfakefs", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=1.3)", "pytest-flake8", "pytest-mypy (>=0.9.1)", "pytest-perf (>=0.9.2)"] - -[[package]] -name = "iniconfig" -version = "1.1.1" -description = "iniconfig: brain-dead simple config-ini parsing" -category = "dev" -optional = false -python-versions = "*" - -[[package]] -name = "ipykernel" -version = "6.17.1" -description = "IPython Kernel for Jupyter" -category = "dev" -optional = false -python-versions = ">=3.8" - -[package.dependencies] -appnope = {version = "*", markers = "platform_system == \"Darwin\""} -debugpy = ">=1.0" -ipython = ">=7.23.1" -jupyter-client = ">=6.1.12" -matplotlib-inline = ">=0.1" -nest-asyncio = "*" -packaging = "*" -psutil = "*" -pyzmq = ">=17" -tornado = ">=6.1" -traitlets = ">=5.1.0" - -[package.extras] -docs = ["myst-parser", "pydata-sphinx-theme", "sphinx", "sphinxcontrib-github-alt"] -test = ["flaky", "ipyparallel", "pre-commit", "pytest (>=7.0)", "pytest-cov", "pytest-timeout"] - -[[package]] -name = "ipython" -version = "8.6.0" -description = "IPython: Productive Interactive Computing" -category = "main" -optional = false -python-versions = ">=3.8" - -[package.dependencies] -appnope = {version = "*", markers = "sys_platform == \"darwin\""} -backcall = "*" -colorama = {version = "*", markers = "sys_platform == \"win32\""} -decorator = "*" -jedi = ">=0.16" -matplotlib-inline = "*" -pexpect = {version = ">4.3", markers = "sys_platform != \"win32\""} -pickleshare = "*" -prompt-toolkit = ">3.0.1,<3.1.0" -pygments = ">=2.4.0" -stack-data = "*" -traitlets = ">=5" - -[package.extras] -all = ["black", "curio", "docrepr", "ipykernel", "ipyparallel", "ipywidgets", "matplotlib", "matplotlib (!=3.2.0)", "nbconvert", "nbformat", "notebook", "numpy (>=1.20)", "pandas", "pytest (<7)", "pytest (<7.1)", "pytest-asyncio", "qtconsole", "setuptools (>=18.5)", "sphinx (>=1.3)", "sphinx-rtd-theme", "stack-data", "testpath", "trio", "typing-extensions"] -black = ["black"] -doc = ["docrepr", "ipykernel", "matplotlib", "pytest (<7)", "pytest (<7.1)", "pytest-asyncio", "setuptools (>=18.5)", "sphinx (>=1.3)", "sphinx-rtd-theme", "stack-data", "testpath", "typing-extensions"] -kernel = ["ipykernel"] -nbconvert = ["nbconvert"] -nbformat = ["nbformat"] -notebook = ["ipywidgets", "notebook"] -parallel = ["ipyparallel"] -qtconsole = ["qtconsole"] -test = ["pytest (<7.1)", "pytest-asyncio", "testpath"] -test-extra = ["curio", "matplotlib (!=3.2.0)", "nbformat", "numpy (>=1.20)", "pandas", "pytest (<7.1)", "pytest-asyncio", "testpath", "trio"] - -[[package]] -name = "ipython-genutils" -version = "0.2.0" -description = "Vestigial utilities from IPython" -category = "dev" -optional = false -python-versions = "*" - -[[package]] -name = "ipywidgets" -version = "8.0.2" -description = "Jupyter interactive widgets" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -ipykernel = ">=4.5.1" -ipython = ">=6.1.0" -jupyterlab-widgets = ">=3.0,<4.0" -traitlets = ">=4.3.1" -widgetsnbextension = ">=4.0,<5.0" - -[package.extras] -test = ["jsonschema", "pytest (>=3.6.0)", "pytest-cov", "pytz"] - -[[package]] -name = "jedi" -version = "0.18.1" -description = "An autocompletion tool for Python that can be used for text editors." -category = "main" -optional = false -python-versions = ">=3.6" - -[package.dependencies] -parso = ">=0.8.0,<0.9.0" - -[package.extras] -qa = ["flake8 (==3.8.3)", "mypy (==0.782)"] -testing = ["Django (<3.1)", "colorama", "docopt", "pytest (<7.0.0)"] - -[[package]] -name = "jinja2" -version = "3.1.2" -description = "A very fast and expressive template engine." -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -MarkupSafe = ">=2.0" - -[package.extras] -i18n = ["Babel (>=2.7)"] - -[[package]] -name = "jsonschema" -version = "4.17.0" -description = "An implementation of JSON Schema validation for Python" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -attrs = ">=17.4.0" -pyrsistent = ">=0.14.0,<0.17.0 || >0.17.0,<0.17.1 || >0.17.1,<0.17.2 || >0.17.2" - -[package.extras] -format = ["fqdn", "idna", "isoduration", "jsonpointer (>1.13)", "rfc3339-validator", "rfc3987", "uri-template", "webcolors (>=1.11)"] -format-nongpl = ["fqdn", "idna", "isoduration", "jsonpointer (>1.13)", "rfc3339-validator", "rfc3986-validator (>0.1.0)", "uri-template", "webcolors (>=1.11)"] - -[[package]] -name = "jupyter" -version = "1.0.0" -description = "Jupyter metapackage. Install all the Jupyter components in one go." -category = "dev" -optional = false -python-versions = "*" - -[package.dependencies] -ipykernel = "*" -ipywidgets = "*" -jupyter-console = "*" -nbconvert = "*" -notebook = "*" -qtconsole = "*" - -[[package]] -name = "jupyter-client" -version = "7.4.7" -description = "Jupyter protocol implementation and client libraries" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -entrypoints = "*" -jupyter-core = ">=4.9.2" -nest-asyncio = ">=1.5.4" -python-dateutil = ">=2.8.2" -pyzmq = ">=23.0" -tornado = ">=6.2" -traitlets = "*" - -[package.extras] -doc = ["ipykernel", "myst-parser", "sphinx (>=1.3.6)", "sphinx-rtd-theme", "sphinxcontrib-github-alt"] -test = ["codecov", "coverage", "ipykernel (>=6.12)", "ipython", "mypy", "pre-commit", "pytest", "pytest-asyncio (>=0.18)", "pytest-cov", "pytest-timeout"] - -[[package]] -name = "jupyter-console" -version = "6.4.4" -description = "Jupyter terminal console" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -ipykernel = "*" -ipython = "*" -jupyter-client = ">=7.0.0" -prompt-toolkit = ">=2.0.0,<3.0.0 || >3.0.0,<3.0.1 || >3.0.1,<3.1.0" -pygments = "*" - -[package.extras] -test = ["pexpect"] - -[[package]] -name = "jupyter-core" -version = "5.0.0" -description = "Jupyter core package. A base package on which Jupyter projects rely." -category = "dev" -optional = false -python-versions = ">=3.8" - -[package.dependencies] -platformdirs = "*" -pywin32 = {version = ">=1.0", markers = "sys_platform == \"win32\" and platform_python_implementation != \"PyPy\""} -traitlets = "*" - -[package.extras] -test = ["ipykernel", "pre-commit", "pytest", "pytest-cov", "pytest-timeout"] - -[[package]] -name = "jupyter-server" -version = "1.23.2" -description = "The backend—i.e. core services, APIs, and REST endpoints—to Jupyter web applications." -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -anyio = ">=3.1.0,<4" -argon2-cffi = "*" -jinja2 = "*" -jupyter-client = ">=6.1.12" -jupyter-core = ">=4.7.0" -nbconvert = ">=6.4.4" -nbformat = ">=5.2.0" -packaging = "*" -prometheus-client = "*" -pywinpty = {version = "*", markers = "os_name == \"nt\""} -pyzmq = ">=17" -Send2Trash = "*" -terminado = ">=0.8.3" -tornado = ">=6.1.0" -traitlets = ">=5.1" -websocket-client = "*" - -[package.extras] -test = ["coverage", "ipykernel", "pre-commit", "pytest (>=7.0)", "pytest-console-scripts", "pytest-cov", "pytest-mock", "pytest-timeout", "pytest-tornasync", "requests"] - -[[package]] -name = "jupyterlab-pygments" -version = "0.2.2" -description = "Pygments theme using JupyterLab CSS variables" -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "jupyterlab-widgets" -version = "3.0.3" -description = "Jupyter interactive widgets for JupyterLab" -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "kiwisolver" -version = "1.4.4" -description = "A fast implementation of the Cassowary constraint solver" -category = "main" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "markupsafe" -version = "2.1.1" -description = "Safely add untrusted strings to HTML/XML markup." -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "matplotlib" -version = "3.6.2" -description = "Python plotting package" -category = "main" -optional = false -python-versions = ">=3.8" - -[package.dependencies] -contourpy = ">=1.0.1" -cycler = ">=0.10" -fonttools = ">=4.22.0" -kiwisolver = ">=1.0.1" -numpy = ">=1.19" -packaging = ">=20.0" -pillow = ">=6.2.0" -pyparsing = ">=2.2.1" -python-dateutil = ">=2.7" -setuptools_scm = ">=7" - -[[package]] -name = "matplotlib-inline" -version = "0.1.6" -description = "Inline Matplotlib backend for Jupyter" -category = "main" -optional = false -python-versions = ">=3.5" - -[package.dependencies] -traitlets = "*" - -[[package]] -name = "meshcat" -version = "0.3.2" -description = "WebGL-based visualizer for 3D geometries and scenes" -category = "main" -optional = true -python-versions = "*" - -[package.dependencies] -ipython = ">=5" -numpy = ">=1.14.0" -pillow = ">=7.0.0" -pyngrok = ">=4.1.6" -pyzmq = ">=17.0.0" -tornado = ">=4.0.0" -u-msgpack-python = ">=2.4.1" - -[[package]] -name = "mistune" -version = "2.0.4" -description = "A sane Markdown parser with useful plugins and renderers" -category = "dev" -optional = false -python-versions = "*" - -[[package]] -name = "nbclassic" -version = "0.4.8" -description = "A web-based notebook environment for interactive computing" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -argon2-cffi = "*" -ipykernel = "*" -ipython-genutils = "*" -jinja2 = "*" -jupyter-client = ">=6.1.1" -jupyter-core = ">=4.6.1" -jupyter-server = ">=1.8" -nbconvert = ">=5" -nbformat = "*" -nest-asyncio = ">=1.5" -notebook-shim = ">=0.1.0" -prometheus-client = "*" -pyzmq = ">=17" -Send2Trash = ">=1.8.0" -terminado = ">=0.8.3" -tornado = ">=6.1" -traitlets = ">=4.2.1" - -[package.extras] -docs = ["myst-parser", "nbsphinx", "sphinx", "sphinx-rtd-theme", "sphinxcontrib-github-alt"] -json-logging = ["json-logging"] -test = ["coverage", "nbval", "pytest", "pytest-cov", "pytest-playwright", "pytest-tornasync", "requests", "requests-unixsocket", "testpath"] - -[[package]] -name = "nbclient" -version = "0.7.0" -description = "A client library for executing notebooks. Formerly nbconvert's ExecutePreprocessor." -category = "dev" -optional = false -python-versions = ">=3.7.0" - -[package.dependencies] -jupyter-client = ">=6.1.5" -nbformat = ">=5.0" -nest-asyncio = "*" -traitlets = ">=5.2.2" - -[package.extras] -sphinx = ["Sphinx (>=1.7)", "autodoc-traits", "mock", "moto", "myst-parser", "sphinx-book-theme"] -test = ["black", "check-manifest", "flake8", "ipykernel", "ipython", "ipywidgets", "mypy", "nbconvert", "pip (>=18.1)", "pre-commit", "pytest (>=4.1)", "pytest-asyncio", "pytest-cov (>=2.6.1)", "setuptools (>=60.0)", "testpath", "twine (>=1.11.0)", "xmltodict"] - -[[package]] -name = "nbconvert" -version = "7.2.5" -description = "Converting Jupyter Notebooks" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -beautifulsoup4 = "*" -bleach = "*" -defusedxml = "*" -importlib-metadata = {version = ">=3.6", markers = "python_version < \"3.10\""} -jinja2 = ">=3.0" -jupyter-core = ">=4.7" -jupyterlab-pygments = "*" -markupsafe = ">=2.0" -mistune = ">=2.0.3,<3" -nbclient = ">=0.5.0" -nbformat = ">=5.1" -packaging = "*" -pandocfilters = ">=1.4.1" -pygments = ">=2.4.1" -tinycss2 = "*" -traitlets = ">=5.0" - -[package.extras] -all = ["ipykernel", "ipython", "ipywidgets (>=7)", "myst-parser", "nbsphinx (>=0.2.12)", "pre-commit", "pyppeteer (>=1,<1.1)", "pyqtwebengine (>=5.15)", "pytest", "pytest-cov", "pytest-dependency", "sphinx (==5.0.2)", "sphinx-rtd-theme", "tornado (>=6.1)"] -docs = ["ipython", "myst-parser", "nbsphinx (>=0.2.12)", "sphinx (==5.0.2)", "sphinx-rtd-theme"] -qtpdf = ["pyqtwebengine (>=5.15)"] -qtpng = ["pyqtwebengine (>=5.15)"] -serve = ["tornado (>=6.1)"] -test = ["ipykernel", "ipywidgets (>=7)", "pre-commit", "pyppeteer (>=1,<1.1)", "pytest", "pytest-cov", "pytest-dependency"] -webpdf = ["pyppeteer (>=1,<1.1)"] - -[[package]] -name = "nbformat" -version = "5.7.0" -description = "The Jupyter Notebook format" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -fastjsonschema = "*" -jsonschema = ">=2.6" -jupyter-core = "*" -traitlets = ">=5.1" - -[package.extras] -test = ["check-manifest", "pep440", "pre-commit", "pytest", "testpath"] - -[[package]] -name = "nest-asyncio" -version = "1.5.6" -description = "Patch asyncio to allow nested event loops" -category = "dev" -optional = false -python-versions = ">=3.5" - -[[package]] -name = "notebook" -version = "6.5.2" -description = "A web-based notebook environment for interactive computing" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -argon2-cffi = "*" -ipykernel = "*" -ipython-genutils = "*" -jinja2 = "*" -jupyter-client = ">=5.3.4" -jupyter-core = ">=4.6.1" -nbclassic = ">=0.4.7" -nbconvert = ">=5" -nbformat = "*" -nest-asyncio = ">=1.5" -prometheus-client = "*" -pyzmq = ">=17" -Send2Trash = ">=1.8.0" -terminado = ">=0.8.3" -tornado = ">=6.1" -traitlets = ">=4.2.1" - -[package.extras] -docs = ["myst-parser", "nbsphinx", "sphinx", "sphinx-rtd-theme", "sphinxcontrib-github-alt"] -json-logging = ["json-logging"] -test = ["coverage", "nbval", "pytest", "pytest-cov", "requests", "requests-unixsocket", "selenium (==4.1.5)", "testpath"] - -[[package]] -name = "notebook-shim" -version = "0.2.2" -description = "A shim layer for notebook traits and config" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -jupyter-server = ">=1.8,<3" - -[package.extras] -test = ["pytest", "pytest-console-scripts", "pytest-tornasync"] - -[[package]] -name = "numpy" -version = "1.23.5" -description = "NumPy is the fundamental package for array computing with Python." -category = "main" -optional = false -python-versions = ">=3.8" - -[[package]] -name = "nvidia-cublas-cu11" -version = "11.10.3.66" -description = "CUBLAS native runtime libraries" -category = "main" -optional = false -python-versions = ">=3" - -[package.dependencies] -setuptools = "*" -wheel = "*" - -[[package]] -name = "nvidia-cuda-nvrtc-cu11" -version = "11.7.99" -description = "NVRTC native runtime libraries" -category = "main" -optional = false -python-versions = ">=3" - -[package.dependencies] -setuptools = "*" -wheel = "*" - -[[package]] -name = "nvidia-cuda-runtime-cu11" -version = "11.7.99" -description = "CUDA Runtime native Libraries" -category = "main" -optional = false -python-versions = ">=3" - -[package.dependencies] -setuptools = "*" -wheel = "*" - -[[package]] -name = "nvidia-cudnn-cu11" -version = "8.5.0.96" -description = "cuDNN runtime libraries" -category = "main" -optional = false -python-versions = ">=3" - -[package.dependencies] -setuptools = "*" -wheel = "*" - -[[package]] -name = "packaging" -version = "21.3" -description = "Core utilities for Python packages" -category = "main" -optional = false -python-versions = ">=3.6" - -[package.dependencies] -pyparsing = ">=2.0.2,<3.0.5 || >3.0.5" - -[[package]] -name = "pandas" -version = "1.5.1" -description = "Powerful data structures for data analysis, time series, and statistics" -category = "dev" -optional = false -python-versions = ">=3.8" - -[package.dependencies] -numpy = [ - {version = ">=1.20.3", markers = "python_version < \"3.10\""}, - {version = ">=1.21.0", markers = "python_version >= \"3.10\""}, -] -python-dateutil = ">=2.8.1" -pytz = ">=2020.1" - -[package.extras] -test = ["hypothesis (>=5.5.3)", "pytest (>=6.0)", "pytest-xdist (>=1.31)"] - -[[package]] -name = "pandocfilters" -version = "1.5.0" -description = "Utilities for writing pandoc filters in python" -category = "dev" -optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" - -[[package]] -name = "parso" -version = "0.8.3" -description = "A Python Parser" -category = "main" -optional = false -python-versions = ">=3.6" - -[package.extras] -qa = ["flake8 (==3.8.3)", "mypy (==0.782)"] -testing = ["docopt", "pytest (<6.0.0)"] - -[[package]] -name = "pexpect" -version = "4.8.0" -description = "Pexpect allows easy control of interactive console applications." -category = "main" -optional = false -python-versions = "*" - -[package.dependencies] -ptyprocess = ">=0.5" - -[[package]] -name = "pickleshare" -version = "0.7.5" -description = "Tiny 'shelve'-like database with concurrency support" -category = "main" -optional = false -python-versions = "*" - -[[package]] -name = "pillow" -version = "9.3.0" -description = "Python Imaging Library (Fork)" -category = "main" -optional = false -python-versions = ">=3.7" - -[package.extras] -docs = ["furo", "olefile", "sphinx (>=2.4)", "sphinx-copybutton", "sphinx-issues (>=3.0.1)", "sphinx-removed-in", "sphinxext-opengraph"] -tests = ["check-manifest", "coverage", "defusedxml", "markdown2", "olefile", "packaging", "pyroma", "pytest", "pytest-cov", "pytest-timeout"] - -[[package]] -name = "platformdirs" -version = "2.5.4" -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" - -[package.extras] -docs = ["furo (>=2022.9.29)", "proselint (>=0.13)", "sphinx (>=5.3)", "sphinx-autodoc-typehints (>=1.19.4)"] -test = ["appdirs (==1.4.4)", "pytest (>=7.2)", "pytest-cov (>=4)", "pytest-mock (>=3.10)"] - -[[package]] -name = "pluggy" -version = "1.0.0" -description = "plugin and hook calling mechanisms for python" -category = "dev" -optional = false -python-versions = ">=3.6" - -[package.extras] -dev = ["pre-commit", "tox"] -testing = ["pytest", "pytest-benchmark"] - -[[package]] -name = "prometheus-client" -version = "0.15.0" -description = "Python client for the Prometheus monitoring system." -category = "dev" -optional = false -python-versions = ">=3.6" - -[package.extras] -twisted = ["twisted"] - -[[package]] -name = "prompt-toolkit" -version = "3.0.32" -description = "Library for building powerful interactive command lines in Python" -category = "main" -optional = false -python-versions = ">=3.6.2" - -[package.dependencies] -wcwidth = "*" - -[[package]] -name = "protobuf" -version = "4.21.9" -description = "" -category = "main" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "psutil" -version = "5.9.4" -description = "Cross-platform lib for process and system monitoring in Python." -category = "dev" -optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" - -[package.extras] -test = ["enum34", "ipaddress", "mock", "pywin32", "wmi"] - -[[package]] -name = "ptyprocess" -version = "0.7.0" -description = "Run a subprocess in a pseudo terminal" -category = "main" -optional = false -python-versions = "*" - -[[package]] -name = "pure-eval" -version = "0.2.2" -description = "Safely evaluate AST nodes without side effects" -category = "main" -optional = false -python-versions = "*" - -[package.extras] -tests = ["pytest"] - -[[package]] -name = "py" -version = "1.11.0" -description = "library with cross-python path, ini-parsing, io, code, log facilities" -category = "main" -optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" - -[[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.*" - -[[package]] -name = "pydot" -version = "1.4.2" -description = "Python interface to Graphviz's Dot" -category = "main" -optional = true -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" - -[package.dependencies] -pyparsing = ">=2.1.4" - -[[package]] -name = "pygments" -version = "2.13.0" -description = "Pygments is a syntax highlighting package written in Python." -category = "main" -optional = false -python-versions = ">=3.6" - -[package.extras] -plugins = ["importlib-metadata"] - -[[package]] -name = "pyngrok" -version = "5.1.0" -description = "A Python wrapper for ngrok." -category = "main" -optional = true -python-versions = ">=3.5" - -[package.dependencies] -PyYAML = "*" - -[[package]] -name = "pyparsing" -version = "3.0.9" -description = "pyparsing module - Classes and methods to define and execute parsing grammars" -category = "main" -optional = false -python-versions = ">=3.6.8" - -[package.extras] -diagrams = ["jinja2", "railroad-diagrams"] - -[[package]] -name = "pyrsistent" -version = "0.19.2" -description = "Persistent/Functional/Immutable data structures" -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "pyserial" -version = "3.5" -description = "Python Serial Port Extension" -category = "main" -optional = false -python-versions = "*" - -[package.extras] -cp2110 = ["hidapi"] - -[[package]] -name = "pytest" -version = "7.2.0" -description = "pytest: simple powerful testing with Python" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -attrs = ">=19.2.0" -colorama = {version = "*", markers = "sys_platform == \"win32\""} -exceptiongroup = {version = ">=1.0.0rc8", markers = "python_version < \"3.11\""} -iniconfig = "*" -packaging = "*" -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"] - -[[package]] -name = "python-dateutil" -version = "2.8.2" -description = "Extensions to the standard Python datetime module" -category = "main" -optional = false -python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,>=2.7" - -[package.dependencies] -six = ">=1.5" - -[[package]] -name = "pytz" -version = "2022.6" -description = "World timezone definitions, modern and historical" -category = "dev" -optional = false -python-versions = "*" - -[[package]] -name = "pywin32" -version = "305" -description = "Python for Window Extensions" -category = "dev" -optional = false -python-versions = "*" - -[[package]] -name = "pywinpty" -version = "2.0.9" -description = "Pseudo terminal support for Windows from Python." -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "pyyaml" -version = "6.0" -description = "YAML parser and emitter for Python" -category = "main" -optional = true -python-versions = ">=3.6" - -[[package]] -name = "pyzmq" -version = "24.0.1" -description = "Python bindings for 0MQ" -category = "main" -optional = false -python-versions = ">=3.6" - -[package.dependencies] -cffi = {version = "*", markers = "implementation_name == \"pypy\""} -py = {version = "*", markers = "implementation_name == \"pypy\""} - -[[package]] -name = "qtconsole" -version = "5.4.0" -description = "Jupyter Qt console" -category = "dev" -optional = false -python-versions = ">= 3.7" - -[package.dependencies] -ipykernel = ">=4.1" -ipython-genutils = "*" -jupyter-client = ">=4.1" -jupyter-core = "*" -pygments = "*" -pyzmq = ">=17.1" -qtpy = ">=2.0.1" -traitlets = "<5.2.1 || >5.2.1,<5.2.2 || >5.2.2" - -[package.extras] -doc = ["Sphinx (>=1.3)"] -test = ["flaky", "pytest", "pytest-qt"] - -[[package]] -name = "qtpy" -version = "2.3.0" -description = "Provides an abstraction layer on top of the various Qt bindings (PyQt5/6 and PySide2/6)." -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -packaging = "*" - -[package.extras] -test = ["pytest (>=6,!=7.0.0,!=7.0.1)", "pytest-cov (>=3.0.0)", "pytest-qt"] - -[[package]] -name = "seaborn" -version = "0.12.1" -description = "Statistical data visualization" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -matplotlib = ">=3.1,<3.6.1 || >3.6.1" -numpy = ">=1.17" -pandas = ">=0.25" - -[package.extras] -dev = ["flake8", "mypy", "pandas-stubs", "pre-commit", "pytest", "pytest-cov", "pytest-xdist"] -docs = ["ipykernel", "nbconvert", "numpydoc", "pydata_sphinx_theme (==0.10.0rc2)", "pyyaml", "sphinx-copybutton", "sphinx-design", "sphinx-issues"] -stats = ["scipy (>=1.3)", "statsmodels (>=0.10)"] - -[[package]] -name = "send2trash" -version = "1.8.0" -description = "Send file to trash natively under Mac OS X, Windows and Linux." -category = "dev" -optional = false -python-versions = "*" - -[package.extras] -nativelib = ["pyobjc-framework-Cocoa", "pywin32"] -objc = ["pyobjc-framework-Cocoa"] -win32 = ["pywin32"] - -[[package]] -name = "setuptools" -version = "65.6.0" -description = "Easily download, build, install, upgrade, and uninstall Python packages" -category = "main" -optional = false -python-versions = ">=3.7" - -[package.extras] -docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "pygments-github-lexers (==0.0.5)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-favicon", "sphinx-hoverxref (<2)", "sphinx-inline-tabs", "sphinx-notfound-page (==0.8.3)", "sphinx-reredirects", "sphinxcontrib-towncrier"] -testing = ["build[virtualenv]", "filelock (>=3.4.0)", "flake8 (<5)", "flake8-2020", "ini2toml[lite] (>=0.9)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "pip (>=19.1)", "pip-run (>=8.8)", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=1.3)", "pytest-flake8", "pytest-mypy (>=0.9.1)", "pytest-perf", "pytest-timeout", "pytest-xdist", "tomli-w (>=1.0.0)", "virtualenv (>=13.0.0)", "wheel"] -testing-integration = ["build[virtualenv]", "filelock (>=3.4.0)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "pytest", "pytest-enabler", "pytest-xdist", "tomli", "virtualenv (>=13.0.0)", "wheel"] - -[[package]] -name = "setuptools-scm" -version = "7.0.5" -description = "the blessed package to manage your versions by scm tags" -category = "main" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -packaging = ">=20.0" -setuptools = "*" -tomli = ">=1.0.0" -typing-extensions = "*" - -[package.extras] -test = ["pytest (>=6.2)", "virtualenv (>20)"] -toml = ["setuptools (>=42)"] - -[[package]] -name = "six" -version = "1.16.0" -description = "Python 2 and 3 compatibility utilities" -category = "main" -optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*" - -[[package]] -name = "sniffio" -version = "1.3.0" -description = "Sniff out which async library your code is running under" -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "soupsieve" -version = "2.3.2.post1" -description = "A modern CSS selector implementation for Beautiful Soup." -category = "dev" -optional = false -python-versions = ">=3.6" - -[[package]] -name = "stack-data" -version = "0.6.1" -description = "Extract data from python stack frames and tracebacks for informative displays" -category = "main" -optional = false -python-versions = "*" - -[package.dependencies] -asttokens = ">=2.1.0" -executing = ">=1.2.0" -pure-eval = "*" - -[package.extras] -tests = ["cython", "littleutils", "pygments", "pytest", "typeguard"] - -[[package]] -name = "terminado" -version = "0.17.0" -description = "Tornado websocket backend for the Xterm.js Javascript terminal emulator library." -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -ptyprocess = {version = "*", markers = "os_name != \"nt\""} -pywinpty = {version = ">=1.1.0", markers = "os_name == \"nt\""} -tornado = ">=6.1.0" - -[package.extras] -docs = ["pydata-sphinx-theme", "sphinx"] -test = ["pre-commit", "pytest (>=7.0)", "pytest-timeout"] - -[[package]] -name = "tinycss2" -version = "1.2.1" -description = "A tiny CSS parser" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.dependencies] -webencodings = ">=0.4" - -[package.extras] -doc = ["sphinx", "sphinx_rtd_theme"] -test = ["flake8", "isort", "pytest"] - -[[package]] -name = "tomli" -version = "2.0.1" -description = "A lil' TOML parser" -category = "main" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "torch" -version = "1.13.0" -description = "Tensors and Dynamic neural networks in Python with strong GPU acceleration" -category = "main" -optional = false -python-versions = ">=3.7.0" - -[package.dependencies] -nvidia-cublas-cu11 = "11.10.3.66" -nvidia-cuda-nvrtc-cu11 = "11.7.99" -nvidia-cuda-runtime-cu11 = "11.7.99" -nvidia-cudnn-cu11 = "8.5.0.96" -typing-extensions = "*" - -[package.extras] -opt-einsum = ["opt-einsum (>=3.3)"] - -[[package]] -name = "tornado" -version = "6.2" -description = "Tornado is a Python web framework and asynchronous networking library, originally developed at FriendFeed." -category = "main" -optional = false -python-versions = ">= 3.7" - -[[package]] -name = "traitlets" -version = "5.5.0" -description = "" -category = "main" -optional = false -python-versions = ">=3.7" - -[package.extras] -docs = ["myst-parser", "pydata-sphinx-theme", "sphinx"] -test = ["pre-commit", "pytest"] - -[[package]] -name = "typing-extensions" -version = "4.4.0" -description = "Backported and Experimental Type Hints for Python 3.7+" -category = "main" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "u-msgpack-python" -version = "2.7.2" -description = "A portable, lightweight MessagePack serializer and deserializer written in pure Python." -category = "main" -optional = true -python-versions = "*" - -[[package]] -name = "varint" -version = "1.0.2" -description = "Simple python varint implementation" -category = "main" -optional = false -python-versions = "*" - -[[package]] -name = "wcwidth" -version = "0.2.5" -description = "Measures the displayed width of unicode strings in a terminal" -category = "main" -optional = false -python-versions = "*" - -[[package]] -name = "webencodings" -version = "0.5.1" -description = "Character encoding aliases for legacy web content" -category = "dev" -optional = false -python-versions = "*" - -[[package]] -name = "websocket-client" -version = "1.4.2" -description = "WebSocket client for Python with low level API options" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.extras] -docs = ["Sphinx (>=3.4)", "sphinx-rtd-theme (>=0.5)"] -optional = ["python-socks", "wsaccel"] -test = ["websockets"] - -[[package]] -name = "wheel" -version = "0.38.4" -description = "A built-package format for Python" -category = "main" -optional = false -python-versions = ">=3.7" - -[package.extras] -test = ["pytest (>=3.0.0)"] - -[[package]] -name = "widgetsnbextension" -version = "4.0.3" -description = "Jupyter interactive widgets for Jupyter Notebook" -category = "dev" -optional = false -python-versions = ">=3.7" - -[[package]] -name = "zipp" -version = "3.10.0" -description = "Backport of pathlib-compatible object wrapper for zip files" -category = "dev" -optional = false -python-versions = ">=3.7" - -[package.extras] -docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)"] -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)"] - -[extras] -pydrake = ["drake"] - -[metadata] -lock-version = "1.1" -python-versions = "^3.9" -content-hash = "8a7630560c764d58e651372015250b418d989e04d1ad308095691927df6c813e" - -[metadata.files] -anyio = [ - {file = "anyio-3.6.2-py3-none-any.whl", hash = "sha256:fbbe32bd270d2a2ef3ed1c5d45041250284e31fc0a4df4a5a6071842051a51e3"}, - {file = "anyio-3.6.2.tar.gz", hash = "sha256:25ea0d673ae30af41a0c442f81cf3b38c7e79fdc7b60335a4c14e05eb0947421"}, -] -appnope = [ - {file = "appnope-0.1.3-py2.py3-none-any.whl", hash = "sha256:265a455292d0bd8a72453494fa24df5a11eb18373a60c7c0430889f22548605e"}, - {file = "appnope-0.1.3.tar.gz", hash = "sha256:02bd91c4de869fbb1e1c50aafc4098827a7a54ab2f39d9dcba6c9547ed920e24"}, -] -argon2-cffi = [ - {file = "argon2-cffi-21.3.0.tar.gz", hash = "sha256:d384164d944190a7dd7ef22c6aa3ff197da12962bd04b17f64d4e93d934dba5b"}, - {file = "argon2_cffi-21.3.0-py3-none-any.whl", hash = "sha256:8c976986f2c5c0e5000919e6de187906cfd81fb1c72bf9d88c01177e77da7f80"}, -] -argon2-cffi-bindings = [ - {file = "argon2-cffi-bindings-21.2.0.tar.gz", hash = "sha256:bb89ceffa6c791807d1305ceb77dbfacc5aa499891d2c55661c6459651fc39e3"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:ccb949252cb2ab3a08c02024acb77cfb179492d5701c7cbdbfd776124d4d2367"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9524464572e12979364b7d600abf96181d3541da11e23ddf565a32e70bd4dc0d"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b746dba803a79238e925d9046a63aa26bf86ab2a2fe74ce6b009a1c3f5c8f2ae"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:58ed19212051f49a523abb1dbe954337dc82d947fb6e5a0da60f7c8471a8476c"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:bd46088725ef7f58b5a1ef7ca06647ebaf0eb4baff7d1d0d177c6cc8744abd86"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-musllinux_1_1_i686.whl", hash = "sha256:8cd69c07dd875537a824deec19f978e0f2078fdda07fd5c42ac29668dda5f40f"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-musllinux_1_1_x86_64.whl", hash = "sha256:f1152ac548bd5b8bcecfb0b0371f082037e47128653df2e8ba6e914d384f3c3e"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-win32.whl", hash = "sha256:603ca0aba86b1349b147cab91ae970c63118a0f30444d4bc80355937c950c082"}, - {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-win_amd64.whl", hash = "sha256:b2ef1c30440dbbcba7a5dc3e319408b59676e2e039e2ae11a8775ecf482b192f"}, - {file = "argon2_cffi_bindings-21.2.0-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:e415e3f62c8d124ee16018e491a009937f8cf7ebf5eb430ffc5de21b900dad93"}, - {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:3e385d1c39c520c08b53d63300c3ecc28622f076f4c2b0e6d7e796e9f6502194"}, - {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c3e3cc67fdb7d82c4718f19b4e7a87123caf8a93fde7e23cf66ac0337d3cb3f"}, - {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6a22ad9800121b71099d0fb0a65323810a15f2e292f2ba450810a7316e128ee5"}, - {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f9f8b450ed0547e3d473fdc8612083fd08dd2120d6ac8f73828df9b7d45bb351"}, - {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:93f9bf70084f97245ba10ee36575f0c3f1e7d7724d67d8e5b08e61787c320ed7"}, - {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:3b9ef65804859d335dc6b31582cad2c5166f0c3e7975f324d9ffaa34ee7e6583"}, - {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d4966ef5848d820776f5f562a7d45fdd70c2f330c961d0d745b784034bd9f48d"}, - {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:20ef543a89dee4db46a1a6e206cd015360e5a75822f76df533845c3cbaf72670"}, - {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ed2937d286e2ad0cc79a7087d3c272832865f779430e0cc2b4f3718d3159b0cb"}, - {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:5e00316dabdaea0b2dd82d141cc66889ced0cdcbfa599e8b471cf22c620c329a"}, -] -asttokens = [ - {file = "asttokens-2.1.0-py2.py3-none-any.whl", hash = "sha256:1b28ed85e254b724439afc783d4bee767f780b936c3fe8b3275332f42cf5f561"}, - {file = "asttokens-2.1.0.tar.gz", hash = "sha256:4aa76401a151c8cc572d906aad7aea2a841780834a19d780f4321c0fe1b54635"}, -] -attrs = [ - {file = "attrs-22.1.0-py2.py3-none-any.whl", hash = "sha256:86efa402f67bf2df34f51a335487cf46b1ec130d02b8d39fd248abfd30da551c"}, - {file = "attrs-22.1.0.tar.gz", hash = "sha256:29adc2665447e5191d0e7c568fde78b21f9672d344281d0c6e1ab085429b22b6"}, -] -backcall = [ - {file = "backcall-0.2.0-py2.py3-none-any.whl", hash = "sha256:fbbce6a29f263178a1f7915c1940bde0ec2b2a967566fe1c65c1dfb7422bd255"}, - {file = "backcall-0.2.0.tar.gz", hash = "sha256:5cbdbf27be5e7cfadb448baf0aa95508f91f2bbc6c6437cd9cd06e2a4c215e1e"}, -] -beautifulsoup4 = [ - {file = "beautifulsoup4-4.11.1-py3-none-any.whl", hash = "sha256:58d5c3d29f5a36ffeb94f02f0d786cd53014cf9b3b3951d42e0080d8a9498d30"}, - {file = "beautifulsoup4-4.11.1.tar.gz", hash = "sha256:ad9aa55b65ef2808eb405f46cf74df7fcb7044d5cbc26487f96eb2ef2e436693"}, -] -bleach = [ - {file = "bleach-5.0.1-py3-none-any.whl", hash = "sha256:085f7f33c15bd408dd9b17a4ad77c577db66d76203e5984b1bd59baeee948b2a"}, - {file = "bleach-5.0.1.tar.gz", hash = "sha256:0d03255c47eb9bd2f26aa9bb7f2107732e7e8fe195ca2f64709fcf3b0a4a085c"}, -] -cffi = [ - {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"}, -] -colorama = [ - {file = "colorama-0.4.6-py2.py3-none-any.whl", hash = "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6"}, - {file = "colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44"}, -] -contourpy = [ - {file = "contourpy-1.0.6-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:613c665529899b5d9fade7e5d1760111a0b011231277a0d36c49f0d3d6914bd6"}, - {file = "contourpy-1.0.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:78ced51807ccb2f45d4ea73aca339756d75d021069604c2fccd05390dc3c28eb"}, - {file = "contourpy-1.0.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:b3b1bd7577c530eaf9d2bc52d1a93fef50ac516a8b1062c3d1b9bcec9ebe329b"}, - {file = "contourpy-1.0.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8834c14b8c3dd849005e06703469db9bf96ba2d66a3f88ecc539c9a8982e0ee"}, - {file = "contourpy-1.0.6-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f4052a8a4926d4468416fc7d4b2a7b2a3e35f25b39f4061a7e2a3a2748c4fc48"}, - {file = "contourpy-1.0.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1c0e1308307a75e07d1f1b5f0f56b5af84538a5e9027109a7bcf6cb47c434e72"}, - {file = "contourpy-1.0.6-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:9fc4e7973ed0e1fe689435842a6e6b330eb7ccc696080dda9a97b1a1b78e41db"}, - {file = "contourpy-1.0.6-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:08e8d09d96219ace6cb596506fb9b64ea5f270b2fb9121158b976d88871fcfd1"}, - {file = "contourpy-1.0.6-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:f33da6b5d19ad1bb5e7ad38bb8ba5c426d2178928bc2b2c44e8823ea0ecb6ff3"}, - {file = "contourpy-1.0.6-cp310-cp310-win32.whl", hash = "sha256:12a7dc8439544ed05c6553bf026d5e8fa7fad48d63958a95d61698df0e00092b"}, - {file = "contourpy-1.0.6-cp310-cp310-win_amd64.whl", hash = "sha256:eadad75bf91897f922e0fb3dca1b322a58b1726a953f98c2e5f0606bd8408621"}, - {file = "contourpy-1.0.6-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:913bac9d064cff033cf3719e855d4f1db9f1c179e0ecf3ba9fdef21c21c6a16a"}, - {file = "contourpy-1.0.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:46deb310a276cc5c1fd27958e358cce68b1e8a515fa5a574c670a504c3a3fe30"}, - {file = "contourpy-1.0.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b64f747e92af7da3b85631a55d68c45a2d728b4036b03cdaba4bd94bcc85bd6f"}, - {file = "contourpy-1.0.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:50627bf76abb6ba291ad08db583161939c2c5fab38c38181b7833423ab9c7de3"}, - {file = "contourpy-1.0.6-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:358f6364e4873f4d73360b35da30066f40387dd3c427a3e5432c6b28dd24a8fa"}, - {file = "contourpy-1.0.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c78bfbc1a7bff053baf7e508449d2765964d67735c909b583204e3240a2aca45"}, - {file = "contourpy-1.0.6-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:e43255a83835a129ef98f75d13d643844d8c646b258bebd11e4a0975203e018f"}, - {file = "contourpy-1.0.6-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:375d81366afd547b8558c4720337218345148bc2fcffa3a9870cab82b29667f2"}, - {file = "contourpy-1.0.6-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:b98c820608e2dca6442e786817f646d11057c09a23b68d2b3737e6dcb6e4a49b"}, - {file = "contourpy-1.0.6-cp311-cp311-win32.whl", hash = "sha256:0e4854cc02006ad6684ce092bdadab6f0912d131f91c2450ce6dbdea78ee3c0b"}, - {file = "contourpy-1.0.6-cp311-cp311-win_amd64.whl", hash = "sha256:d2eff2af97ea0b61381828b1ad6cd249bbd41d280e53aea5cccd7b2b31b8225c"}, - {file = "contourpy-1.0.6-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:5b117d29433fc8393b18a696d794961464e37afb34a6eeb8b2c37b5f4128a83e"}, - {file = "contourpy-1.0.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:341330ed19074f956cb20877ad8d2ae50e458884bfa6a6df3ae28487cc76c768"}, - {file = "contourpy-1.0.6-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:371f6570a81dfdddbb837ba432293a63b4babb942a9eb7aaa699997adfb53278"}, - {file = "contourpy-1.0.6-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9447c45df407d3ecb717d837af3b70cfef432138530712263730783b3d016512"}, - {file = "contourpy-1.0.6-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:730c27978a0003b47b359935478b7d63fd8386dbb2dcd36c1e8de88cbfc1e9de"}, - {file = "contourpy-1.0.6-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:da1ef35fd79be2926ba80fbb36327463e3656c02526e9b5b4c2b366588b74d9a"}, - {file = "contourpy-1.0.6-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:cd2bc0c8f2e8de7dd89a7f1c10b8844e291bca17d359373203ef2e6100819edd"}, - {file = "contourpy-1.0.6-cp37-cp37m-win32.whl", hash = "sha256:3a1917d3941dd58732c449c810fa7ce46cc305ce9325a11261d740118b85e6f3"}, - {file = "contourpy-1.0.6-cp37-cp37m-win_amd64.whl", hash = "sha256:06ca79e1efbbe2df795822df2fa173d1a2b38b6e0f047a0ec7903fbca1d1847e"}, - {file = "contourpy-1.0.6-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:e626cefff8491bce356221c22af5a3ea528b0b41fbabc719c00ae233819ea0bf"}, - {file = "contourpy-1.0.6-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:dbe6fe7a1166b1ddd7b6d887ea6fa8389d3f28b5ed3f73a8f40ece1fc5a3d340"}, - {file = "contourpy-1.0.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:e13b31d1b4b68db60b3b29f8e337908f328c7f05b9add4b1b5c74e0691180109"}, - {file = "contourpy-1.0.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a79d239fc22c3b8d9d3de492aa0c245533f4f4c7608e5749af866949c0f1b1b9"}, - {file = "contourpy-1.0.6-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9e8e686a6db92a46111a1ee0ee6f7fbfae4048f0019de207149f43ac1812cf95"}, - {file = "contourpy-1.0.6-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:acd2bd02f1a7adff3a1f33e431eb96ab6d7987b039d2946a9b39fe6fb16a1036"}, - {file = "contourpy-1.0.6-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:03d1b9c6b44a9e30d554654c72be89af94fab7510b4b9f62356c64c81cec8b7d"}, - {file = "contourpy-1.0.6-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:b48d94386f1994db7c70c76b5808c12e23ed7a4ee13693c2fc5ab109d60243c0"}, - {file = "contourpy-1.0.6-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:208bc904889c910d95aafcf7be9e677726df9ef71e216780170dbb7e37d118fa"}, - {file = "contourpy-1.0.6-cp38-cp38-win32.whl", hash = "sha256:444fb776f58f4906d8d354eb6f6ce59d0a60f7b6a720da6c1ccb839db7c80eb9"}, - {file = "contourpy-1.0.6-cp38-cp38-win_amd64.whl", hash = "sha256:9bc407a6af672da20da74823443707e38ece8b93a04009dca25856c2d9adadb1"}, - {file = "contourpy-1.0.6-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:aa4674cf3fa2bd9c322982644967f01eed0c91bb890f624e0e0daf7a5c3383e9"}, - {file = "contourpy-1.0.6-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:6f56515e7c6fae4529b731f6c117752247bef9cdad2b12fc5ddf8ca6a50965a5"}, - {file = "contourpy-1.0.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:344cb3badf6fc7316ad51835f56ac387bdf86c8e1b670904f18f437d70da4183"}, - {file = "contourpy-1.0.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0b1e66346acfb17694d46175a0cea7d9036f12ed0c31dfe86f0f405eedde2bdd"}, - {file = "contourpy-1.0.6-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8468b40528fa1e15181cccec4198623b55dcd58306f8815a793803f51f6c474a"}, - {file = "contourpy-1.0.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1dedf4c64185a216c35eb488e6f433297c660321275734401760dafaeb0ad5c2"}, - {file = "contourpy-1.0.6-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:494efed2c761f0f37262815f9e3c4bb9917c5c69806abdee1d1cb6611a7174a0"}, - {file = "contourpy-1.0.6-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:75a2e638042118118ab39d337da4c7908c1af74a8464cad59f19fbc5bbafec9b"}, - {file = "contourpy-1.0.6-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:a628bba09ba72e472bf7b31018b6281fd4cc903f0888049a3724afba13b6e0b8"}, - {file = "contourpy-1.0.6-cp39-cp39-win32.whl", hash = "sha256:e1739496c2f0108013629aa095cc32a8c6363444361960c07493818d0dea2da4"}, - {file = "contourpy-1.0.6-cp39-cp39-win_amd64.whl", hash = "sha256:a457ee72d9032e86730f62c5eeddf402e732fdf5ca8b13b41772aa8ae13a4563"}, - {file = "contourpy-1.0.6-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:d912f0154a20a80ea449daada904a7eb6941c83281a9fab95de50529bfc3a1da"}, - {file = "contourpy-1.0.6-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4081918147fc4c29fad328d5066cfc751da100a1098398742f9f364be63803fc"}, - {file = "contourpy-1.0.6-pp37-pypy37_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0537cc1195245bbe24f2913d1f9211b8f04eb203de9044630abd3664c6cc339c"}, - {file = "contourpy-1.0.6-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dcd556c8fc37a342dd636d7eef150b1399f823a4462f8c968e11e1ebeabee769"}, - {file = "contourpy-1.0.6-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:f6ca38dd8d988eca8f07305125dec6f54ac1c518f1aaddcc14d08c01aebb6efc"}, - {file = "contourpy-1.0.6-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:c1baa49ab9fedbf19d40d93163b7d3e735d9cd8d5efe4cce9907902a6dad391f"}, - {file = "contourpy-1.0.6-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:211dfe2bd43bf5791d23afbe23a7952e8ac8b67591d24be3638cabb648b3a6eb"}, - {file = "contourpy-1.0.6-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c38c6536c2d71ca2f7e418acaf5bca30a3af7f2a2fa106083c7d738337848dbe"}, - {file = "contourpy-1.0.6-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1b1ee48a130da4dd0eb8055bbab34abf3f6262957832fd575e0cab4979a15a41"}, - {file = "contourpy-1.0.6-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:5641927cc5ae66155d0c80195dc35726eae060e7defc18b7ab27600f39dd1fe7"}, - {file = "contourpy-1.0.6-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:7ee394502026d68652c2824348a40bf50f31351a668977b51437131a90d777ea"}, - {file = "contourpy-1.0.6-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0b97454ed5b1368b66ed414c754cba15b9750ce69938fc6153679787402e4cdf"}, - {file = "contourpy-1.0.6-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0236875c5a0784215b49d00ebbe80c5b6b5d5244b3655a36dda88105334dea17"}, - {file = "contourpy-1.0.6-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:84c593aeff7a0171f639da92cb86d24954bbb61f8a1b530f74eb750a14685832"}, - {file = "contourpy-1.0.6-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:9b0e7fe7f949fb719b206548e5cde2518ffb29936afa4303d8a1c4db43dcb675"}, - {file = "contourpy-1.0.6.tar.gz", hash = "sha256:6e459ebb8bb5ee4c22c19cc000174f8059981971a33ce11e17dddf6aca97a142"}, -] -cycler = [ - {file = "cycler-0.11.0-py3-none-any.whl", hash = "sha256:3a27e95f763a428a739d2add979fa7494c912a32c17c4c38c4d5f082cad165a3"}, - {file = "cycler-0.11.0.tar.gz", hash = "sha256:9c87405839a19696e837b3b818fed3f5f69f16f1eec1a1ad77e043dcea9c772f"}, -] -dacite = [ - {file = "dacite-1.6.0-py3-none-any.whl", hash = "sha256:4331535f7aabb505c732fa4c3c094313fc0a1d5ea19907bf4726a7819a68b93f"}, - {file = "dacite-1.6.0.tar.gz", hash = "sha256:d48125ed0a0352d3de9f493bf980038088f45f3f9d7498f090b50a847daaa6df"}, -] -debugpy = [ - {file = "debugpy-1.6.3-cp310-cp310-macosx_10_15_x86_64.whl", hash = "sha256:c4b2bd5c245eeb49824bf7e539f95fb17f9a756186e51c3e513e32999d8846f3"}, - {file = "debugpy-1.6.3-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:b8deaeb779699350deeed835322730a3efec170b88927debc9ba07a1a38e2585"}, - {file = "debugpy-1.6.3-cp310-cp310-win32.whl", hash = "sha256:fc233a0160f3b117b20216f1169e7211b83235e3cd6749bcdd8dbb72177030c7"}, - {file = "debugpy-1.6.3-cp310-cp310-win_amd64.whl", hash = "sha256:dda8652520eae3945833e061cbe2993ad94a0b545aebd62e4e6b80ee616c76b2"}, - {file = "debugpy-1.6.3-cp37-cp37m-macosx_10_15_x86_64.whl", hash = "sha256:d5c814596a170a0a58fa6fad74947e30bfd7e192a5d2d7bd6a12156c2899e13a"}, - {file = "debugpy-1.6.3-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:c4cd6f37e3c168080d61d698390dfe2cd9e74ebf80b448069822a15dadcda57d"}, - {file = "debugpy-1.6.3-cp37-cp37m-win32.whl", hash = "sha256:3c9f985944a30cfc9ae4306ac6a27b9c31dba72ca943214dad4a0ab3840f6161"}, - {file = "debugpy-1.6.3-cp37-cp37m-win_amd64.whl", hash = "sha256:5ad571a36cec137ae6ed951d0ff75b5e092e9af6683da084753231150cbc5b25"}, - {file = "debugpy-1.6.3-cp38-cp38-macosx_10_15_x86_64.whl", hash = "sha256:adcfea5ea06d55d505375995e150c06445e2b20cd12885bcae566148c076636b"}, - {file = "debugpy-1.6.3-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:daadab4403427abd090eccb38d8901afd8b393e01fd243048fab3f1d7132abb4"}, - {file = "debugpy-1.6.3-cp38-cp38-win32.whl", hash = "sha256:6efc30325b68e451118b795eff6fe8488253ca3958251d5158106d9c87581bc6"}, - {file = "debugpy-1.6.3-cp38-cp38-win_amd64.whl", hash = "sha256:86d784b72c5411c833af1cd45b83d80c252b77c3bfdb43db17c441d772f4c734"}, - {file = "debugpy-1.6.3-cp39-cp39-macosx_10_15_x86_64.whl", hash = "sha256:4e255982552b0edfe3a6264438dbd62d404baa6556a81a88f9420d3ed79b06ae"}, - {file = "debugpy-1.6.3-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:cca23cb6161ac89698d629d892520327dd1be9321c0960e610bbcb807232b45d"}, - {file = "debugpy-1.6.3-cp39-cp39-win32.whl", hash = "sha256:7c302095a81be0d5c19f6529b600bac971440db3e226dce85347cc27e6a61908"}, - {file = "debugpy-1.6.3-cp39-cp39-win_amd64.whl", hash = "sha256:34d2cdd3a7c87302ba5322b86e79c32c2115be396f3f09ca13306d8a04fe0f16"}, - {file = "debugpy-1.6.3-py2.py3-none-any.whl", hash = "sha256:84c39940a0cac410bf6aa4db00ba174f973eef521fbe9dd058e26bcabad89c4f"}, - {file = "debugpy-1.6.3.zip", hash = "sha256:e8922090514a890eec99cfb991bab872dd2e353ebb793164d5f01c362b9a40bf"}, -] -decorator = [ - {file = "decorator-5.1.1-py3-none-any.whl", hash = "sha256:b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186"}, - {file = "decorator-5.1.1.tar.gz", hash = "sha256:637996211036b6385ef91435e4fae22989472f9d571faba8927ba8253acbc330"}, -] -defusedxml = [ - {file = "defusedxml-0.7.1-py2.py3-none-any.whl", hash = "sha256:a352e7e428770286cc899e2542b6cdaedb2b4953ff269a210103ec58f6198a61"}, - {file = "defusedxml-0.7.1.tar.gz", hash = "sha256:1bb3032db185915b62d7c6209c5a8792be6a32ab2fedacc84e01b52c51aa3e69"}, -] -drake = [ - {file = "drake-1.10.0-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:360151465c0fb6c997aac7002490a25fee4bdfe796e3c823030d2f35824055b8"}, - {file = "drake-1.10.0-cp310-cp310-macosx_12_0_x86_64.whl", hash = "sha256:1b6ef6e417fdd4214a9b2e0a03e501004cce637a144f1159e60845d8e64012eb"}, - {file = "drake-1.10.0-cp310-cp310-manylinux_2_31_x86_64.whl", hash = "sha256:f1943d743252d8d3e67ce74c5056e62bd35f15ec09e68df5b9af3a8087153dbf"}, - {file = "drake-1.10.0-cp38-cp38-manylinux_2_31_x86_64.whl", hash = "sha256:3f035a5b94f206b33b7a8c615edfdf6d2d1216e062539fe7d77e49991474457e"}, - {file = "drake-1.10.0-cp39-cp39-manylinux_2_31_x86_64.whl", hash = "sha256:49763efc21a310a9edb0e4e34e1bfd5416d650a2d47c823e55b31630b8fe756b"}, -] -entrypoints = [ - {file = "entrypoints-0.4-py3-none-any.whl", hash = "sha256:f174b5ff827504fd3cd97cc3f8649f3693f51538c7e4bdf3ef002c8429d42f9f"}, - {file = "entrypoints-0.4.tar.gz", hash = "sha256:b706eddaa9218a19ebcd67b56818f05bb27589b1ca9e8d797b74affad4ccacd4"}, -] -exceptiongroup = [ - {file = "exceptiongroup-1.0.4-py3-none-any.whl", hash = "sha256:542adf9dea4055530d6e1279602fa5cb11dab2395fa650b8674eaec35fc4a828"}, - {file = "exceptiongroup-1.0.4.tar.gz", hash = "sha256:bd14967b79cd9bdb54d97323216f8fdf533e278df937aa2a90089e7d6e06e5ec"}, -] -executing = [ - {file = "executing-1.2.0-py2.py3-none-any.whl", hash = "sha256:0314a69e37426e3608aada02473b4161d4caf5a4b244d1d0c48072b8fee7bacc"}, - {file = "executing-1.2.0.tar.gz", hash = "sha256:19da64c18d2d851112f09c287f8d3dbbdf725ab0e569077efb6cdcbd3497c107"}, -] -fastjsonschema = [ - {file = "fastjsonschema-2.16.2-py3-none-any.whl", hash = "sha256:21f918e8d9a1a4ba9c22e09574ba72267a6762d47822db9add95f6454e51cc1c"}, - {file = "fastjsonschema-2.16.2.tar.gz", hash = "sha256:01e366f25d9047816fe3d288cbfc3e10541daf0af2044763f3d0ade42476da18"}, -] -fonttools = [ - {file = "fonttools-4.38.0-py3-none-any.whl", hash = "sha256:820466f43c8be8c3009aef8b87e785014133508f0de64ec469e4efb643ae54fb"}, - {file = "fonttools-4.38.0.zip", hash = "sha256:2bb244009f9bf3fa100fc3ead6aeb99febe5985fa20afbfbaa2f8946c2fbdaf1"}, -] -idna = [ - {file = "idna-3.4-py3-none-any.whl", hash = "sha256:90b77e79eaa3eba6de819a0c442c0b4ceefc341a7a2ab77d7562bf49f425c5c2"}, - {file = "idna-3.4.tar.gz", hash = "sha256:814f528e8dead7d329833b91c5faa87d60bf71824cd12a7530b5526063d02cb4"}, -] -importlib-metadata = [ - {file = "importlib_metadata-5.0.0-py3-none-any.whl", hash = "sha256:ddb0e35065e8938f867ed4928d0ae5bf2a53b7773871bfe6bcc7e4fcdc7dea43"}, - {file = "importlib_metadata-5.0.0.tar.gz", hash = "sha256:da31db32b304314d044d3c12c79bd59e307889b287ad12ff387b3500835fc2ab"}, -] -iniconfig = [ - {file = "iniconfig-1.1.1-py2.py3-none-any.whl", hash = "sha256:011e24c64b7f47f6ebd835bb12a743f2fbe9a26d4cecaa7f53bc4f35ee9da8b3"}, - {file = "iniconfig-1.1.1.tar.gz", hash = "sha256:bc3af051d7d14b2ee5ef9969666def0cd1a000e121eaea580d4a313df4b37f32"}, -] -ipykernel = [ - {file = "ipykernel-6.17.1-py3-none-any.whl", hash = "sha256:3a9a1b2ad6dbbd5879855aabb4557f08e63fa2208bffed897f03070e2bb436f6"}, - {file = "ipykernel-6.17.1.tar.gz", hash = "sha256:e178c1788399f93a459c241fe07c3b810771c607b1fb064a99d2c5d40c90c5d4"}, -] -ipython = [ - {file = "ipython-8.6.0-py3-none-any.whl", hash = "sha256:91ef03016bcf72dd17190f863476e7c799c6126ec7e8be97719d1bc9a78a59a4"}, - {file = "ipython-8.6.0.tar.gz", hash = "sha256:7c959e3dedbf7ed81f9b9d8833df252c430610e2a4a6464ec13cd20975ce20a5"}, -] -ipython-genutils = [ - {file = "ipython_genutils-0.2.0-py2.py3-none-any.whl", hash = "sha256:72dd37233799e619666c9f639a9da83c34013a73e8bbc79a7a6348d93c61fab8"}, - {file = "ipython_genutils-0.2.0.tar.gz", hash = "sha256:eb2e116e75ecef9d4d228fdc66af54269afa26ab4463042e33785b887c628ba8"}, -] -ipywidgets = [ - {file = "ipywidgets-8.0.2-py3-none-any.whl", hash = "sha256:1dc3dd4ee19ded045ea7c86eb273033d238d8e43f9e7872c52d092683f263891"}, - {file = "ipywidgets-8.0.2.tar.gz", hash = "sha256:08cb75c6e0a96836147cbfdc55580ae04d13e05d26ffbc377b4e1c68baa28b1f"}, -] -jedi = [ - {file = "jedi-0.18.1-py2.py3-none-any.whl", hash = "sha256:637c9635fcf47945ceb91cd7f320234a7be540ded6f3e99a50cb6febdfd1ba8d"}, - {file = "jedi-0.18.1.tar.gz", hash = "sha256:74137626a64a99c8eb6ae5832d99b3bdd7d29a3850fe2aa80a4126b2a7d949ab"}, -] -jinja2 = [ - {file = "Jinja2-3.1.2-py3-none-any.whl", hash = "sha256:6088930bfe239f0e6710546ab9c19c9ef35e29792895fed6e6e31a023a182a61"}, - {file = "Jinja2-3.1.2.tar.gz", hash = "sha256:31351a702a408a9e7595a8fc6150fc3f43bb6bf7e319770cbc0db9df9437e852"}, -] -jsonschema = [ - {file = "jsonschema-4.17.0-py3-none-any.whl", hash = "sha256:f660066c3966db7d6daeaea8a75e0b68237a48e51cf49882087757bb59916248"}, - {file = "jsonschema-4.17.0.tar.gz", hash = "sha256:5bfcf2bca16a087ade17e02b282d34af7ccd749ef76241e7f9bd7c0cb8a9424d"}, -] -jupyter = [ - {file = "jupyter-1.0.0-py2.py3-none-any.whl", hash = "sha256:5b290f93b98ffbc21c0c7e749f054b3267782166d72fa5e3ed1ed4eaf34a2b78"}, - {file = "jupyter-1.0.0.tar.gz", hash = "sha256:d9dc4b3318f310e34c82951ea5d6683f67bed7def4b259fafbfe4f1beb1d8e5f"}, - {file = "jupyter-1.0.0.zip", hash = "sha256:3e1f86076bbb7c8c207829390305a2b1fe836d471ed54be66a3b8c41e7f46cc7"}, -] -jupyter-client = [ - {file = "jupyter_client-7.4.7-py3-none-any.whl", hash = "sha256:df56ae23b8e1da1b66f89dee1368e948b24a7f780fa822c5735187589fc4c157"}, - {file = "jupyter_client-7.4.7.tar.gz", hash = "sha256:330f6b627e0b4bf2f54a3a0dd9e4a22d2b649c8518168afedce2c96a1ceb2860"}, -] -jupyter-console = [ - {file = "jupyter_console-6.4.4-py3-none-any.whl", hash = "sha256:756df7f4f60c986e7bc0172e4493d3830a7e6e75c08750bbe59c0a5403ad6dee"}, - {file = "jupyter_console-6.4.4.tar.gz", hash = "sha256:172f5335e31d600df61613a97b7f0352f2c8250bbd1092ef2d658f77249f89fb"}, -] -jupyter-core = [ - {file = "jupyter_core-5.0.0-py3-none-any.whl", hash = "sha256:6da1fae48190da8551e1b5dbbb19d51d00b079d59a073c7030407ecaf96dbb1e"}, - {file = "jupyter_core-5.0.0.tar.gz", hash = "sha256:4ed68b7c606197c7e344a24b7195eef57898157075a69655a886074b6beb7043"}, -] -jupyter-server = [ - {file = "jupyter_server-1.23.2-py3-none-any.whl", hash = "sha256:c01d0e84c22a14dd6b0e7d8ce4105b08a3426b46582668e28046a64c07311a4f"}, - {file = "jupyter_server-1.23.2.tar.gz", hash = "sha256:69cb954ef02c0ba1837787e34e4a1240c93c8eb590662fae1840778861957660"}, -] -jupyterlab-pygments = [ - {file = "jupyterlab_pygments-0.2.2-py2.py3-none-any.whl", hash = "sha256:2405800db07c9f770863bcf8049a529c3dd4d3e28536638bd7c1c01d2748309f"}, - {file = "jupyterlab_pygments-0.2.2.tar.gz", hash = "sha256:7405d7fde60819d905a9fa8ce89e4cd830e318cdad22a0030f7a901da705585d"}, -] -jupyterlab-widgets = [ - {file = "jupyterlab_widgets-3.0.3-py3-none-any.whl", hash = "sha256:6aa1bc0045470d54d76b9c0b7609a8f8f0087573bae25700a370c11f82cb38c8"}, - {file = "jupyterlab_widgets-3.0.3.tar.gz", hash = "sha256:c767181399b4ca8b647befe2d913b1260f51bf9d8ef9b7a14632d4c1a7b536bd"}, -] -kiwisolver = [ - {file = "kiwisolver-1.4.4-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:2f5e60fabb7343a836360c4f0919b8cd0d6dbf08ad2ca6b9cf90bf0c76a3c4f6"}, - {file = "kiwisolver-1.4.4-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:10ee06759482c78bdb864f4109886dff7b8a56529bc1609d4f1112b93fe6423c"}, - {file = "kiwisolver-1.4.4-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c79ebe8f3676a4c6630fd3f777f3cfecf9289666c84e775a67d1d358578dc2e3"}, - {file = "kiwisolver-1.4.4-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:abbe9fa13da955feb8202e215c4018f4bb57469b1b78c7a4c5c7b93001699938"}, - {file = "kiwisolver-1.4.4-cp310-cp310-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:7577c1987baa3adc4b3c62c33bd1118c3ef5c8ddef36f0f2c950ae0b199e100d"}, - {file = "kiwisolver-1.4.4-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f8ad8285b01b0d4695102546b342b493b3ccc6781fc28c8c6a1bb63e95d22f09"}, - {file = "kiwisolver-1.4.4-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8ed58b8acf29798b036d347791141767ccf65eee7f26bde03a71c944449e53de"}, - {file = "kiwisolver-1.4.4-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a68b62a02953b9841730db7797422f983935aeefceb1679f0fc85cbfbd311c32"}, - {file = "kiwisolver-1.4.4-cp310-cp310-win32.whl", hash = "sha256:e92a513161077b53447160b9bd8f522edfbed4bd9759e4c18ab05d7ef7e49408"}, - {file = "kiwisolver-1.4.4-cp310-cp310-win_amd64.whl", hash = "sha256:3fe20f63c9ecee44560d0e7f116b3a747a5d7203376abeea292ab3152334d004"}, - {file = "kiwisolver-1.4.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e0ea21f66820452a3f5d1655f8704a60d66ba1191359b96541eaf457710a5fc6"}, - {file = "kiwisolver-1.4.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:bc9db8a3efb3e403e4ecc6cd9489ea2bac94244f80c78e27c31dcc00d2790ac2"}, - {file = "kiwisolver-1.4.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d5b61785a9ce44e5a4b880272baa7cf6c8f48a5180c3e81c59553ba0cb0821ca"}, - {file = "kiwisolver-1.4.4-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c2dbb44c3f7e6c4d3487b31037b1bdbf424d97687c1747ce4ff2895795c9bf69"}, - {file = "kiwisolver-1.4.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6295ecd49304dcf3bfbfa45d9a081c96509e95f4b9d0eb7ee4ec0530c4a96514"}, - {file = "kiwisolver-1.4.4-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4bd472dbe5e136f96a4b18f295d159d7f26fd399136f5b17b08c4e5f498cd494"}, - {file = "kiwisolver-1.4.4-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:bf7d9fce9bcc4752ca4a1b80aabd38f6d19009ea5cbda0e0856983cf6d0023f5"}, - {file = "kiwisolver-1.4.4-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:78d6601aed50c74e0ef02f4204da1816147a6d3fbdc8b3872d263338a9052c51"}, - {file = "kiwisolver-1.4.4-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:877272cf6b4b7e94c9614f9b10140e198d2186363728ed0f701c6eee1baec1da"}, - {file = "kiwisolver-1.4.4-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:db608a6757adabb32f1cfe6066e39b3706d8c3aa69bbc353a5b61edad36a5cb4"}, - {file = "kiwisolver-1.4.4-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:5853eb494c71e267912275e5586fe281444eb5e722de4e131cddf9d442615626"}, - {file = "kiwisolver-1.4.4-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:f0a1dbdb5ecbef0d34eb77e56fcb3e95bbd7e50835d9782a45df81cc46949750"}, - {file = "kiwisolver-1.4.4-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:283dffbf061a4ec60391d51e6155e372a1f7a4f5b15d59c8505339454f8989e4"}, - {file = "kiwisolver-1.4.4-cp311-cp311-win32.whl", hash = "sha256:d06adcfa62a4431d404c31216f0f8ac97397d799cd53800e9d3efc2fbb3cf14e"}, - {file = "kiwisolver-1.4.4-cp311-cp311-win_amd64.whl", hash = "sha256:e7da3fec7408813a7cebc9e4ec55afed2d0fd65c4754bc376bf03498d4e92686"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:62ac9cc684da4cf1778d07a89bf5f81b35834cb96ca523d3a7fb32509380cbf6"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:41dae968a94b1ef1897cb322b39360a0812661dba7c682aa45098eb8e193dbdf"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:02f79693ec433cb4b5f51694e8477ae83b3205768a6fb48ffba60549080e295b"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d0611a0a2a518464c05ddd5a3a1a0e856ccc10e67079bb17f265ad19ab3c7597"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:db5283d90da4174865d520e7366801a93777201e91e79bacbac6e6927cbceede"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:1041feb4cda8708ce73bb4dcb9ce1ccf49d553bf87c3954bdfa46f0c3f77252c"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-win32.whl", hash = "sha256:a553dadda40fef6bfa1456dc4be49b113aa92c2a9a9e8711e955618cd69622e3"}, - {file = "kiwisolver-1.4.4-cp37-cp37m-win_amd64.whl", hash = "sha256:03baab2d6b4a54ddbb43bba1a3a2d1627e82d205c5cf8f4c924dc49284b87166"}, - {file = "kiwisolver-1.4.4-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:841293b17ad704d70c578f1f0013c890e219952169ce8a24ebc063eecf775454"}, - {file = "kiwisolver-1.4.4-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:f4f270de01dd3e129a72efad823da90cc4d6aafb64c410c9033aba70db9f1ff0"}, - {file = "kiwisolver-1.4.4-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:f9f39e2f049db33a908319cf46624a569b36983c7c78318e9726a4cb8923b26c"}, - {file = "kiwisolver-1.4.4-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c97528e64cb9ebeff9701e7938653a9951922f2a38bd847787d4a8e498cc83ae"}, - {file = "kiwisolver-1.4.4-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1d1573129aa0fd901076e2bfb4275a35f5b7aa60fbfb984499d661ec950320b0"}, - {file = "kiwisolver-1.4.4-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ad881edc7ccb9d65b0224f4e4d05a1e85cf62d73aab798943df6d48ab0cd79a1"}, - {file = "kiwisolver-1.4.4-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:b428ef021242344340460fa4c9185d0b1f66fbdbfecc6c63eff4b7c29fad429d"}, - {file = "kiwisolver-1.4.4-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:2e407cb4bd5a13984a6c2c0fe1845e4e41e96f183e5e5cd4d77a857d9693494c"}, - {file = "kiwisolver-1.4.4-cp38-cp38-win32.whl", hash = "sha256:75facbe9606748f43428fc91a43edb46c7ff68889b91fa31f53b58894503a191"}, - {file = "kiwisolver-1.4.4-cp38-cp38-win_amd64.whl", hash = "sha256:5bce61af018b0cb2055e0e72e7d65290d822d3feee430b7b8203d8a855e78766"}, - {file = "kiwisolver-1.4.4-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:8c808594c88a025d4e322d5bb549282c93c8e1ba71b790f539567932722d7bd8"}, - {file = "kiwisolver-1.4.4-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:f0a71d85ecdd570ded8ac3d1c0f480842f49a40beb423bb8014539a9f32a5897"}, - {file = "kiwisolver-1.4.4-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:b533558eae785e33e8c148a8d9921692a9fe5aa516efbdff8606e7d87b9d5824"}, - {file = "kiwisolver-1.4.4-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:efda5fc8cc1c61e4f639b8067d118e742b812c930f708e6667a5ce0d13499e29"}, - {file = "kiwisolver-1.4.4-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:7c43e1e1206cd421cd92e6b3280d4385d41d7166b3ed577ac20444b6995a445f"}, - {file = "kiwisolver-1.4.4-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bc8d3bd6c72b2dd9decf16ce70e20abcb3274ba01b4e1c96031e0c4067d1e7cd"}, - {file = "kiwisolver-1.4.4-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4ea39b0ccc4f5d803e3337dd46bcce60b702be4d86fd0b3d7531ef10fd99a1ac"}, - {file = "kiwisolver-1.4.4-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:968f44fdbf6dd757d12920d63b566eeb4d5b395fd2d00d29d7ef00a00582aac9"}, - {file = "kiwisolver-1.4.4-cp39-cp39-win32.whl", hash = "sha256:da7e547706e69e45d95e116e6939488d62174e033b763ab1496b4c29b76fabea"}, - {file = "kiwisolver-1.4.4-cp39-cp39-win_amd64.whl", hash = "sha256:ba59c92039ec0a66103b1d5fe588fa546373587a7d68f5c96f743c3396afc04b"}, - {file = "kiwisolver-1.4.4-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:91672bacaa030f92fc2f43b620d7b337fd9a5af28b0d6ed3f77afc43c4a64b5a"}, - {file = "kiwisolver-1.4.4-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:787518a6789009c159453da4d6b683f468ef7a65bbde796bcea803ccf191058d"}, - {file = "kiwisolver-1.4.4-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da152d8cdcab0e56e4f45eb08b9aea6455845ec83172092f09b0e077ece2cf7a"}, - {file = "kiwisolver-1.4.4-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:ecb1fa0db7bf4cff9dac752abb19505a233c7f16684c5826d1f11ebd9472b871"}, - {file = "kiwisolver-1.4.4-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:28bc5b299f48150b5f822ce68624e445040595a4ac3d59251703779836eceff9"}, - {file = "kiwisolver-1.4.4-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:81e38381b782cc7e1e46c4e14cd997ee6040768101aefc8fa3c24a4cc58e98f8"}, - {file = "kiwisolver-1.4.4-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:2a66fdfb34e05b705620dd567f5a03f239a088d5a3f321e7b6ac3239d22aa286"}, - {file = "kiwisolver-1.4.4-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:872b8ca05c40d309ed13eb2e582cab0c5a05e81e987ab9c521bf05ad1d5cf5cb"}, - {file = "kiwisolver-1.4.4-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:70e7c2e7b750585569564e2e5ca9845acfaa5da56ac46df68414f29fea97be9f"}, - {file = "kiwisolver-1.4.4-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:9f85003f5dfa867e86d53fac6f7e6f30c045673fa27b603c397753bebadc3008"}, - {file = "kiwisolver-1.4.4-pp39-pypy39_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2e307eb9bd99801f82789b44bb45e9f541961831c7311521b13a6c85afc09767"}, - {file = "kiwisolver-1.4.4-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b1792d939ec70abe76f5054d3f36ed5656021dcad1322d1cc996d4e54165cef9"}, - {file = "kiwisolver-1.4.4-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f6cb459eea32a4e2cf18ba5fcece2dbdf496384413bc1bae15583f19e567f3b2"}, - {file = "kiwisolver-1.4.4-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:36dafec3d6d6088d34e2de6b85f9d8e2324eb734162fba59d2ba9ed7a2043d5b"}, - {file = "kiwisolver-1.4.4.tar.gz", hash = "sha256:d41997519fcba4a1e46eb4a2fe31bc12f0ff957b2b81bac28db24744f333e955"}, -] -markupsafe = [ - {file = "MarkupSafe-2.1.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:86b1f75c4e7c2ac2ccdaec2b9022845dbb81880ca318bb7a0a01fbf7813e3812"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:f121a1420d4e173a5d96e47e9a0c0dcff965afdf1626d28de1460815f7c4ee7a"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a49907dd8420c5685cfa064a1335b6754b74541bbb3706c259c02ed65b644b3e"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:10c1bfff05d95783da83491be968e8fe789263689c02724e0c691933c52994f5"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b7bd98b796e2b6553da7225aeb61f447f80a1ca64f41d83612e6139ca5213aa4"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:b09bf97215625a311f669476f44b8b318b075847b49316d3e28c08e41a7a573f"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:694deca8d702d5db21ec83983ce0bb4b26a578e71fbdbd4fdcd387daa90e4d5e"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:efc1913fd2ca4f334418481c7e595c00aad186563bbc1ec76067848c7ca0a933"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-win32.whl", hash = "sha256:4a33dea2b688b3190ee12bd7cfa29d39c9ed176bda40bfa11099a3ce5d3a7ac6"}, - {file = "MarkupSafe-2.1.1-cp310-cp310-win_amd64.whl", hash = "sha256:dda30ba7e87fbbb7eab1ec9f58678558fd9a6b8b853530e176eabd064da81417"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:671cd1187ed5e62818414afe79ed29da836dde67166a9fac6d435873c44fdd02"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3799351e2336dc91ea70b034983ee71cf2f9533cdff7c14c90ea126bfd95d65a"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e72591e9ecd94d7feb70c1cbd7be7b3ebea3f548870aa91e2732960fa4d57a37"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6fbf47b5d3728c6aea2abb0589b5d30459e369baa772e0f37a0320185e87c980"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:d5ee4f386140395a2c818d149221149c54849dfcfcb9f1debfe07a8b8bd63f9a"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:bcb3ed405ed3222f9904899563d6fc492ff75cce56cba05e32eff40e6acbeaa3"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:e1c0b87e09fa55a220f058d1d49d3fb8df88fbfab58558f1198e08c1e1de842a"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-win32.whl", hash = "sha256:8dc1c72a69aa7e082593c4a203dcf94ddb74bb5c8a731e4e1eb68d031e8498ff"}, - {file = "MarkupSafe-2.1.1-cp37-cp37m-win_amd64.whl", hash = "sha256:97a68e6ada378df82bc9f16b800ab77cbf4b2fada0081794318520138c088e4a"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:e8c843bbcda3a2f1e3c2ab25913c80a3c5376cd00c6e8c4a86a89a28c8dc5452"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:0212a68688482dc52b2d45013df70d169f542b7394fc744c02a57374a4207003"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8e576a51ad59e4bfaac456023a78f6b5e6e7651dcd383bcc3e18d06f9b55d6d1"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4b9fe39a2ccc108a4accc2676e77da025ce383c108593d65cc909add5c3bd601"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:96e37a3dc86e80bf81758c152fe66dbf60ed5eca3d26305edf01892257049925"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:6d0072fea50feec76a4c418096652f2c3238eaa014b2f94aeb1d56a66b41403f"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:089cf3dbf0cd6c100f02945abeb18484bd1ee57a079aefd52cffd17fba910b88"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:6a074d34ee7a5ce3effbc526b7083ec9731bb3cbf921bbe1d3005d4d2bdb3a63"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-win32.whl", hash = "sha256:421be9fbf0ffe9ffd7a378aafebbf6f4602d564d34be190fc19a193232fd12b1"}, - {file = "MarkupSafe-2.1.1-cp38-cp38-win_amd64.whl", hash = "sha256:fc7b548b17d238737688817ab67deebb30e8073c95749d55538ed473130ec0c7"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:e04e26803c9c3851c931eac40c695602c6295b8d432cbe78609649ad9bd2da8a"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:b87db4360013327109564f0e591bd2a3b318547bcef31b468a92ee504d07ae4f"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:99a2a507ed3ac881b975a2976d59f38c19386d128e7a9a18b7df6fff1fd4c1d6"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:56442863ed2b06d19c37f94d999035e15ee982988920e12a5b4ba29b62ad1f77"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3ce11ee3f23f79dbd06fb3d63e2f6af7b12db1d46932fe7bd8afa259a5996603"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:33b74d289bd2f5e527beadcaa3f401e0df0a89927c1559c8566c066fa4248ab7"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:43093fb83d8343aac0b1baa75516da6092f58f41200907ef92448ecab8825135"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:8e3dcf21f367459434c18e71b2a9532d96547aef8a871872a5bd69a715c15f96"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-win32.whl", hash = "sha256:d4306c36ca495956b6d568d276ac11fdd9c30a36f1b6eb928070dc5360b22e1c"}, - {file = "MarkupSafe-2.1.1-cp39-cp39-win_amd64.whl", hash = "sha256:46d00d6cfecdde84d40e572d63735ef81423ad31184100411e6e3388d405e247"}, - {file = "MarkupSafe-2.1.1.tar.gz", hash = "sha256:7f91197cc9e48f989d12e4e6fbc46495c446636dfc81b9ccf50bb0ec74b91d4b"}, -] -matplotlib = [ - {file = "matplotlib-3.6.2-cp310-cp310-macosx_10_12_universal2.whl", hash = "sha256:8d0068e40837c1d0df6e3abf1cdc9a34a6d2611d90e29610fa1d2455aeb4e2e5"}, - {file = "matplotlib-3.6.2-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:252957e208c23db72ca9918cb33e160c7833faebf295aaedb43f5b083832a267"}, - {file = "matplotlib-3.6.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:d50e8c1e571ee39b5dfbc295c11ad65988879f68009dd281a6e1edbc2ff6c18c"}, - {file = "matplotlib-3.6.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d840adcad7354be6f2ec28d0706528b0026e4c3934cc6566b84eac18633eab1b"}, - {file = "matplotlib-3.6.2-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:78ec3c3412cf277e6252764ee4acbdbec6920cc87ad65862272aaa0e24381eee"}, - {file = "matplotlib-3.6.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9347cc6822f38db2b1d1ce992f375289670e595a2d1c15961aacbe0977407dfc"}, - {file = "matplotlib-3.6.2-cp310-cp310-win32.whl", hash = "sha256:e0bbee6c2a5bf2a0017a9b5e397babb88f230e6f07c3cdff4a4c4bc75ed7c617"}, - {file = "matplotlib-3.6.2-cp310-cp310-win_amd64.whl", hash = "sha256:8a0ae37576ed444fe853709bdceb2be4c7df6f7acae17b8378765bd28e61b3ae"}, - {file = "matplotlib-3.6.2-cp311-cp311-macosx_10_12_universal2.whl", hash = "sha256:5ecfc6559132116dedfc482d0ad9df8a89dc5909eebffd22f3deb684132d002f"}, - {file = "matplotlib-3.6.2-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:9f335e5625feb90e323d7e3868ec337f7b9ad88b5d633f876e3b778813021dab"}, - {file = "matplotlib-3.6.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b2604c6450f9dd2c42e223b1f5dca9643a23cfecc9fde4a94bb38e0d2693b136"}, - {file = "matplotlib-3.6.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e5afe0a7ea0e3a7a257907060bee6724a6002b7eec55d0db16fd32409795f3e1"}, - {file = "matplotlib-3.6.2-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ca0e7a658fbafcddcaefaa07ba8dae9384be2343468a8e011061791588d839fa"}, - {file = "matplotlib-3.6.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:32d29c8c26362169c80c5718ce367e8c64f4dd068a424e7110df1dd2ed7bd428"}, - {file = "matplotlib-3.6.2-cp311-cp311-win32.whl", hash = "sha256:5024b8ed83d7f8809982d095d8ab0b179bebc07616a9713f86d30cf4944acb73"}, - {file = "matplotlib-3.6.2-cp311-cp311-win_amd64.whl", hash = "sha256:52c2bdd7cd0bf9d5ccdf9c1816568fd4ccd51a4d82419cc5480f548981b47dd0"}, - {file = "matplotlib-3.6.2-cp38-cp38-macosx_10_12_universal2.whl", hash = "sha256:8a8dbe2cb7f33ff54b16bb5c500673502a35f18ac1ed48625e997d40c922f9cc"}, - {file = "matplotlib-3.6.2-cp38-cp38-macosx_10_12_x86_64.whl", hash = "sha256:380d48c15ec41102a2b70858ab1dedfa33eb77b2c0982cb65a200ae67a48e9cb"}, - {file = "matplotlib-3.6.2-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:0844523dfaaff566e39dbfa74e6f6dc42e92f7a365ce80929c5030b84caa563a"}, - {file = "matplotlib-3.6.2-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:7f716b6af94dc1b6b97c46401774472f0867e44595990fe80a8ba390f7a0a028"}, - {file = "matplotlib-3.6.2-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:74153008bd24366cf099d1f1e83808d179d618c4e32edb0d489d526523a94d9f"}, - {file = "matplotlib-3.6.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f41e57ad63d336fe50d3a67bb8eaa26c09f6dda6a59f76777a99b8ccd8e26aec"}, - {file = "matplotlib-3.6.2-cp38-cp38-win32.whl", hash = "sha256:d0e9ac04065a814d4cf2c6791a2ad563f739ae3ae830d716d54245c2b96fead6"}, - {file = "matplotlib-3.6.2-cp38-cp38-win_amd64.whl", hash = "sha256:8a9d899953c722b9afd7e88dbefd8fb276c686c3116a43c577cfabf636180558"}, - {file = "matplotlib-3.6.2-cp39-cp39-macosx_10_12_universal2.whl", hash = "sha256:f04f97797df35e442ed09f529ad1235d1f1c0f30878e2fe09a2676b71a8801e0"}, - {file = "matplotlib-3.6.2-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:3964934731fd7a289a91d315919cf757f293969a4244941ab10513d2351b4e83"}, - {file = "matplotlib-3.6.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:168093410b99f647ba61361b208f7b0d64dde1172b5b1796d765cd243cadb501"}, - {file = "matplotlib-3.6.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5e16dcaecffd55b955aa5e2b8a804379789c15987e8ebd2f32f01398a81e975b"}, - {file = "matplotlib-3.6.2-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:83dc89c5fd728fdb03b76f122f43b4dcee8c61f1489e232d9ad0f58020523e1c"}, - {file = "matplotlib-3.6.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:795ad83940732b45d39b82571f87af0081c120feff2b12e748d96bb191169e33"}, - {file = "matplotlib-3.6.2-cp39-cp39-win32.whl", hash = "sha256:19d61ee6414c44a04addbe33005ab1f87539d9f395e25afcbe9a3c50ce77c65c"}, - {file = "matplotlib-3.6.2-cp39-cp39-win_amd64.whl", hash = "sha256:5ba73aa3aca35d2981e0b31230d58abb7b5d7ca104e543ae49709208d8ce706a"}, - {file = "matplotlib-3.6.2-pp38-pypy38_pp73-macosx_10_12_x86_64.whl", hash = "sha256:1836f366272b1557a613f8265db220eb8dd883202bbbabe01bad5a4eadfd0c95"}, - {file = "matplotlib-3.6.2-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0eda9d1b43f265da91fb9ae10d6922b5a986e2234470a524e6b18f14095b20d2"}, - {file = "matplotlib-3.6.2-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec9be0f4826cdb3a3a517509dcc5f87f370251b76362051ab59e42b6b765f8c4"}, - {file = "matplotlib-3.6.2-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:3cef89888a466228fc4e4b2954e740ce8e9afde7c4315fdd18caa1b8de58ca17"}, - {file = "matplotlib-3.6.2-pp39-pypy39_pp73-macosx_10_12_x86_64.whl", hash = "sha256:54fa9fe27f5466b86126ff38123261188bed568c1019e4716af01f97a12fe812"}, - {file = "matplotlib-3.6.2-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e68be81cd8c22b029924b6d0ee814c337c0e706b8d88495a617319e5dd5441c3"}, - {file = "matplotlib-3.6.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b0ca2c60d3966dfd6608f5f8c49b8a0fcf76de6654f2eda55fc6ef038d5a6f27"}, - {file = "matplotlib-3.6.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:4426c74761790bff46e3d906c14c7aab727543293eed5a924300a952e1a3a3c1"}, - {file = "matplotlib-3.6.2.tar.gz", hash = "sha256:b03fd10a1709d0101c054883b550f7c4c5e974f751e2680318759af005964990"}, -] -matplotlib-inline = [ - {file = "matplotlib-inline-0.1.6.tar.gz", hash = "sha256:f887e5f10ba98e8d2b150ddcf4702c1e5f8b3a20005eb0f74bfdbd360ee6f304"}, - {file = "matplotlib_inline-0.1.6-py3-none-any.whl", hash = "sha256:f1f41aab5328aa5aaea9b16d083b128102f8712542f819fe7e6a420ff581b311"}, -] -meshcat = [ - {file = "meshcat-0.3.2-py3-none-any.whl", hash = "sha256:cba0465d0e29658c48bb65d27f5c8e04ff0a1ac8ce916d65621146c06258a1c7"}, - {file = "meshcat-0.3.2.tar.gz", hash = "sha256:2cfe17cde4fe85d072a3de018a9dabf5626f80c255fff2ce63b26a48d2484ad9"}, -] -mistune = [ - {file = "mistune-2.0.4-py2.py3-none-any.whl", hash = "sha256:182cc5ee6f8ed1b807de6b7bb50155df7b66495412836b9a74c8fbdfc75fe36d"}, - {file = "mistune-2.0.4.tar.gz", hash = "sha256:9ee0a66053e2267aba772c71e06891fa8f1af6d4b01d5e84e267b4570d4d9808"}, -] -nbclassic = [ - {file = "nbclassic-0.4.8-py3-none-any.whl", hash = "sha256:cbf05df5842b420d5cece0143462380ea9d308ff57c2dc0eb4d6e035b18fbfb3"}, - {file = "nbclassic-0.4.8.tar.gz", hash = "sha256:c74d8a500f8e058d46b576a41e5bc640711e1032cf7541dde5f73ea49497e283"}, -] -nbclient = [ - {file = "nbclient-0.7.0-py3-none-any.whl", hash = "sha256:434c91385cf3e53084185334d675a0d33c615108b391e260915d1aa8e86661b8"}, - {file = "nbclient-0.7.0.tar.gz", hash = "sha256:a1d844efd6da9bc39d2209bf996dbd8e07bf0f36b796edfabaa8f8a9ab77c3aa"}, -] -nbconvert = [ - {file = "nbconvert-7.2.5-py3-none-any.whl", hash = "sha256:3e90e108bb5637b5b8a1422af1156af1368b39dd25369ff7faa7dfdcdef18f81"}, - {file = "nbconvert-7.2.5.tar.gz", hash = "sha256:8fdc44fd7d9424db7fdc6e1e834a02f6b8620ffb653767388be2f9eb16f84184"}, -] -nbformat = [ - {file = "nbformat-5.7.0-py3-none-any.whl", hash = "sha256:1b05ec2c552c2f1adc745f4eddce1eac8ca9ffd59bb9fd859e827eaa031319f9"}, - {file = "nbformat-5.7.0.tar.gz", hash = "sha256:1d4760c15c1a04269ef5caf375be8b98dd2f696e5eb9e603ec2bf091f9b0d3f3"}, -] -nest-asyncio = [ - {file = "nest_asyncio-1.5.6-py3-none-any.whl", hash = "sha256:b9a953fb40dceaa587d109609098db21900182b16440652454a146cffb06e8b8"}, - {file = "nest_asyncio-1.5.6.tar.gz", hash = "sha256:d267cc1ff794403f7df692964d1d2a3fa9418ffea2a3f6859a439ff482fef290"}, -] -notebook = [ - {file = "notebook-6.5.2-py3-none-any.whl", hash = "sha256:e04f9018ceb86e4fa841e92ea8fb214f8d23c1cedfde530cc96f92446924f0e4"}, - {file = "notebook-6.5.2.tar.gz", hash = "sha256:c1897e5317e225fc78b45549a6ab4b668e4c996fd03a04e938fe5e7af2bfffd0"}, -] -notebook-shim = [ - {file = "notebook_shim-0.2.2-py3-none-any.whl", hash = "sha256:9c6c30f74c4fbea6fce55c1be58e7fd0409b1c681b075dcedceb005db5026949"}, - {file = "notebook_shim-0.2.2.tar.gz", hash = "sha256:090e0baf9a5582ff59b607af523ca2db68ff216da0c69956b62cab2ef4fc9c3f"}, -] -numpy = [ - {file = "numpy-1.23.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:9c88793f78fca17da0145455f0d7826bcb9f37da4764af27ac945488116efe63"}, - {file = "numpy-1.23.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:e9f4c4e51567b616be64e05d517c79a8a22f3606499941d97bb76f2ca59f982d"}, - {file = "numpy-1.23.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7903ba8ab592b82014713c491f6c5d3a1cde5b4a3bf116404e08f5b52f6daf43"}, - {file = "numpy-1.23.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5e05b1c973a9f858c74367553e236f287e749465f773328c8ef31abe18f691e1"}, - {file = "numpy-1.23.5-cp310-cp310-win32.whl", hash = "sha256:522e26bbf6377e4d76403826ed689c295b0b238f46c28a7251ab94716da0b280"}, - {file = "numpy-1.23.5-cp310-cp310-win_amd64.whl", hash = "sha256:dbee87b469018961d1ad79b1a5d50c0ae850000b639bcb1b694e9981083243b6"}, - {file = "numpy-1.23.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ce571367b6dfe60af04e04a1834ca2dc5f46004ac1cc756fb95319f64c095a96"}, - {file = "numpy-1.23.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:56e454c7833e94ec9769fa0f86e6ff8e42ee38ce0ce1fa4cbb747ea7e06d56aa"}, - {file = "numpy-1.23.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5039f55555e1eab31124a5768898c9e22c25a65c1e0037f4d7c495a45778c9f2"}, - {file = "numpy-1.23.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:58f545efd1108e647604a1b5aa809591ccd2540f468a880bedb97247e72db387"}, - {file = "numpy-1.23.5-cp311-cp311-win32.whl", hash = "sha256:b2a9ab7c279c91974f756c84c365a669a887efa287365a8e2c418f8b3ba73fb0"}, - {file = "numpy-1.23.5-cp311-cp311-win_amd64.whl", hash = "sha256:0cbe9848fad08baf71de1a39e12d1b6310f1d5b2d0ea4de051058e6e1076852d"}, - {file = "numpy-1.23.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:f063b69b090c9d918f9df0a12116029e274daf0181df392839661c4c7ec9018a"}, - {file = "numpy-1.23.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:0aaee12d8883552fadfc41e96b4c82ee7d794949e2a7c3b3a7201e968c7ecab9"}, - {file = "numpy-1.23.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:92c8c1e89a1f5028a4c6d9e3ccbe311b6ba53694811269b992c0b224269e2398"}, - {file = "numpy-1.23.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d208a0f8729f3fb790ed18a003f3a57895b989b40ea4dce4717e9cf4af62c6bb"}, - {file = "numpy-1.23.5-cp38-cp38-win32.whl", hash = "sha256:06005a2ef6014e9956c09ba07654f9837d9e26696a0470e42beedadb78c11b07"}, - {file = "numpy-1.23.5-cp38-cp38-win_amd64.whl", hash = "sha256:ca51fcfcc5f9354c45f400059e88bc09215fb71a48d3768fb80e357f3b457e1e"}, - {file = "numpy-1.23.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:8969bfd28e85c81f3f94eb4a66bc2cf1dbdc5c18efc320af34bffc54d6b1e38f"}, - {file = "numpy-1.23.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:a7ac231a08bb37f852849bbb387a20a57574a97cfc7b6cabb488a4fc8be176de"}, - {file = "numpy-1.23.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bf837dc63ba5c06dc8797c398db1e223a466c7ece27a1f7b5232ba3466aafe3d"}, - {file = "numpy-1.23.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:33161613d2269025873025b33e879825ec7b1d831317e68f4f2f0f84ed14c719"}, - {file = "numpy-1.23.5-cp39-cp39-win32.whl", hash = "sha256:af1da88f6bc3d2338ebbf0e22fe487821ea4d8e89053e25fa59d1d79786e7481"}, - {file = "numpy-1.23.5-cp39-cp39-win_amd64.whl", hash = "sha256:09b7847f7e83ca37c6e627682f145856de331049013853f344f37b0c9690e3df"}, - {file = "numpy-1.23.5-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:abdde9f795cf292fb9651ed48185503a2ff29be87770c3b8e2a14b0cd7aa16f8"}, - {file = "numpy-1.23.5-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f9a909a8bae284d46bbfdefbdd4a262ba19d3bc9921b1e76126b1d21c3c34135"}, - {file = "numpy-1.23.5-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:01dd17cbb340bf0fc23981e52e1d18a9d4050792e8fb8363cecbf066a84b827d"}, - {file = "numpy-1.23.5.tar.gz", hash = "sha256:1b1766d6f397c18153d40015ddfc79ddb715cabadc04d2d228d4e5a8bc4ded1a"}, -] -nvidia-cublas-cu11 = [ - {file = "nvidia_cublas_cu11-11.10.3.66-py3-none-manylinux1_x86_64.whl", hash = "sha256:d32e4d75f94ddfb93ea0a5dda08389bcc65d8916a25cb9f37ac89edaeed3bded"}, - {file = "nvidia_cublas_cu11-11.10.3.66-py3-none-win_amd64.whl", hash = "sha256:8ac17ba6ade3ed56ab898a036f9ae0756f1e81052a317bf98f8c6d18dc3ae49e"}, -] -nvidia-cuda-nvrtc-cu11 = [ - {file = "nvidia_cuda_nvrtc_cu11-11.7.99-2-py3-none-manylinux1_x86_64.whl", hash = "sha256:9f1562822ea264b7e34ed5930567e89242d266448e936b85bc97a3370feabb03"}, - {file = "nvidia_cuda_nvrtc_cu11-11.7.99-py3-none-manylinux1_x86_64.whl", hash = "sha256:f7d9610d9b7c331fa0da2d1b2858a4a8315e6d49765091d28711c8946e7425e7"}, - {file = "nvidia_cuda_nvrtc_cu11-11.7.99-py3-none-win_amd64.whl", hash = "sha256:f2effeb1309bdd1b3854fc9b17eaf997808f8b25968ce0c7070945c4265d64a3"}, -] -nvidia-cuda-runtime-cu11 = [ - {file = "nvidia_cuda_runtime_cu11-11.7.99-py3-none-manylinux1_x86_64.whl", hash = "sha256:cc768314ae58d2641f07eac350f40f99dcb35719c4faff4bc458a7cd2b119e31"}, - {file = "nvidia_cuda_runtime_cu11-11.7.99-py3-none-win_amd64.whl", hash = "sha256:bc77fa59a7679310df9d5c70ab13c4e34c64ae2124dd1efd7e5474b71be125c7"}, -] -nvidia-cudnn-cu11 = [ - {file = "nvidia_cudnn_cu11-8.5.0.96-2-py3-none-manylinux1_x86_64.whl", hash = "sha256:402f40adfc6f418f9dae9ab402e773cfed9beae52333f6d86ae3107a1b9527e7"}, - {file = "nvidia_cudnn_cu11-8.5.0.96-py3-none-manylinux1_x86_64.whl", hash = "sha256:71f8111eb830879ff2836db3cccf03bbd735df9b0d17cd93761732ac50a8a108"}, -] -packaging = [ - {file = "packaging-21.3-py3-none-any.whl", hash = "sha256:ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522"}, - {file = "packaging-21.3.tar.gz", hash = "sha256:dd47c42927d89ab911e606518907cc2d3a1f38bbd026385970643f9c5b8ecfeb"}, -] -pandas = [ - {file = "pandas-1.5.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:0a78e05ec09731c5b3bd7a9805927ea631fe6f6cb06f0e7c63191a9a778d52b4"}, - {file = "pandas-1.5.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:5b0c970e2215572197b42f1cff58a908d734503ea54b326412c70d4692256391"}, - {file = "pandas-1.5.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:f340331a3f411910adfb4bbe46c2ed5872d9e473a783d7f14ecf49bc0869c594"}, - {file = "pandas-1.5.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8c709f4700573deb2036d240d140934df7e852520f4a584b2a8d5443b71f54d"}, - {file = "pandas-1.5.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:32e3d9f65606b3f6e76555bfd1d0b68d94aff0929d82010b791b6254bf5a4b96"}, - {file = "pandas-1.5.1-cp310-cp310-win_amd64.whl", hash = "sha256:a52419d9ba5906db516109660b114faf791136c94c1a636ed6b29cbfff9187ee"}, - {file = "pandas-1.5.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:66a1ad667b56e679e06ba73bb88c7309b3f48a4c279bd3afea29f65a766e9036"}, - {file = "pandas-1.5.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:36aa1f8f680d7584e9b572c3203b20d22d697c31b71189322f16811d4ecfecd3"}, - {file = "pandas-1.5.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:bcf1a82b770b8f8c1e495b19a20d8296f875a796c4fe6e91da5ef107f18c5ecb"}, - {file = "pandas-1.5.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c25e5c16ee5c0feb6cf9d982b869eec94a22ddfda9aa2fbed00842cbb697624"}, - {file = "pandas-1.5.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:932d2d7d3cab44cfa275601c982f30c2d874722ef6396bb539e41e4dc4618ed4"}, - {file = "pandas-1.5.1-cp311-cp311-win_amd64.whl", hash = "sha256:eb7e8cf2cf11a2580088009b43de84cabbf6f5dae94ceb489f28dba01a17cb77"}, - {file = "pandas-1.5.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:cb2a9cf1150302d69bb99861c5cddc9c25aceacb0a4ef5299785d0f5389a3209"}, - {file = "pandas-1.5.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:81f0674fa50b38b6793cd84fae5d67f58f74c2d974d2cb4e476d26eee33343d0"}, - {file = "pandas-1.5.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:17da7035d9e6f9ea9cdc3a513161f8739b8f8489d31dc932bc5a29a27243f93d"}, - {file = "pandas-1.5.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:669c8605dba6c798c1863157aefde959c1796671ffb342b80fcb80a4c0bc4c26"}, - {file = "pandas-1.5.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:683779e5728ac9138406c59a11e09cd98c7d2c12f0a5fc2b9c5eecdbb4a00075"}, - {file = "pandas-1.5.1-cp38-cp38-win32.whl", hash = "sha256:ddf46b940ef815af4e542697eaf071f0531449407a7607dd731bf23d156e20a7"}, - {file = "pandas-1.5.1-cp38-cp38-win_amd64.whl", hash = "sha256:db45b94885000981522fb92349e6b76f5aee0924cc5315881239c7859883117d"}, - {file = "pandas-1.5.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:927e59c694e039c75d7023465d311277a1fc29ed7236b5746e9dddf180393113"}, - {file = "pandas-1.5.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:e675f8fe9aa6c418dc8d3aac0087b5294c1a4527f1eacf9fe5ea671685285454"}, - {file = "pandas-1.5.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:04e51b01d5192499390c0015630975f57836cc95c7411415b499b599b05c0c96"}, - {file = "pandas-1.5.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5cee0c74e93ed4f9d39007e439debcaadc519d7ea5c0afc3d590a3a7b2edf060"}, - {file = "pandas-1.5.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b156a971bc451c68c9e1f97567c94fd44155f073e3bceb1b0d195fd98ed12048"}, - {file = "pandas-1.5.1-cp39-cp39-win32.whl", hash = "sha256:05c527c64ee02a47a24031c880ee0ded05af0623163494173204c5b72ddce658"}, - {file = "pandas-1.5.1-cp39-cp39-win_amd64.whl", hash = "sha256:6bb391659a747cf4f181a227c3e64b6d197100d53da98dcd766cc158bdd9ec68"}, - {file = "pandas-1.5.1.tar.gz", hash = "sha256:249cec5f2a5b22096440bd85c33106b6102e0672204abd2d5c014106459804ee"}, -] -pandocfilters = [ - {file = "pandocfilters-1.5.0-py2.py3-none-any.whl", hash = "sha256:33aae3f25fd1a026079f5d27bdd52496f0e0803b3469282162bafdcbdf6ef14f"}, - {file = "pandocfilters-1.5.0.tar.gz", hash = "sha256:0b679503337d233b4339a817bfc8c50064e2eff681314376a47cb582305a7a38"}, -] -parso = [ - {file = "parso-0.8.3-py2.py3-none-any.whl", hash = "sha256:c001d4636cd3aecdaf33cbb40aebb59b094be2a74c556778ef5576c175e19e75"}, - {file = "parso-0.8.3.tar.gz", hash = "sha256:8c07be290bb59f03588915921e29e8a50002acaf2cdc5fa0e0114f91709fafa0"}, -] -pexpect = [ - {file = "pexpect-4.8.0-py2.py3-none-any.whl", hash = "sha256:0b48a55dcb3c05f3329815901ea4fc1537514d6ba867a152b581d69ae3710937"}, - {file = "pexpect-4.8.0.tar.gz", hash = "sha256:fc65a43959d153d0114afe13997d439c22823a27cefceb5ff35c2178c6784c0c"}, -] -pickleshare = [ - {file = "pickleshare-0.7.5-py2.py3-none-any.whl", hash = "sha256:9649af414d74d4df115d5d718f82acb59c9d418196b7b4290ed47a12ce62df56"}, - {file = "pickleshare-0.7.5.tar.gz", hash = "sha256:87683d47965c1da65cdacaf31c8441d12b8044cdec9aca500cd78fc2c683afca"}, -] -pillow = [ - {file = "Pillow-9.3.0-1-cp37-cp37m-win32.whl", hash = "sha256:e6ea6b856a74d560d9326c0f5895ef8050126acfdc7ca08ad703eb0081e82b74"}, - {file = "Pillow-9.3.0-1-cp37-cp37m-win_amd64.whl", hash = "sha256:32a44128c4bdca7f31de5be641187367fe2a450ad83b833ef78910397db491aa"}, - {file = "Pillow-9.3.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:0b7257127d646ff8676ec8a15520013a698d1fdc48bc2a79ba4e53df792526f2"}, - {file = "Pillow-9.3.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:b90f7616ea170e92820775ed47e136208e04c967271c9ef615b6fbd08d9af0e3"}, - {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:68943d632f1f9e3dce98908e873b3a090f6cba1cbb1b892a9e8d97c938871fbe"}, - {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:be55f8457cd1eac957af0c3f5ece7bc3f033f89b114ef30f710882717670b2a8"}, - {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5d77adcd56a42d00cc1be30843d3426aa4e660cab4a61021dc84467123f7a00c"}, - {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:829f97c8e258593b9daa80638aee3789b7df9da5cf1336035016d76f03b8860c"}, - {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:801ec82e4188e935c7f5e22e006d01611d6b41661bba9fe45b60e7ac1a8f84de"}, - {file = "Pillow-9.3.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:871b72c3643e516db4ecf20efe735deb27fe30ca17800e661d769faab45a18d7"}, - {file = "Pillow-9.3.0-cp310-cp310-win32.whl", hash = "sha256:655a83b0058ba47c7c52e4e2df5ecf484c1b0b0349805896dd350cbc416bdd91"}, - {file = "Pillow-9.3.0-cp310-cp310-win_amd64.whl", hash = "sha256:9f47eabcd2ded7698106b05c2c338672d16a6f2a485e74481f524e2a23c2794b"}, - {file = "Pillow-9.3.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:57751894f6618fd4308ed8e0c36c333e2f5469744c34729a27532b3db106ee20"}, - {file = "Pillow-9.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7db8b751ad307d7cf238f02101e8e36a128a6cb199326e867d1398067381bff4"}, - {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3033fbe1feb1b59394615a1cafaee85e49d01b51d54de0cbf6aa8e64182518a1"}, - {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:22b012ea2d065fd163ca096f4e37e47cd8b59cf4b0fd47bfca6abb93df70b34c"}, - {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b9a65733d103311331875c1dca05cb4606997fd33d6acfed695b1232ba1df193"}, - {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:502526a2cbfa431d9fc2a079bdd9061a2397b842bb6bc4239bb176da00993812"}, - {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:90fb88843d3902fe7c9586d439d1e8c05258f41da473952aa8b328d8b907498c"}, - {file = "Pillow-9.3.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:89dca0ce00a2b49024df6325925555d406b14aa3efc2f752dbb5940c52c56b11"}, - {file = "Pillow-9.3.0-cp311-cp311-win32.whl", hash = "sha256:3168434d303babf495d4ba58fc22d6604f6e2afb97adc6a423e917dab828939c"}, - {file = "Pillow-9.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:18498994b29e1cf86d505edcb7edbe814d133d2232d256db8c7a8ceb34d18cef"}, - {file = "Pillow-9.3.0-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:772a91fc0e03eaf922c63badeca75e91baa80fe2f5f87bdaed4280662aad25c9"}, - {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:afa4107d1b306cdf8953edde0534562607fe8811b6c4d9a486298ad31de733b2"}, - {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b4012d06c846dc2b80651b120e2cdd787b013deb39c09f407727ba90015c684f"}, - {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:77ec3e7be99629898c9a6d24a09de089fa5356ee408cdffffe62d67bb75fdd72"}, - {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_28_aarch64.whl", hash = "sha256:6c738585d7a9961d8c2821a1eb3dcb978d14e238be3d70f0a706f7fa9316946b"}, - {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_28_x86_64.whl", hash = "sha256:828989c45c245518065a110434246c44a56a8b2b2f6347d1409c787e6e4651ee"}, - {file = "Pillow-9.3.0-cp37-cp37m-win32.whl", hash = "sha256:82409ffe29d70fd733ff3c1025a602abb3e67405d41b9403b00b01debc4c9a29"}, - {file = "Pillow-9.3.0-cp37-cp37m-win_amd64.whl", hash = "sha256:41e0051336807468be450d52b8edd12ac60bebaa97fe10c8b660f116e50b30e4"}, - {file = "Pillow-9.3.0-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:b03ae6f1a1878233ac620c98f3459f79fd77c7e3c2b20d460284e1fb370557d4"}, - {file = "Pillow-9.3.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:4390e9ce199fc1951fcfa65795f239a8a4944117b5935a9317fb320e7767b40f"}, - {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:40e1ce476a7804b0fb74bcfa80b0a2206ea6a882938eaba917f7a0f004b42502"}, - {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a0a06a052c5f37b4ed81c613a455a81f9a3a69429b4fd7bb913c3fa98abefc20"}, - {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:03150abd92771742d4a8cd6f2fa6246d847dcd2e332a18d0c15cc75bf6703040"}, - {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:15c42fb9dea42465dfd902fb0ecf584b8848ceb28b41ee2b58f866411be33f07"}, - {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:51e0e543a33ed92db9f5ef69a0356e0b1a7a6b6a71b80df99f1d181ae5875636"}, - {file = "Pillow-9.3.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:3dd6caf940756101205dffc5367babf288a30043d35f80936f9bfb37f8355b32"}, - {file = "Pillow-9.3.0-cp38-cp38-win32.whl", hash = "sha256:f1ff2ee69f10f13a9596480335f406dd1f70c3650349e2be67ca3139280cade0"}, - {file = "Pillow-9.3.0-cp38-cp38-win_amd64.whl", hash = "sha256:276a5ca930c913f714e372b2591a22c4bd3b81a418c0f6635ba832daec1cbcfc"}, - {file = "Pillow-9.3.0-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:73bd195e43f3fadecfc50c682f5055ec32ee2c933243cafbfdec69ab1aa87cad"}, - {file = "Pillow-9.3.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:1c7c8ae3864846fc95f4611c78129301e203aaa2af813b703c55d10cc1628535"}, - {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2e0918e03aa0c72ea56edbb00d4d664294815aa11291a11504a377ea018330d3"}, - {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b0915e734b33a474d76c28e07292f196cdf2a590a0d25bcc06e64e545f2d146c"}, - {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:af0372acb5d3598f36ec0914deed2a63f6bcdb7b606da04dc19a88d31bf0c05b"}, - {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:ad58d27a5b0262c0c19b47d54c5802db9b34d38bbf886665b626aff83c74bacd"}, - {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:97aabc5c50312afa5e0a2b07c17d4ac5e865b250986f8afe2b02d772567a380c"}, - {file = "Pillow-9.3.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:9aaa107275d8527e9d6e7670b64aabaaa36e5b6bd71a1015ddd21da0d4e06448"}, - {file = "Pillow-9.3.0-cp39-cp39-win32.whl", hash = "sha256:bac18ab8d2d1e6b4ce25e3424f709aceef668347db8637c2296bcf41acb7cf48"}, - {file = "Pillow-9.3.0-cp39-cp39-win_amd64.whl", hash = "sha256:b472b5ea442148d1c3e2209f20f1e0bb0eb556538690fa70b5e1f79fa0ba8dc2"}, - {file = "Pillow-9.3.0-pp37-pypy37_pp73-macosx_10_10_x86_64.whl", hash = "sha256:ab388aaa3f6ce52ac1cb8e122c4bd46657c15905904b3120a6248b5b8b0bc228"}, - {file = "Pillow-9.3.0-pp37-pypy37_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dbb8e7f2abee51cef77673be97760abff1674ed32847ce04b4af90f610144c7b"}, - {file = "Pillow-9.3.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bca31dd6014cb8b0b2db1e46081b0ca7d936f856da3b39744aef499db5d84d02"}, - {file = "Pillow-9.3.0-pp37-pypy37_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:c7025dce65566eb6e89f56c9509d4f628fddcedb131d9465cacd3d8bac337e7e"}, - {file = "Pillow-9.3.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:ebf2029c1f464c59b8bdbe5143c79fa2045a581ac53679733d3a91d400ff9efb"}, - {file = "Pillow-9.3.0-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:b59430236b8e58840a0dfb4099a0e8717ffb779c952426a69ae435ca1f57210c"}, - {file = "Pillow-9.3.0-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:12ce4932caf2ddf3e41d17fc9c02d67126935a44b86df6a206cf0d7161548627"}, - {file = "Pillow-9.3.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ae5331c23ce118c53b172fa64a4c037eb83c9165aba3a7ba9ddd3ec9fa64a699"}, - {file = "Pillow-9.3.0-pp38-pypy38_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:0b07fffc13f474264c336298d1b4ce01d9c5a011415b79d4ee5527bb69ae6f65"}, - {file = "Pillow-9.3.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:073adb2ae23431d3b9bcbcff3fe698b62ed47211d0716b067385538a1b0f28b8"}, - {file = "Pillow-9.3.0.tar.gz", hash = "sha256:c935a22a557a560108d780f9a0fc426dd7459940dc54faa49d83249c8d3e760f"}, -] -platformdirs = [ - {file = "platformdirs-2.5.4-py3-none-any.whl", hash = "sha256:af0276409f9a02373d540bf8480021a048711d572745aef4b7842dad245eba10"}, - {file = "platformdirs-2.5.4.tar.gz", hash = "sha256:1006647646d80f16130f052404c6b901e80ee4ed6bef6792e1f238a8969106f7"}, -] -pluggy = [ - {file = "pluggy-1.0.0-py2.py3-none-any.whl", hash = "sha256:74134bbf457f031a36d68416e1509f34bd5ccc019f0bcc952c7b909d06b37bd3"}, - {file = "pluggy-1.0.0.tar.gz", hash = "sha256:4224373bacce55f955a878bf9cfa763c1e360858e330072059e10bad68531159"}, -] -prometheus-client = [ - {file = "prometheus_client-0.15.0-py3-none-any.whl", hash = "sha256:db7c05cbd13a0f79975592d112320f2605a325969b270a94b71dcabc47b931d2"}, - {file = "prometheus_client-0.15.0.tar.gz", hash = "sha256:be26aa452490cfcf6da953f9436e95a9f2b4d578ca80094b4458930e5f584ab1"}, -] -prompt-toolkit = [ - {file = "prompt_toolkit-3.0.32-py3-none-any.whl", hash = "sha256:24becda58d49ceac4dc26232eb179ef2b21f133fecda7eed6018d341766ed76e"}, - {file = "prompt_toolkit-3.0.32.tar.gz", hash = "sha256:e7f2129cba4ff3b3656bbdda0e74ee00d2f874a8bcdb9dd16f5fec7b3e173cae"}, -] -protobuf = [ - {file = "protobuf-4.21.9-cp310-abi3-win32.whl", hash = "sha256:6e0be9f09bf9b6cf497b27425487706fa48c6d1632ddd94dab1a5fe11a422392"}, - {file = "protobuf-4.21.9-cp310-abi3-win_amd64.whl", hash = "sha256:a7d0ea43949d45b836234f4ebb5ba0b22e7432d065394b532cdca8f98415e3cf"}, - {file = "protobuf-4.21.9-cp37-abi3-macosx_10_9_universal2.whl", hash = "sha256:b5ab0b8918c136345ff045d4b3d5f719b505b7c8af45092d7f45e304f55e50a1"}, - {file = "protobuf-4.21.9-cp37-abi3-manylinux2014_aarch64.whl", hash = "sha256:2c9c2ed7466ad565f18668aa4731c535511c5d9a40c6da39524bccf43e441719"}, - {file = "protobuf-4.21.9-cp37-abi3-manylinux2014_x86_64.whl", hash = "sha256:e575c57dc8b5b2b2caa436c16d44ef6981f2235eb7179bfc847557886376d740"}, - {file = "protobuf-4.21.9-cp37-cp37m-win32.whl", hash = "sha256:9227c14010acd9ae7702d6467b4625b6fe853175a6b150e539b21d2b2f2b409c"}, - {file = "protobuf-4.21.9-cp37-cp37m-win_amd64.whl", hash = "sha256:a419cc95fca8694804709b8c4f2326266d29659b126a93befe210f5bbc772536"}, - {file = "protobuf-4.21.9-cp38-cp38-win32.whl", hash = "sha256:5b0834e61fb38f34ba8840d7dcb2e5a2f03de0c714e0293b3963b79db26de8ce"}, - {file = "protobuf-4.21.9-cp38-cp38-win_amd64.whl", hash = "sha256:84ea107016244dfc1eecae7684f7ce13c788b9a644cd3fca5b77871366556444"}, - {file = "protobuf-4.21.9-cp39-cp39-win32.whl", hash = "sha256:f9eae277dd240ae19bb06ff4e2346e771252b0e619421965504bd1b1bba7c5fa"}, - {file = "protobuf-4.21.9-cp39-cp39-win_amd64.whl", hash = "sha256:6e312e280fbe3c74ea9e080d9e6080b636798b5e3939242298b591064470b06b"}, - {file = "protobuf-4.21.9-py2.py3-none-any.whl", hash = "sha256:7eb8f2cc41a34e9c956c256e3ac766cf4e1a4c9c925dc757a41a01be3e852965"}, - {file = "protobuf-4.21.9-py3-none-any.whl", hash = "sha256:48e2cd6b88c6ed3d5877a3ea40df79d08374088e89bedc32557348848dff250b"}, - {file = "protobuf-4.21.9.tar.gz", hash = "sha256:61f21493d96d2a77f9ca84fefa105872550ab5ef71d21c458eb80edcf4885a99"}, -] -psutil = [ - {file = "psutil-5.9.4-cp27-cp27m-macosx_10_9_x86_64.whl", hash = "sha256:c1ca331af862803a42677c120aff8a814a804e09832f166f226bfd22b56feee8"}, - {file = "psutil-5.9.4-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:68908971daf802203f3d37e78d3f8831b6d1014864d7a85937941bb35f09aefe"}, - {file = "psutil-5.9.4-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:3ff89f9b835100a825b14c2808a106b6fdcc4b15483141482a12c725e7f78549"}, - {file = "psutil-5.9.4-cp27-cp27m-win32.whl", hash = "sha256:852dd5d9f8a47169fe62fd4a971aa07859476c2ba22c2254d4a1baa4e10b95ad"}, - {file = "psutil-5.9.4-cp27-cp27m-win_amd64.whl", hash = "sha256:9120cd39dca5c5e1c54b59a41d205023d436799b1c8c4d3ff71af18535728e94"}, - {file = "psutil-5.9.4-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:6b92c532979bafc2df23ddc785ed116fced1f492ad90a6830cf24f4d1ea27d24"}, - {file = "psutil-5.9.4-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:efeae04f9516907be44904cc7ce08defb6b665128992a56957abc9b61dca94b7"}, - {file = "psutil-5.9.4-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:54d5b184728298f2ca8567bf83c422b706200bcbbfafdc06718264f9393cfeb7"}, - {file = "psutil-5.9.4-cp36-abi3-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:16653106f3b59386ffe10e0bad3bb6299e169d5327d3f187614b1cb8f24cf2e1"}, - {file = "psutil-5.9.4-cp36-abi3-manylinux_2_12_x86_64.manylinux2010_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:54c0d3d8e0078b7666984e11b12b88af2db11d11249a8ac8920dd5ef68a66e08"}, - {file = "psutil-5.9.4-cp36-abi3-win32.whl", hash = "sha256:149555f59a69b33f056ba1c4eb22bb7bf24332ce631c44a319cec09f876aaeff"}, - {file = "psutil-5.9.4-cp36-abi3-win_amd64.whl", hash = "sha256:fd8522436a6ada7b4aad6638662966de0d61d241cb821239b2ae7013d41a43d4"}, - {file = "psutil-5.9.4-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:6001c809253a29599bc0dfd5179d9f8a5779f9dffea1da0f13c53ee568115e1e"}, - {file = "psutil-5.9.4.tar.gz", hash = "sha256:3d7f9739eb435d4b1338944abe23f49584bde5395f27487d2ee25ad9a8774a62"}, -] -ptyprocess = [ - {file = "ptyprocess-0.7.0-py2.py3-none-any.whl", hash = "sha256:4b41f3967fce3af57cc7e94b888626c18bf37a083e3651ca8feeb66d492fef35"}, - {file = "ptyprocess-0.7.0.tar.gz", hash = "sha256:5c5d0a3b48ceee0b48485e0c26037c0acd7d29765ca3fbb5cb3831d347423220"}, -] -pure-eval = [ - {file = "pure_eval-0.2.2-py3-none-any.whl", hash = "sha256:01eaab343580944bc56080ebe0a674b39ec44a945e6d09ba7db3cb8cec289350"}, - {file = "pure_eval-0.2.2.tar.gz", hash = "sha256:2b45320af6dfaa1750f543d714b6d1c520a1688dec6fd24d339063ce0aaa9ac3"}, -] -py = [ - {file = "py-1.11.0-py2.py3-none-any.whl", hash = "sha256:607c53218732647dff4acdfcd50cb62615cedf612e72d1724fb1a0cc6405b378"}, - {file = "py-1.11.0.tar.gz", hash = "sha256:51c75c4126074b472f746a24399ad32f6053d1b34b68d2fa41e558e6f4a98719"}, -] -pycparser = [ - {file = "pycparser-2.21-py2.py3-none-any.whl", hash = "sha256:8ee45429555515e1f6b185e78100aea234072576aa43ab53aefcae078162fca9"}, - {file = "pycparser-2.21.tar.gz", hash = "sha256:e644fdec12f7872f86c58ff790da456218b10f863970249516d60a5eaca77206"}, -] -pydot = [ - {file = "pydot-1.4.2-py2.py3-none-any.whl", hash = "sha256:66c98190c65b8d2e2382a441b4c0edfdb4f4c025ef9cb9874de478fb0793a451"}, - {file = "pydot-1.4.2.tar.gz", hash = "sha256:248081a39bcb56784deb018977e428605c1c758f10897a339fce1dd728ff007d"}, -] -pygments = [ - {file = "Pygments-2.13.0-py3-none-any.whl", hash = "sha256:f643f331ab57ba3c9d89212ee4a2dabc6e94f117cf4eefde99a0574720d14c42"}, - {file = "Pygments-2.13.0.tar.gz", hash = "sha256:56a8508ae95f98e2b9bdf93a6be5ae3f7d8af858b43e02c5a2ff083726be40c1"}, -] -pyngrok = [ - {file = "pyngrok-5.1.0.tar.gz", hash = "sha256:4d03f44a69c3cbc168b17377956a9edcf723e77dbc864eba34c272db15da443c"}, -] -pyparsing = [ - {file = "pyparsing-3.0.9-py3-none-any.whl", hash = "sha256:5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc"}, - {file = "pyparsing-3.0.9.tar.gz", hash = "sha256:2b020ecf7d21b687f219b71ecad3631f644a47f01403fa1d1036b0c6416d70fb"}, -] -pyrsistent = [ - {file = "pyrsistent-0.19.2-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:d6982b5a0237e1b7d876b60265564648a69b14017f3b5f908c5be2de3f9abb7a"}, - {file = "pyrsistent-0.19.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:187d5730b0507d9285a96fca9716310d572e5464cadd19f22b63a6976254d77a"}, - {file = "pyrsistent-0.19.2-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:055ab45d5911d7cae397dc418808d8802fb95262751872c841c170b0dbf51eed"}, - {file = "pyrsistent-0.19.2-cp310-cp310-win32.whl", hash = "sha256:456cb30ca8bff00596519f2c53e42c245c09e1a4543945703acd4312949bfd41"}, - {file = "pyrsistent-0.19.2-cp310-cp310-win_amd64.whl", hash = "sha256:b39725209e06759217d1ac5fcdb510e98670af9e37223985f330b611f62e7425"}, - {file = "pyrsistent-0.19.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:2aede922a488861de0ad00c7630a6e2d57e8023e4be72d9d7147a9fcd2d30712"}, - {file = "pyrsistent-0.19.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:879b4c2f4d41585c42df4d7654ddffff1239dc4065bc88b745f0341828b83e78"}, - {file = "pyrsistent-0.19.2-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c43bec251bbd10e3cb58ced80609c5c1eb238da9ca78b964aea410fb820d00d6"}, - {file = "pyrsistent-0.19.2-cp37-cp37m-win32.whl", hash = "sha256:d690b18ac4b3e3cab73b0b7aa7dbe65978a172ff94970ff98d82f2031f8971c2"}, - {file = "pyrsistent-0.19.2-cp37-cp37m-win_amd64.whl", hash = "sha256:3ba4134a3ff0fc7ad225b6b457d1309f4698108fb6b35532d015dca8f5abed73"}, - {file = "pyrsistent-0.19.2-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:a178209e2df710e3f142cbd05313ba0c5ebed0a55d78d9945ac7a4e09d923308"}, - {file = "pyrsistent-0.19.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e371b844cec09d8dc424d940e54bba8f67a03ebea20ff7b7b0d56f526c71d584"}, - {file = "pyrsistent-0.19.2-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:111156137b2e71f3a9936baf27cb322e8024dac3dc54ec7fb9f0bcf3249e68bb"}, - {file = "pyrsistent-0.19.2-cp38-cp38-win32.whl", hash = "sha256:e5d8f84d81e3729c3b506657dddfe46e8ba9c330bf1858ee33108f8bb2adb38a"}, - {file = "pyrsistent-0.19.2-cp38-cp38-win_amd64.whl", hash = "sha256:9cd3e9978d12b5d99cbdc727a3022da0430ad007dacf33d0bf554b96427f33ab"}, - {file = "pyrsistent-0.19.2-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:f1258f4e6c42ad0b20f9cfcc3ada5bd6b83374516cd01c0960e3cb75fdca6770"}, - {file = "pyrsistent-0.19.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:21455e2b16000440e896ab99e8304617151981ed40c29e9507ef1c2e4314ee95"}, - {file = "pyrsistent-0.19.2-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bfd880614c6237243ff53a0539f1cb26987a6dc8ac6e66e0c5a40617296a045e"}, - {file = "pyrsistent-0.19.2-cp39-cp39-win32.whl", hash = "sha256:71d332b0320642b3261e9fee47ab9e65872c2bd90260e5d225dabeed93cbd42b"}, - {file = "pyrsistent-0.19.2-cp39-cp39-win_amd64.whl", hash = "sha256:dec3eac7549869365fe263831f576c8457f6c833937c68542d08fde73457d291"}, - {file = "pyrsistent-0.19.2-py3-none-any.whl", hash = "sha256:ea6b79a02a28550c98b6ca9c35b9f492beaa54d7c5c9e9949555893c8a9234d0"}, - {file = "pyrsistent-0.19.2.tar.gz", hash = "sha256:bfa0351be89c9fcbcb8c9879b826f4353be10f58f8a677efab0c017bf7137ec2"}, -] -pyserial = [ - {file = "pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0"}, - {file = "pyserial-3.5.tar.gz", hash = "sha256:3c77e014170dfffbd816e6ffc205e9842efb10be9f58ec16d3e8675b4925cddb"}, -] -pytest = [ - {file = "pytest-7.2.0-py3-none-any.whl", hash = "sha256:892f933d339f068883b6fd5a459f03d85bfcb355e4981e146d2c7616c21fef71"}, - {file = "pytest-7.2.0.tar.gz", hash = "sha256:c4014eb40e10f11f355ad4e3c2fb2c6c6d1919c73f3b5a433de4708202cade59"}, -] -python-dateutil = [ - {file = "python-dateutil-2.8.2.tar.gz", hash = "sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86"}, - {file = "python_dateutil-2.8.2-py2.py3-none-any.whl", hash = "sha256:961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9"}, -] -pytz = [ - {file = "pytz-2022.6-py2.py3-none-any.whl", hash = "sha256:222439474e9c98fced559f1709d89e6c9cbf8d79c794ff3eb9f8800064291427"}, - {file = "pytz-2022.6.tar.gz", hash = "sha256:e89512406b793ca39f5971bc999cc538ce125c0e51c27941bef4568b460095e2"}, -] -pywin32 = [ - {file = "pywin32-305-cp310-cp310-win32.whl", hash = "sha256:421f6cd86e84bbb696d54563c48014b12a23ef95a14e0bdba526be756d89f116"}, - {file = "pywin32-305-cp310-cp310-win_amd64.whl", hash = "sha256:73e819c6bed89f44ff1d690498c0a811948f73777e5f97c494c152b850fad478"}, - {file = "pywin32-305-cp310-cp310-win_arm64.whl", hash = "sha256:742eb905ce2187133a29365b428e6c3b9001d79accdc30aa8969afba1d8470f4"}, - {file = "pywin32-305-cp311-cp311-win32.whl", hash = "sha256:19ca459cd2e66c0e2cc9a09d589f71d827f26d47fe4a9d09175f6aa0256b51c2"}, - {file = "pywin32-305-cp311-cp311-win_amd64.whl", hash = "sha256:326f42ab4cfff56e77e3e595aeaf6c216712bbdd91e464d167c6434b28d65990"}, - {file = "pywin32-305-cp311-cp311-win_arm64.whl", hash = "sha256:4ecd404b2c6eceaca52f8b2e3e91b2187850a1ad3f8b746d0796a98b4cea04db"}, - {file = "pywin32-305-cp36-cp36m-win32.whl", hash = "sha256:48d8b1659284f3c17b68587af047d110d8c44837736b8932c034091683e05863"}, - {file = "pywin32-305-cp36-cp36m-win_amd64.whl", hash = "sha256:13362cc5aa93c2beaf489c9c9017c793722aeb56d3e5166dadd5ef82da021fe1"}, - {file = "pywin32-305-cp37-cp37m-win32.whl", hash = "sha256:a55db448124d1c1484df22fa8bbcbc45c64da5e6eae74ab095b9ea62e6d00496"}, - {file = "pywin32-305-cp37-cp37m-win_amd64.whl", hash = "sha256:109f98980bfb27e78f4df8a51a8198e10b0f347257d1e265bb1a32993d0c973d"}, - {file = "pywin32-305-cp38-cp38-win32.whl", hash = "sha256:9dd98384da775afa009bc04863426cb30596fd78c6f8e4e2e5bbf4edf8029504"}, - {file = "pywin32-305-cp38-cp38-win_amd64.whl", hash = "sha256:56d7a9c6e1a6835f521788f53b5af7912090674bb84ef5611663ee1595860fc7"}, - {file = "pywin32-305-cp39-cp39-win32.whl", hash = "sha256:9d968c677ac4d5cbdaa62fd3014ab241718e619d8e36ef8e11fb930515a1e918"}, - {file = "pywin32-305-cp39-cp39-win_amd64.whl", hash = "sha256:50768c6b7c3f0b38b7fb14dd4104da93ebced5f1a50dc0e834594bff6fbe1271"}, -] -pywinpty = [ - {file = "pywinpty-2.0.9-cp310-none-win_amd64.whl", hash = "sha256:30a7b371446a694a6ce5ef906d70ac04e569de5308c42a2bdc9c3bc9275ec51f"}, - {file = "pywinpty-2.0.9-cp311-none-win_amd64.whl", hash = "sha256:d78ef6f4bd7a6c6f94dc1a39ba8fb028540cc39f5cb593e756506db17843125f"}, - {file = "pywinpty-2.0.9-cp37-none-win_amd64.whl", hash = "sha256:5ed36aa087e35a3a183f833631b3e4c1ae92fe2faabfce0fa91b77ed3f0f1382"}, - {file = "pywinpty-2.0.9-cp38-none-win_amd64.whl", hash = "sha256:2352f44ee913faaec0a02d3c112595e56b8af7feeb8100efc6dc1a8685044199"}, - {file = "pywinpty-2.0.9-cp39-none-win_amd64.whl", hash = "sha256:ba75ec55f46c9e17db961d26485b033deb20758b1731e8e208e1e8a387fcf70c"}, - {file = "pywinpty-2.0.9.tar.gz", hash = "sha256:01b6400dd79212f50a2f01af1c65b781290ff39610853db99bf03962eb9a615f"}, -] -pyyaml = [ - {file = "PyYAML-6.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:d4db7c7aef085872ef65a8fd7d6d09a14ae91f691dec3e87ee5ee0539d516f53"}, - {file = "PyYAML-6.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:9df7ed3b3d2e0ecfe09e14741b857df43adb5a3ddadc919a2d94fbdf78fea53c"}, - {file = "PyYAML-6.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:77f396e6ef4c73fdc33a9157446466f1cff553d979bd00ecb64385760c6babdc"}, - {file = "PyYAML-6.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a80a78046a72361de73f8f395f1f1e49f956c6be882eed58505a15f3e430962b"}, - {file = "PyYAML-6.0-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:f84fbc98b019fef2ee9a1cb3ce93e3187a6df0b2538a651bfb890254ba9f90b5"}, - {file = "PyYAML-6.0-cp310-cp310-win32.whl", hash = "sha256:2cd5df3de48857ed0544b34e2d40e9fac445930039f3cfe4bcc592a1f836d513"}, - {file = "PyYAML-6.0-cp310-cp310-win_amd64.whl", hash = "sha256:daf496c58a8c52083df09b80c860005194014c3698698d1a57cbcfa182142a3a"}, - {file = "PyYAML-6.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:d4b0ba9512519522b118090257be113b9468d804b19d63c71dbcf4a48fa32358"}, - {file = "PyYAML-6.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:81957921f441d50af23654aa6c5e5eaf9b06aba7f0a19c18a538dc7ef291c5a1"}, - {file = "PyYAML-6.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:afa17f5bc4d1b10afd4466fd3a44dc0e245382deca5b3c353d8b757f9e3ecb8d"}, - {file = "PyYAML-6.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:dbad0e9d368bb989f4515da330b88a057617d16b6a8245084f1b05400f24609f"}, - {file = "PyYAML-6.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:432557aa2c09802be39460360ddffd48156e30721f5e8d917f01d31694216782"}, - {file = "PyYAML-6.0-cp311-cp311-win32.whl", hash = "sha256:bfaef573a63ba8923503d27530362590ff4f576c626d86a9fed95822a8255fd7"}, - {file = "PyYAML-6.0-cp311-cp311-win_amd64.whl", hash = "sha256:01b45c0191e6d66c470b6cf1b9531a771a83c1c4208272ead47a3ae4f2f603bf"}, - {file = "PyYAML-6.0-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:897b80890765f037df3403d22bab41627ca8811ae55e9a722fd0392850ec4d86"}, - {file = "PyYAML-6.0-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:50602afada6d6cbfad699b0c7bb50d5ccffa7e46a3d738092afddc1f9758427f"}, - {file = "PyYAML-6.0-cp36-cp36m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:48c346915c114f5fdb3ead70312bd042a953a8ce5c7106d5bfb1a5254e47da92"}, - {file = "PyYAML-6.0-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:98c4d36e99714e55cfbaaee6dd5badbc9a1ec339ebfc3b1f52e293aee6bb71a4"}, - {file = "PyYAML-6.0-cp36-cp36m-win32.whl", hash = "sha256:0283c35a6a9fbf047493e3a0ce8d79ef5030852c51e9d911a27badfde0605293"}, - {file = "PyYAML-6.0-cp36-cp36m-win_amd64.whl", hash = "sha256:07751360502caac1c067a8132d150cf3d61339af5691fe9e87803040dbc5db57"}, - {file = "PyYAML-6.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:819b3830a1543db06c4d4b865e70ded25be52a2e0631ccd2f6a47a2822f2fd7c"}, - {file = "PyYAML-6.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:473f9edb243cb1935ab5a084eb238d842fb8f404ed2193a915d1784b5a6b5fc0"}, - {file = "PyYAML-6.0-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0ce82d761c532fe4ec3f87fc45688bdd3a4c1dc5e0b4a19814b9009a29baefd4"}, - {file = "PyYAML-6.0-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:231710d57adfd809ef5d34183b8ed1eeae3f76459c18fb4a0b373ad56bedcdd9"}, - {file = "PyYAML-6.0-cp37-cp37m-win32.whl", hash = "sha256:c5687b8d43cf58545ade1fe3e055f70eac7a5a1a0bf42824308d868289a95737"}, - {file = "PyYAML-6.0-cp37-cp37m-win_amd64.whl", hash = "sha256:d15a181d1ecd0d4270dc32edb46f7cb7733c7c508857278d3d378d14d606db2d"}, - {file = "PyYAML-6.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:0b4624f379dab24d3725ffde76559cff63d9ec94e1736b556dacdfebe5ab6d4b"}, - {file = "PyYAML-6.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:213c60cd50106436cc818accf5baa1aba61c0189ff610f64f4a3e8c6726218ba"}, - {file = "PyYAML-6.0-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9fa600030013c4de8165339db93d182b9431076eb98eb40ee068700c9c813e34"}, - {file = "PyYAML-6.0-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:277a0ef2981ca40581a47093e9e2d13b3f1fbbeffae064c1d21bfceba2030287"}, - {file = "PyYAML-6.0-cp38-cp38-win32.whl", hash = "sha256:d4eccecf9adf6fbcc6861a38015c2a64f38b9d94838ac1810a9023a0609e1b78"}, - {file = "PyYAML-6.0-cp38-cp38-win_amd64.whl", hash = "sha256:1e4747bc279b4f613a09eb64bba2ba602d8a6664c6ce6396a4d0cd413a50ce07"}, - {file = "PyYAML-6.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:055d937d65826939cb044fc8c9b08889e8c743fdc6a32b33e2390f66013e449b"}, - {file = "PyYAML-6.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e61ceaab6f49fb8bdfaa0f92c4b57bcfbea54c09277b1b4f7ac376bfb7a7c174"}, - {file = "PyYAML-6.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d67d839ede4ed1b28a4e8909735fc992a923cdb84e618544973d7dfc71540803"}, - {file = "PyYAML-6.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:cba8c411ef271aa037d7357a2bc8f9ee8b58b9965831d9e51baf703280dc73d3"}, - {file = "PyYAML-6.0-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:40527857252b61eacd1d9af500c3337ba8deb8fc298940291486c465c8b46ec0"}, - {file = "PyYAML-6.0-cp39-cp39-win32.whl", hash = "sha256:b5b9eccad747aabaaffbc6064800670f0c297e52c12754eb1d976c57e4f74dcb"}, - {file = "PyYAML-6.0-cp39-cp39-win_amd64.whl", hash = "sha256:b3d267842bf12586ba6c734f89d1f5b871df0273157918b0ccefa29deb05c21c"}, - {file = "PyYAML-6.0.tar.gz", hash = "sha256:68fb519c14306fec9720a2a5b45bc9f0c8d1b9c72adf45c37baedfcd949c35a2"}, -] -pyzmq = [ - {file = "pyzmq-24.0.1-cp310-cp310-macosx_10_15_universal2.whl", hash = "sha256:28b119ba97129d3001673a697b7cce47fe6de1f7255d104c2f01108a5179a066"}, - {file = "pyzmq-24.0.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:bcbebd369493d68162cddb74a9c1fcebd139dfbb7ddb23d8f8e43e6c87bac3a6"}, - {file = "pyzmq-24.0.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ae61446166983c663cee42c852ed63899e43e484abf080089f771df4b9d272ef"}, - {file = "pyzmq-24.0.1-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:87f7ac99b15270db8d53f28c3c7b968612993a90a5cf359da354efe96f5372b4"}, - {file = "pyzmq-24.0.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9dca7c3956b03b7663fac4d150f5e6d4f6f38b2462c1e9afd83bcf7019f17913"}, - {file = "pyzmq-24.0.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:8c78bfe20d4c890cb5580a3b9290f700c570e167d4cdcc55feec07030297a5e3"}, - {file = "pyzmq-24.0.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:48f721f070726cd2a6e44f3c33f8ee4b24188e4b816e6dd8ba542c8c3bb5b246"}, - {file = "pyzmq-24.0.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:afe1f3bc486d0ce40abb0a0c9adb39aed3bbac36ebdc596487b0cceba55c21c1"}, - {file = "pyzmq-24.0.1-cp310-cp310-win32.whl", hash = "sha256:3e6192dbcefaaa52ed81be88525a54a445f4b4fe2fffcae7fe40ebb58bd06bfd"}, - {file = "pyzmq-24.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:86de64468cad9c6d269f32a6390e210ca5ada568c7a55de8e681ca3b897bb340"}, - {file = "pyzmq-24.0.1-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:838812c65ed5f7c2bd11f7b098d2e5d01685a3f6d1f82849423b570bae698c00"}, - {file = "pyzmq-24.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:dfb992dbcd88d8254471760879d48fb20836d91baa90f181c957122f9592b3dc"}, - {file = "pyzmq-24.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7abddb2bd5489d30ffeb4b93a428130886c171b4d355ccd226e83254fcb6b9ef"}, - {file = "pyzmq-24.0.1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:94010bd61bc168c103a5b3b0f56ed3b616688192db7cd5b1d626e49f28ff51b3"}, - {file = "pyzmq-24.0.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:8242543c522d84d033fe79be04cb559b80d7eb98ad81b137ff7e0a9020f00ace"}, - {file = "pyzmq-24.0.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ccb94342d13e3bf3ffa6e62f95b5e3f0bc6bfa94558cb37f4b3d09d6feb536ff"}, - {file = "pyzmq-24.0.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:6640f83df0ae4ae1104d4c62b77e9ef39be85ebe53f636388707d532bee2b7b8"}, - {file = "pyzmq-24.0.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:a180dbd5ea5d47c2d3b716d5c19cc3fb162d1c8db93b21a1295d69585bfddac1"}, - {file = "pyzmq-24.0.1-cp311-cp311-win32.whl", hash = "sha256:624321120f7e60336be8ec74a172ae7fba5c3ed5bf787cc85f7e9986c9e0ebc2"}, - {file = "pyzmq-24.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:1724117bae69e091309ffb8255412c4651d3f6355560d9af312d547f6c5bc8b8"}, - {file = "pyzmq-24.0.1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:15975747462ec49fdc863af906bab87c43b2491403ab37a6d88410635786b0f4"}, - {file = "pyzmq-24.0.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b947e264f0e77d30dcbccbb00f49f900b204b922eb0c3a9f0afd61aaa1cedc3d"}, - {file = "pyzmq-24.0.1-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:0ec91f1bad66f3ee8c6deb65fa1fe418e8ad803efedd69c35f3b5502f43bd1dc"}, - {file = "pyzmq-24.0.1-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:db03704b3506455d86ec72c3358a779e9b1d07b61220dfb43702b7b668edcd0d"}, - {file = "pyzmq-24.0.1-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:e7e66b4e403c2836ac74f26c4b65d8ac0ca1eef41dfcac2d013b7482befaad83"}, - {file = "pyzmq-24.0.1-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:7a23ccc1083c260fa9685c93e3b170baba45aeed4b524deb3f426b0c40c11639"}, - {file = "pyzmq-24.0.1-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:fa0ae3275ef706c0309556061185dd0e4c4cd3b7d6f67ae617e4e677c7a41e2e"}, - {file = "pyzmq-24.0.1-cp36-cp36m-win32.whl", hash = "sha256:f01de4ec083daebf210531e2cca3bdb1608dbbbe00a9723e261d92087a1f6ebc"}, - {file = "pyzmq-24.0.1-cp36-cp36m-win_amd64.whl", hash = "sha256:de4217b9eb8b541cf2b7fde4401ce9d9a411cc0af85d410f9d6f4333f43640be"}, - {file = "pyzmq-24.0.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:78068e8678ca023594e4a0ab558905c1033b2d3e806a0ad9e3094e231e115a33"}, - {file = "pyzmq-24.0.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:77c2713faf25a953c69cf0f723d1b7dd83827b0834e6c41e3fb3bbc6765914a1"}, - {file = "pyzmq-24.0.1-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:8bb4af15f305056e95ca1bd086239b9ebc6ad55e9f49076d27d80027f72752f6"}, - {file = "pyzmq-24.0.1-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:0f14cffd32e9c4c73da66db97853a6aeceaac34acdc0fae9e5bbc9370281864c"}, - {file = "pyzmq-24.0.1-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:0108358dab8c6b27ff6b985c2af4b12665c1bc659648284153ee501000f5c107"}, - {file = "pyzmq-24.0.1-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:d66689e840e75221b0b290b0befa86f059fb35e1ee6443bce51516d4d61b6b99"}, - {file = "pyzmq-24.0.1-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:ae08ac90aa8fa14caafc7a6251bd218bf6dac518b7bff09caaa5e781119ba3f2"}, - {file = "pyzmq-24.0.1-cp37-cp37m-win32.whl", hash = "sha256:8421aa8c9b45ea608c205db9e1c0c855c7e54d0e9c2c2f337ce024f6843cab3b"}, - {file = "pyzmq-24.0.1-cp37-cp37m-win_amd64.whl", hash = "sha256:54d8b9c5e288362ec8595c1d98666d36f2070fd0c2f76e2b3c60fbad9bd76227"}, - {file = "pyzmq-24.0.1-cp38-cp38-macosx_10_15_universal2.whl", hash = "sha256:acbd0a6d61cc954b9f535daaa9ec26b0a60a0d4353c5f7c1438ebc88a359a47e"}, - {file = "pyzmq-24.0.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:47b11a729d61a47df56346283a4a800fa379ae6a85870d5a2e1e4956c828eedc"}, - {file = "pyzmq-24.0.1-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:abe6eb10122f0d746a0d510c2039ae8edb27bc9af29f6d1b05a66cc2401353ff"}, - {file = "pyzmq-24.0.1-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:07bec1a1b22dacf718f2c0e71b49600bb6a31a88f06527dfd0b5aababe3fa3f7"}, - {file = "pyzmq-24.0.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f0d945a85b70da97ae86113faf9f1b9294efe66bd4a5d6f82f2676d567338b66"}, - {file = "pyzmq-24.0.1-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:1b7928bb7580736ffac5baf814097be342ba08d3cfdfb48e52773ec959572287"}, - {file = "pyzmq-24.0.1-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:b946da90dc2799bcafa682692c1d2139b2a96ec3c24fa9fc6f5b0da782675330"}, - {file = "pyzmq-24.0.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:c8840f064b1fb377cffd3efeaad2b190c14d4c8da02316dae07571252d20b31f"}, - {file = "pyzmq-24.0.1-cp38-cp38-win32.whl", hash = "sha256:4854f9edc5208f63f0841c0c667260ae8d6846cfa233c479e29fdc85d42ebd58"}, - {file = "pyzmq-24.0.1-cp38-cp38-win_amd64.whl", hash = "sha256:42d4f97b9795a7aafa152a36fe2ad44549b83a743fd3e77011136def512e6c2a"}, - {file = "pyzmq-24.0.1-cp39-cp39-macosx_10_15_universal2.whl", hash = "sha256:52afb0ac962963fff30cf1be775bc51ae083ef4c1e354266ab20e5382057dd62"}, - {file = "pyzmq-24.0.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:8bad8210ad4df68c44ff3685cca3cda448ee46e20d13edcff8909eba6ec01ca4"}, - {file = "pyzmq-24.0.1-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:dabf1a05318d95b1537fd61d9330ef4313ea1216eea128a17615038859da3b3b"}, - {file = "pyzmq-24.0.1-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:5bd3d7dfd9cd058eb68d9a905dec854f86649f64d4ddf21f3ec289341386c44b"}, - {file = "pyzmq-24.0.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e8012bce6836d3f20a6c9599f81dfa945f433dab4dbd0c4917a6fb1f998ab33d"}, - {file = "pyzmq-24.0.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:c31805d2c8ade9b11feca4674eee2b9cce1fec3e8ddb7bbdd961a09dc76a80ea"}, - {file = "pyzmq-24.0.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:3104f4b084ad5d9c0cb87445cc8cfd96bba710bef4a66c2674910127044df209"}, - {file = "pyzmq-24.0.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:df0841f94928f8af9c7a1f0aaaffba1fb74607af023a152f59379c01c53aee58"}, - {file = "pyzmq-24.0.1-cp39-cp39-win32.whl", hash = "sha256:a435ef8a3bd95c8a2d316d6e0ff70d0db524f6037411652803e118871d703333"}, - {file = "pyzmq-24.0.1-cp39-cp39-win_amd64.whl", hash = "sha256:2032d9cb994ce3b4cba2b8dfae08c7e25bc14ba484c770d4d3be33c27de8c45b"}, - {file = "pyzmq-24.0.1-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:bb5635c851eef3a7a54becde6da99485eecf7d068bd885ac8e6d173c4ecd68b0"}, - {file = "pyzmq-24.0.1-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:83ea1a398f192957cb986d9206ce229efe0ee75e3c6635baff53ddf39bd718d5"}, - {file = "pyzmq-24.0.1-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:941fab0073f0a54dc33d1a0460cb04e0d85893cb0c5e1476c785000f8b359409"}, - {file = "pyzmq-24.0.1-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0e8f482c44ccb5884bf3f638f29bea0f8dc68c97e38b2061769c4cb697f6140d"}, - {file = "pyzmq-24.0.1-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:613010b5d17906c4367609e6f52e9a2595e35d5cc27d36ff3f1b6fa6e954d944"}, - {file = "pyzmq-24.0.1-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:65c94410b5a8355cfcf12fd600a313efee46ce96a09e911ea92cf2acf6708804"}, - {file = "pyzmq-24.0.1-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:20e7eeb1166087db636c06cae04a1ef59298627f56fb17da10528ab52a14c87f"}, - {file = "pyzmq-24.0.1-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:a2712aee7b3834ace51738c15d9ee152cc5a98dc7d57dd93300461b792ab7b43"}, - {file = "pyzmq-24.0.1-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1a7c280185c4da99e0cc06c63bdf91f5b0b71deb70d8717f0ab870a43e376db8"}, - {file = "pyzmq-24.0.1-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:858375573c9225cc8e5b49bfac846a77b696b8d5e815711b8d4ba3141e6e8879"}, - {file = "pyzmq-24.0.1-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:80093b595921eed1a2cead546a683b9e2ae7f4a4592bb2ab22f70d30174f003a"}, - {file = "pyzmq-24.0.1-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8f3f3154fde2b1ff3aa7b4f9326347ebc89c8ef425ca1db8f665175e6d3bd42f"}, - {file = "pyzmq-24.0.1-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:abb756147314430bee5d10919b8493c0ccb109ddb7f5dfd2fcd7441266a25b75"}, - {file = "pyzmq-24.0.1-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:44e706bac34e9f50779cb8c39f10b53a4d15aebb97235643d3112ac20bd577b4"}, - {file = "pyzmq-24.0.1-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:687700f8371643916a1d2c61f3fdaa630407dd205c38afff936545d7b7466066"}, - {file = "pyzmq-24.0.1.tar.gz", hash = "sha256:216f5d7dbb67166759e59b0479bca82b8acf9bed6015b526b8eb10143fb08e77"}, -] -qtconsole = [ - {file = "qtconsole-5.4.0-py3-none-any.whl", hash = "sha256:be13560c19bdb3b54ed9741a915aa701a68d424519e8341ac479a91209e694b2"}, - {file = "qtconsole-5.4.0.tar.gz", hash = "sha256:57748ea2fd26320a0b77adba20131cfbb13818c7c96d83fafcb110ff55f58b35"}, -] -qtpy = [ - {file = "QtPy-2.3.0-py3-none-any.whl", hash = "sha256:8d6d544fc20facd27360ea189592e6135c614785f0dec0b4f083289de6beb408"}, - {file = "QtPy-2.3.0.tar.gz", hash = "sha256:0603c9c83ccc035a4717a12908bf6bc6cb22509827ea2ec0e94c2da7c9ed57c5"}, -] -seaborn = [ - {file = "seaborn-0.12.1-py3-none-any.whl", hash = "sha256:a9eb39cba095fcb1e4c89a7fab1c57137d70a715a7f2eefcd41c9913c4d4ed65"}, - {file = "seaborn-0.12.1.tar.gz", hash = "sha256:bb1eb1d51d3097368c187c3ef089c0288ec1fe8aa1c69fb324c68aa1d02df4c1"}, -] -send2trash = [ - {file = "Send2Trash-1.8.0-py3-none-any.whl", hash = "sha256:f20eaadfdb517eaca5ce077640cb261c7d2698385a6a0f072a4a5447fd49fa08"}, - {file = "Send2Trash-1.8.0.tar.gz", hash = "sha256:d2c24762fd3759860a0aff155e45871447ea58d2be6bdd39b5c8f966a0c99c2d"}, -] -setuptools = [ - {file = "setuptools-65.6.0-py3-none-any.whl", hash = "sha256:6211d2f5eddad8757bd0484923ca7c0a6302ebc4ab32ea5e94357176e0ca0840"}, - {file = "setuptools-65.6.0.tar.gz", hash = "sha256:d1eebf881c6114e51df1664bc2c9133d022f78d12d5f4f665b9191f084e2862d"}, -] -setuptools-scm = [ - {file = "setuptools_scm-7.0.5-py3-none-any.whl", hash = "sha256:7930f720905e03ccd1e1d821db521bff7ec2ac9cf0ceb6552dd73d24a45d3b02"}, - {file = "setuptools_scm-7.0.5.tar.gz", hash = "sha256:031e13af771d6f892b941adb6ea04545bbf91ebc5ce68c78aaf3fff6e1fb4844"}, -] -six = [ - {file = "six-1.16.0-py2.py3-none-any.whl", hash = "sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254"}, - {file = "six-1.16.0.tar.gz", hash = "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926"}, -] -sniffio = [ - {file = "sniffio-1.3.0-py3-none-any.whl", hash = "sha256:eecefdce1e5bbfb7ad2eeaabf7c1eeb404d7757c379bd1f7e5cce9d8bf425384"}, - {file = "sniffio-1.3.0.tar.gz", hash = "sha256:e60305c5e5d314f5389259b7f22aaa33d8f7dee49763119234af3755c55b9101"}, -] -soupsieve = [ - {file = "soupsieve-2.3.2.post1-py3-none-any.whl", hash = "sha256:3b2503d3c7084a42b1ebd08116e5f81aadfaea95863628c80a3b774a11b7c759"}, - {file = "soupsieve-2.3.2.post1.tar.gz", hash = "sha256:fc53893b3da2c33de295667a0e19f078c14bf86544af307354de5fcf12a3f30d"}, -] -stack-data = [ - {file = "stack_data-0.6.1-py3-none-any.whl", hash = "sha256:960cb054d6a1b2fdd9cbd529e365b3c163e8dabf1272e02cfe36b58403cff5c6"}, - {file = "stack_data-0.6.1.tar.gz", hash = "sha256:6c9a10eb5f342415fe085db551d673955611afb821551f554d91772415464315"}, -] -terminado = [ - {file = "terminado-0.17.0-py3-none-any.whl", hash = "sha256:bf6fe52accd06d0661d7611cc73202121ec6ee51e46d8185d489ac074ca457c2"}, - {file = "terminado-0.17.0.tar.gz", hash = "sha256:520feaa3aeab8ad64a69ca779be54be9234edb2d0d6567e76c93c2c9a4e6e43f"}, -] -tinycss2 = [ - {file = "tinycss2-1.2.1-py3-none-any.whl", hash = "sha256:2b80a96d41e7c3914b8cda8bc7f705a4d9c49275616e886103dd839dfc847847"}, - {file = "tinycss2-1.2.1.tar.gz", hash = "sha256:8cff3a8f066c2ec677c06dbc7b45619804a6938478d9d73c284b29d14ecb0627"}, -] -tomli = [ - {file = "tomli-2.0.1-py3-none-any.whl", hash = "sha256:939de3e7a6161af0c887ef91b7d41a53e7c5a1ca976325f429cb46ea9bc30ecc"}, - {file = "tomli-2.0.1.tar.gz", hash = "sha256:de526c12914f0c550d15924c62d72abc48d6fe7364aa87328337a31007fe8a4f"}, -] -torch = [ - {file = "torch-1.13.0-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:f68edfea71ade3862039ba66bcedf954190a2db03b0c41a9b79afd72210abd97"}, - {file = "torch-1.13.0-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:d2d2753519415d154de4d3e64d2eaaeefdba6b6fd7d69d5ffaef595988117700"}, - {file = "torch-1.13.0-cp310-cp310-win_amd64.whl", hash = "sha256:6c227c16626e4ce766cca5351cc62a2358a11e8e466410a298487b9dff159eb1"}, - {file = "torch-1.13.0-cp310-none-macosx_10_9_x86_64.whl", hash = "sha256:49a949b8136b32b2ec0724cbf4c6678b54e974b7d68f19f1231eea21cde5c23b"}, - {file = "torch-1.13.0-cp310-none-macosx_11_0_arm64.whl", hash = "sha256:0fdd38c96230947b1ed870fed4a560252f8d23c3a2bf4dab9d2d42b18f2e67c8"}, - {file = "torch-1.13.0-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:43db0723fc66ad6486f86dc4890c497937f7cd27429f28f73fb7e4d74b7482e2"}, - {file = "torch-1.13.0-cp37-cp37m-manylinux1_x86_64.whl", hash = "sha256:e643ac8d086706e82f77b5d4dfcf145a9dd37b69e03e64177fc23821754d2ed7"}, - {file = "torch-1.13.0-cp37-cp37m-manylinux2014_aarch64.whl", hash = "sha256:bb33a911460475d1594a8c8cb73f58c08293211760796d99cae8c2509b86d7f1"}, - {file = "torch-1.13.0-cp37-cp37m-win_amd64.whl", hash = "sha256:220325d0f4e69ee9edf00c04208244ef7cf22ebce083815ce272c7491f0603f5"}, - {file = "torch-1.13.0-cp37-none-macosx_10_9_x86_64.whl", hash = "sha256:cd1e67db6575e1b173a626077a54e4911133178557aac50683db03a34e2b636a"}, - {file = "torch-1.13.0-cp37-none-macosx_11_0_arm64.whl", hash = "sha256:9197ec216833b836b67e4d68e513d31fb38d9789d7cd998a08fba5b499c38454"}, - {file = "torch-1.13.0-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:fa768432ce4b8ffa29184c79a3376ab3de4a57b302cdf3c026a6be4c5a8ab75b"}, - {file = "torch-1.13.0-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:635dbb99d981a6483ca533b3dc7be18ef08dd9e1e96fb0bb0e6a99d79e85a130"}, - {file = "torch-1.13.0-cp38-cp38-win_amd64.whl", hash = "sha256:857c7d5b1624c5fd979f66d2b074765733dba3f5e1cc97b7d6909155a2aae3ce"}, - {file = "torch-1.13.0-cp38-none-macosx_10_9_x86_64.whl", hash = "sha256:ef934a21da6f6a516d0a9c712a80d09c56128abdc6af8dc151bee5199b4c3b4e"}, - {file = "torch-1.13.0-cp38-none-macosx_11_0_arm64.whl", hash = "sha256:f01a9ae0d4b69d2fc4145e8beab45b7877342dddbd4838a7d3c11ca7f6680745"}, - {file = "torch-1.13.0-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:9ac382cedaf2f70afea41380ad8e7c06acef6b5b7e2aef3971cdad666ca6e185"}, - {file = "torch-1.13.0-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:e20df14d874b024851c58e8bb3846249cb120e677f7463f60c986e3661f88680"}, - {file = "torch-1.13.0-cp39-cp39-win_amd64.whl", hash = "sha256:4a378f5091307381abfb30eb821174e12986f39b1cf7c4522bf99155256819eb"}, - {file = "torch-1.13.0-cp39-none-macosx_10_9_x86_64.whl", hash = "sha256:922a4910613b310fbeb87707f00cb76fec328eb60cc1349ed2173e7c9b6edcd8"}, - {file = "torch-1.13.0-cp39-none-macosx_11_0_arm64.whl", hash = "sha256:47fe6228386bff6d74319a2ffe9d4ed943e6e85473d78e80502518c607d644d2"}, -] -tornado = [ - {file = "tornado-6.2-cp37-abi3-macosx_10_9_universal2.whl", hash = "sha256:20f638fd8cc85f3cbae3c732326e96addff0a15e22d80f049e00121651e82e72"}, - {file = "tornado-6.2-cp37-abi3-macosx_10_9_x86_64.whl", hash = "sha256:87dcafae3e884462f90c90ecc200defe5e580a7fbbb4365eda7c7c1eb809ebc9"}, - {file = "tornado-6.2-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ba09ef14ca9893954244fd872798b4ccb2367c165946ce2dd7376aebdde8e3ac"}, - {file = "tornado-6.2-cp37-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b8150f721c101abdef99073bf66d3903e292d851bee51910839831caba341a75"}, - {file = "tornado-6.2-cp37-abi3-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d3a2f5999215a3a06a4fc218026cd84c61b8b2b40ac5296a6db1f1451ef04c1e"}, - {file = "tornado-6.2-cp37-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:5f8c52d219d4995388119af7ccaa0bcec289535747620116a58d830e7c25d8a8"}, - {file = "tornado-6.2-cp37-abi3-musllinux_1_1_i686.whl", hash = "sha256:6fdfabffd8dfcb6cf887428849d30cf19a3ea34c2c248461e1f7d718ad30b66b"}, - {file = "tornado-6.2-cp37-abi3-musllinux_1_1_x86_64.whl", hash = "sha256:1d54d13ab8414ed44de07efecb97d4ef7c39f7438cf5e976ccd356bebb1b5fca"}, - {file = "tornado-6.2-cp37-abi3-win32.whl", hash = "sha256:5c87076709343557ef8032934ce5f637dbb552efa7b21d08e89ae7619ed0eb23"}, - {file = "tornado-6.2-cp37-abi3-win_amd64.whl", hash = "sha256:e5f923aa6a47e133d1cf87d60700889d7eae68988704e20c75fb2d65677a8e4b"}, - {file = "tornado-6.2.tar.gz", hash = "sha256:9b630419bde84ec666bfd7ea0a4cb2a8a651c2d5cccdbdd1972a0c859dfc3c13"}, -] -traitlets = [ - {file = "traitlets-5.5.0-py3-none-any.whl", hash = "sha256:1201b2c9f76097195989cdf7f65db9897593b0dfd69e4ac96016661bb6f0d30f"}, - {file = "traitlets-5.5.0.tar.gz", hash = "sha256:b122f9ff2f2f6c1709dab289a05555be011c87828e911c0cf4074b85cb780a79"}, -] -typing-extensions = [ - {file = "typing_extensions-4.4.0-py3-none-any.whl", hash = "sha256:16fa4864408f655d35ec496218b85f79b3437c829e93320c7c9215ccfd92489e"}, - {file = "typing_extensions-4.4.0.tar.gz", hash = "sha256:1511434bb92bf8dd198c12b1cc812e800d4181cfcb867674e0f8279cc93087aa"}, -] -u-msgpack-python = [ - {file = "u-msgpack-python-2.7.2.tar.gz", hash = "sha256:e86f7ac6aa0ef4c6c49f004b4fd435bce99c23e2dd5d73003f3f9816024c2bd8"}, - {file = "u_msgpack_python-2.7.2-py2.py3-none-any.whl", hash = "sha256:00c77bbb65f8f68c8bd2570e0a14dee84aba429629ea78adc713f94da52ee386"}, -] -varint = [ - {file = "varint-1.0.2.tar.gz", hash = "sha256:a6ecc02377ac5ee9d65a6a8ad45c9ff1dac8ccee19400a5950fb51d594214ca5"}, -] -wcwidth = [ - {file = "wcwidth-0.2.5-py2.py3-none-any.whl", hash = "sha256:beb4802a9cebb9144e99086eff703a642a13d6a0052920003a230f3294bbe784"}, - {file = "wcwidth-0.2.5.tar.gz", hash = "sha256:c4d647b99872929fdb7bdcaa4fbe7f01413ed3d98077df798530e5b04f116c83"}, -] -webencodings = [ - {file = "webencodings-0.5.1-py2.py3-none-any.whl", hash = "sha256:a0af1213f3c2226497a97e2b3aa01a7e4bee4f403f95be16fc9acd2947514a78"}, - {file = "webencodings-0.5.1.tar.gz", hash = "sha256:b36a1c245f2d304965eb4e0a82848379241dc04b865afcc4aab16748587e1923"}, -] -websocket-client = [ - {file = "websocket-client-1.4.2.tar.gz", hash = "sha256:d6e8f90ca8e2dd4e8027c4561adeb9456b54044312dba655e7cae652ceb9ae59"}, - {file = "websocket_client-1.4.2-py3-none-any.whl", hash = "sha256:d6b06432f184438d99ac1f456eaf22fe1ade524c3dd16e661142dc54e9cba574"}, -] -wheel = [ - {file = "wheel-0.38.4-py3-none-any.whl", hash = "sha256:b60533f3f5d530e971d6737ca6d58681ee434818fab630c83a734bb10c083ce8"}, - {file = "wheel-0.38.4.tar.gz", hash = "sha256:965f5259b566725405b05e7cf774052044b1ed30119b5d586b2703aafe8719ac"}, -] -widgetsnbextension = [ - {file = "widgetsnbextension-4.0.3-py3-none-any.whl", hash = "sha256:7f3b0de8fda692d31ef03743b598620e31c2668b835edbd3962d080ccecf31eb"}, - {file = "widgetsnbextension-4.0.3.tar.gz", hash = "sha256:34824864c062b0b3030ad78210db5ae6a3960dfb61d5b27562d6631774de0286"}, -] -zipp = [ - {file = "zipp-3.10.0-py3-none-any.whl", hash = "sha256:4fcb6f278987a6605757302a6e40e896257570d11c51628968ccb2a47e80c6c1"}, - {file = "zipp-3.10.0.tar.gz", hash = "sha256:7a7262fd930bd3e36c50b9a64897aec3fafff3dfdeec9623ae22b40e93f99bb8"}, -] diff --git a/pyproject.toml b/pyproject.toml index c0d7836..b01c4b8 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,29 +1,56 @@ [tool.poetry] name = "cartpole" -version = "0.1.0" -description = "" -authors = [] -readme = "readme.md" +version = "3.0.0" +license = "MIT" +description = "Control study project" +authors = [ + "Simagin Denis ", + "Andrew Bondarev " +] +repository = "https://github.com/robotics-laboratory/cart-pole" +documentation = "https://cartpole.robotics-lab.ru" +keywords = ["cartpole", "control", "reinforcement learning"] + +packages = [ + { include = "cartpole" }, +] + +[[tool.poetry.source]] +name = "torch" +url = "https://download.pytorch.org/whl/cpu/" +priority = "explicit" [tool.poetry.dependencies] -python = "^3.9" -torch = "^1.13.0" -numpy = "^1.23.5" +python = "~3.10" + +casadi = "^3.6" +dacite = "^1.6" +foxglove-websocket = "^0.1" +mcap = "^1.1" +numpy = "^1.26" +pydantic = "^2.3" protobuf = "^4.21.9" pyserial = "^3.5" +scipy = "^1.11" +torch = [ + {url="https://download.pytorch.org/whl/cpu/torch-2.0.1-cp310-none-macosx_11_0_arm64.whl", markers="platform_system == 'Darwin' and platform_machine == 'arm64'"}, + {url="https://download.pytorch.org/whl/cpu/torch-2.0.1-cp310-none-macosx_10_9_x86_64.whl", markers="platform_system == 'Darwin' and platform_machine == 'x86_64'"}, + {url="https://download.pytorch.org/whl/torch-2.0.1-cp310-cp310-manylinux2014_aarch64.whl", markers="platform_system == 'Linux' and platform_machine == 'aarch64'"}, + {url="https://download.pytorch.org/whl/cpu/torch-2.0.1%2Bcpu-cp310-cp310-linux_x86_64.whl", markers="platform_system == 'Linux' and platform_machine == 'x86_64'"}, + {url="https://download.pytorch.org/whl/cpu/torch-2.0.1%2Bcpu-cp310-cp310-win_amd64.whl", markers="platform_system == 'Windows' and platform_machine == 'amd64'"} +] varint = "^1.0.2" -dacite = "^1.6.0" -drake = {version = "^1.10.0", optional = true} [tool.poetry.group.dev.dependencies] -jupyter = "^1.0.0" -pytest = "^7.2.0" -matplotlib = "^3.6.2" -pandas = "^1.5.1" -seaborn = "^0.12.1" - -[tool.poetry.extras] -pydrake = ["drake"] +jupyter = "^1.0" +matplotlib = "^3.8" +mkdocs = "^1.5" +mkdocstrings = { version = "^0.24", extras = ["python"] } +mkdocs-material = "^9.4" +mkdocs-material-extensions = "^1.2" +ruff = "^0.2" +pandas = "^2.1" +pytest = "^7.4" [build-system] requires = ["poetry-core"] diff --git a/readme.md b/readme.md index aff9eea..7284914 100644 --- a/readme.md +++ b/readme.md @@ -1,43 +1,17 @@ # CartPole -[![CI](https://github.com/dasimagin/cart_pole/actions/workflows/ci.yml/badge.svg?branch=master)](https://github.com/dasimagin/cart_pole/actions/workflows/ci.yml) +[![docs](https://github.com/robotics-laboratory/cart-pole/actions/workflows/docs.yml/badge.svg)](https://robotics-laboratory.github.io/cart-pole/) -## Overview -This is a student project that is designed to learn the basics of robotics and control theory. -The environment is some variation of the cart-pole problem described by Barto, Sutton, and Anderson. -A pole is attached by an joint to a cart, which moves along guide axis. -Some stepper drives the cart. The control target is desired acceleration of the cart. +It is an educational project of [the robotics group](https://cs.hse.ru/robotics) (HSE/FCS). It is designed to learn the basics of optimal control and reinforcement learning. +The environment is a variation of famous cart-pole problem. +A pole is attached by a joint to a cart, moving along a guide axis. +A stepper motor drives the cart. The control input is the cart's acceleration. +The pole is initially at the rest state, and our goal is to swing up the pole and maintain it in unstable equilibrium state. +There is also a radial variation where the cart moves in a circle. -The cart starts at the middle with no velocity and acceleration. The pole is initially at rest state. -The goal is to swing up the pole and maintain it in upright pose by increasing and reducing the cart's velocity. +You can follow our progress on [YouTube](https://youtube.com/playlist?list=PLR1nN_AQOO9yAG5CHOA4l2x3j89t-3PYf) or take part in the project (here is the [full documentation](https://cartpole.robotics-lab.ru). +Please, contact us if you have any questions or suggestions. -![CartPole](docs/svg/classic_cart_pole.svg) - -Also there is radial variation, where cart moves in a circle. - -![RadialCartPole](docs/svg/radial_cart_pole.svg) - -## Interface -We declare a common [interface](cart_pole/blob/master/interface.py) both for simulator and control. -It allows us to easily train model and make inference on device, use transfer learning, generate real training samples and etc. - -### State -**Field** | **Unit** | **Description** -------------- | -------- | --------------- -positon | m | Position of the cart along the guide axis. The middle is a reference point. -velocity | m/s | Instantaneous linear speed of the cart. -accelerration | m/s^2 | Instantaneous acceleration of the cart. -pole_angle | rad | Angle of pole (ccw). The he lowest position is the reference point. -pole_velocity | rad/s | Instantaneous angular velocity of the pole. -error_code | enum | Current error code - -### Error code -**Code** | **Int** | **Description** ----------------| ------- | --------------- -NO_ERROR | 0 | Position of the cart along the guide axis. The middle is a reference point. -NEED_RESET | 1 | Environment loose control (use soft or hard reset). -X_OVERFLOW | 2 | The maximum allowed position is achieved. -V_OVERFLOW | 3 | The maximum allowed velocity is achieved. -A_OVERFLOW | 4 | The maximum allowed acceleration is achieved. -MOTOR_STALLED | 5 | Some problems with stepper. -ENDSTOP_HIT | 6 | The cart has touched one of endstop hit. +
+ Lamb +
diff --git a/tests/test_log.py b/tests/test_log.py new file mode 100644 index 0000000..a5b0516 --- /dev/null +++ b/tests/test_log.py @@ -0,0 +1,51 @@ +from cartpole import log, State +from pydantic import BaseModel +from time import sleep, time + +import pytest + +class SomeObject(BaseModel): + name: str = '' + value: float = 0.0 + +def test_log_some_object(): + # use default setting and lazy initialization + + # send some object, use current time + log.publish('/some/object', SomeObject(name='first', value=1.0)) + + # send another object, specify time explicitly + log.publish('/some/object', SomeObject(name='second', value=2.0), time()) + + +def test_log_state(): + # explicitly setup logger, specify log path + log.setup(log_path='test.mcap') + + # send state + log.publish('/cartpole/state', State()) + + +def test_log_bad_object(): + # explicitly setup logger only for foxglove + log.setup() + + # send bad object (not pydantic model) + log.publish('/str', 'something') + + # after a while get an forwarded error from foxglove thread + sleep(0.1) + with pytest.raises(AssertionError): + log.publish('/some/object', SomeObject()) + +def test_log_different_types_to_one_topic(): + # reset logger, after fail before and setup for mcap + log.setup('test.mcap') + topic = '/cartpole/state' + + log.publish(topic, State()) + + # send another type to the same topic, now we get an error immediately, + # because mcap logger works at the same thread + with pytest.raises(AssertionError): + log.publish(topic, SomeObject())