diff --git a/.github/workflows/Tests.yml b/.github/workflows/Tests.yml index 5ae70c5c..c531942f 100644 --- a/.github/workflows/Tests.yml +++ b/.github/workflows/Tests.yml @@ -8,7 +8,10 @@ jobs: strategy: matrix: os: [ubuntu-latest, windows-latest, macos-latest] - python: ["3.7", "3.8", "3.9", "3.10"] + python: ["3.8", "3.9", "3.10", "3.11"] + env: + OS: ${{ matrix.os }} + PYTHON: ${{ matrix.python }} steps: - uses: actions/checkout@v2 - name: Set up Python @@ -23,17 +26,15 @@ jobs: run: poetry install - name: Run tests run: poetry run pytest -k "not connected_to_drone" --cov-report=xml --cov blueye - - name: Upload coverage - run: | - curl -s https://codecov.io/bash |\ - bash -s -- -F \ - $(echo ${{ matrix.os}} |\ - cut -d "-" -f 1 |\ - sed "s/$/_python${{ matrix.python }}/" |\ - sed "s/\.//") - shell: bash - env: - CODECOV_TOKEN: "${{ secrets.CODECOV_TOKEN }}" + - name: Upload coverage to Codecov + uses: codecov/codecov-action@v3 + with: + token: ${{ secrets.CODECOV_TOKEN }} + env_vars: OS,PYTHON + fail_ci_if_error: false + files: ./coverage.xml + flags: ${{ matrix.os }}_${{ matrix.python }} + name: codecov-umbrella continue-on-error: true CheckFormatting: diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 80dcf6ad..c58c2814 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -3,4 +3,4 @@ repos: rev: stable hooks: - id: black - language_version: python3.7 + language_version: python3.8 diff --git a/blueye/sdk/__init__.py b/blueye/sdk/__init__.py index 7d07d9b5..7627f273 100644 --- a/blueye/sdk/__init__.py +++ b/blueye/sdk/__init__.py @@ -1,4 +1,3 @@ -from .camera import DepthUnitOverlay, FontSizeOverlay, LogoOverlay, TemperatureUnitOverlay from .constants import WaterDensities from .drone import Drone from .utils import open_local_documentation diff --git a/blueye/sdk/battery.py b/blueye/sdk/battery.py new file mode 100644 index 00000000..ecf5ebc3 --- /dev/null +++ b/blueye/sdk/battery.py @@ -0,0 +1,28 @@ +from __future__ import annotations + +from typing import TYPE_CHECKING, Optional + +import blueye.protocol + +# Necessary to avoid cyclic imports +if TYPE_CHECKING: + from .drone import Drone + + +class Battery: + def __init__(self, parent_drone: Drone): + self._parent_drone = parent_drone + + @property + def state_of_charge(self) -> Optional[float]: + """Get the battery state of charge + + *Returns*: + + * Current state of charge of the drone battery (0..1) + """ + battery_tel = self._parent_drone.telemetry.get(blueye.protocol.BatteryTel) + if battery_tel is not None: + return battery_tel.battery.level + else: + return None diff --git a/blueye/sdk/camera.py b/blueye/sdk/camera.py index f1680662..f32ac4ec 100644 --- a/blueye/sdk/camera.py +++ b/blueye/sdk/camera.py @@ -2,11 +2,9 @@ import re import warnings -from collections import namedtuple -from enum import Enum -from typing import TYPE_CHECKING, NamedTuple +from typing import TYPE_CHECKING, Optional -import numpy as np +import blueye.protocol import requests # Necessary to avoid cyclic imports @@ -15,28 +13,6 @@ class Tilt: - @staticmethod - def _tilt_angle_from_debug_flags(flags: int) -> float: - """Helper function for decoding tilt angle from debug flags - - The tilt angle is encoded as an int8, with 0 at 0 degrees, and each increment representing - 0.5 degrees in either direction. A positive angle is upwards, and negative is downwards. - """ - - TILT_ANGLE_MASK = 0x0000FF0000000000 - TILT_ANGLE_OFFSET = 40 - tilt_angle_array = np.array( - np.right_shift(np.bitwise_and(flags, TILT_ANGLE_MASK), TILT_ANGLE_OFFSET), - dtype=[("tilt_angle", np.int8)], - ).astype([("tilt_angle", float)]) - return tilt_angle_array["tilt_angle"] / 2 - - @staticmethod - def _tilt_stabilization_status_from_debug_flags(flags: int) -> bool: - """Helper function for decoding tilt stabilization status from debug flags""" - TILT_STABILIZATION_MASK = 0x100 - return bool(flags & TILT_STABILIZATION_MASK) - def __init__(self, parent_drone: Drone): self._parent_drone = parent_drone @@ -48,92 +24,54 @@ def _verify_tilt_in_features(self): if "tilt" not in self._parent_drone.features: raise RuntimeError("The connected drone does not support tilting the camera.") - def set_speed(self, speed: float): + def set_velocity(self, velocity: float): """Set the speed and direction of the camera tilt *Arguments*: - * speed (float): Speed and direction of the tilt. 1 is max speed up, -1 is max speed down. + * velocity (float): Speed and direction of the tilt. 1 is max speed up, -1 is max speed down. - Requires a drone with the tilt feature, and software version 1.5 or newer. - A RuntimeError is raised if either of those requirements are not met. + Raises a RuntimeError if the connected drone does not have the tilt option """ - - self._parent_drone._verify_required_blunux_version("1.5") self._verify_tilt_in_features() - - # The tilt command is grouped together with the thruster commands, so to avoid messing with - # the thruster setpoint while tilting we need to get the current setpoint and send it with - # the tilt command. - with self._parent_drone.motion.thruster_lock: - thruster_setpoints = self._parent_drone.motion.current_thruster_setpoints.values() - self._parent_drone._tcp_client.motion_input_tilt(*thruster_setpoints, 0, 0, speed) + self._parent_drone._ctrl_client.set_tilt_velocity(velocity) @property - def angle(self) -> float: + def angle(self) -> Optional[float]: """Return the current angle of the camera tilt - Requires a drone with the tilt feature, and software version 1.5 or newer. - A RuntimeError is raised if either of those requirements are not met. + Raises a RuntimeError if the connected drone does not have the tilt option """ - - self._parent_drone._verify_required_blunux_version("1.5") self._verify_tilt_in_features() - - debug_flags = self._parent_drone._state_watcher.general_state["debug_flags"] - return self._tilt_angle_from_debug_flags(debug_flags) + tilt_angle_tel = self._parent_drone.telemetry.get(blueye.protocol.TiltAngleTel) + if tilt_angle_tel is not None: + return tilt_angle_tel.angle.value + else: + return None @property - def stabilization_enabled(self) -> bool: - """Get the state of active camera stabilization + def stabilization_enabled(self) -> Optional[bool]: + """Get or set the state of active camera stabilization - Use the `toggle_stabilization` method to turn stabilization on or off + *Arguments*: + + * enabled (bool): True to turn stabilization on, False to turn it off *Returns*: - * Current state of active camera stabilization (bool) + * enabled (bool): Current state of active camera stabilization """ - self._parent_drone._verify_required_blunux_version("1.6.42") self._verify_tilt_in_features() + tilt_stab_tel = self._parent_drone.telemetry.get(blueye.protocol.TiltStabilizationTel) + if tilt_stab_tel is not None: + return tilt_stab_tel.state.enabled + else: + return None - debug_flags = self._parent_drone._state_watcher.general_state["debug_flags"] - return self._tilt_stabilization_status_from_debug_flags(debug_flags) - - def toggle_stabilization(self): - """Toggle active camera stabilization on or off - - Requires a drone with the tilt feature, and Blunux version 1.6.42 or newer. - A RuntimeError is raised if either of those requirements are not met. - """ - - self._parent_drone._verify_required_blunux_version("1.6.42") + @stabilization_enabled.setter + def stabilization_enabled(self, enabled: bool): self._verify_tilt_in_features() - self._parent_drone._tcp_client.toggle_tilt_stabilization() - - -class LogoOverlay(Enum): - DISABLED = 0 - BLUEYE = 1 - CUSTOM = 2 - - -class DepthUnitOverlay(Enum): - METERS = 0 - FEET = 1 - - -class TemperatureUnitOverlay(Enum): - CELSIUS = 0 - FAHRENHEIT = 1 - - -class FontSizeOverlay(Enum): - PX15 = 15 - PX20 = 20 - PX25 = 25 - PX30 = 30 - PX35 = 35 - PX40 = 40 + self._parent_drone._ctrl_client.set_tilt_stabilization(enabled) class Overlay: @@ -141,196 +79,155 @@ class Overlay: def __init__(self, parent_drone: Drone): self._parent_drone = parent_drone + self._overlay_parametres = None - def _get_named_overlay_parameters(self) -> NamedTuple: - """Get overlay parameters from drone and convert them to a named tuple""" - - NamedParameters = namedtuple( - "Parameters", - [ - "returned_parameter", - "temperature_enabled", - "depth_enabled", - "heading_enabled", - "tilt_enabled", - "date_enabled", - "logo_index", - "depth_unit", - "temperature_unit", - "tz_offset", - "margin_width", - "margin_height", - "font_size", - "title", - "subtitle", - "date_format", - ], - ) - parameters = self._parent_drone._tcp_client.get_overlay_parameters() - return NamedParameters(*parameters) + def _update_overlay_parameters(self): + self._overlay_parametres = self._parent_drone._req_rep_client.get_overlay_parameters() @property def temperature_enabled(self) -> bool: - """Get or set the state of the temperature overlay - - Requires Blunux version 1.7.60 or newer. - """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return bool(self._get_named_overlay_parameters().temperature_enabled) + """Get or set the state of the temperature overlay""" + self._update_overlay_parameters() + return self._overlay_parametres.temperature_enabled @temperature_enabled.setter def temperature_enabled(self, enable_temperature: bool): - self._parent_drone._verify_required_blunux_version("1.7.60") - self._parent_drone._tcp_client.set_overlay_temperature_enabled( - 1 if enable_temperature else 0 - ) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.temperature_enabled = enable_temperature + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def depth_enabled(self) -> bool: - """Get or set the state of the depth overlay - - Requires Blunux version 1.7.60 or newer. - """ + """Get or set the state of the depth overlay""" - self._parent_drone._verify_required_blunux_version("1.7.60") - return bool(self._get_named_overlay_parameters().depth_enabled) + self._update_overlay_parameters() + return self._overlay_parametres.depth_enabled @depth_enabled.setter def depth_enabled(self, enable_depth: bool): - self._parent_drone._verify_required_blunux_version("1.7.60") - self._parent_drone._tcp_client.set_overlay_depth_enabled(1 if enable_depth else 0) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.depth_enabled = enable_depth + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def heading_enabled(self) -> bool: - """Get or set the state of the heading overlay - - Requires Blunux version 1.7.60 or newer. - """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return bool(self._get_named_overlay_parameters().heading_enabled) + """Get or set the state of the heading overlay""" + self._update_overlay_parameters() + return self._overlay_parametres.heading_enabled @heading_enabled.setter def heading_enabled(self, enable_heading: bool): - self._parent_drone._verify_required_blunux_version("1.7.60") - self._parent_drone._tcp_client.set_overlay_heading_enabled(1 if enable_heading else 0) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.heading_enabled = enable_heading + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def tilt_enabled(self) -> bool: - """Get or set the state of the tilt overlay - - Requires Blunux version 1.7.60 or newer. - """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return bool(self._get_named_overlay_parameters().tilt_enabled) + """Get or set the state of the tilt overlay""" + self._update_overlay_parameters() + return self._overlay_parametres.tilt_enabled @tilt_enabled.setter def tilt_enabled(self, enable_tilt: bool): - self._parent_drone._verify_required_blunux_version("1.7.60") - self._parent_drone._tcp_client.set_overlay_tilt_enabled(1 if enable_tilt else 0) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.tilt_enabled = enable_tilt + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def date_enabled(self) -> bool: - """Get or set the state of the date overlay - - Requires Blunux version 1.7.60 or newer. - """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return bool(self._get_named_overlay_parameters().date_enabled) + """Get or set the state of the date overlay""" + if self._overlay_parametres is None: + self._update_overlay_parameters() + return self._overlay_parametres.date_enabled @date_enabled.setter def date_enabled(self, enable_date: bool): - self._parent_drone._verify_required_blunux_version("1.7.60") - self._parent_drone._tcp_client.set_overlay_date_enabled(1 if enable_date else 0) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.date_enabled = enable_date + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property - def logo(self) -> LogoOverlay: + def logo(self) -> blueye.protcol.LogoType: """Get or set logo overlay selection - Needs to be set to an instance of the `LogoOverlay` class, if not a RuntimeWarning is - raised. + Needs to be set to an instance of the `blueye.protocol.LogoType` enum, if not a + RuntimeWarning is raised. - Requires Blunux version 1.8.72 or newer. """ - - self._parent_drone._verify_required_blunux_version("1.8.72") - return LogoOverlay(self._get_named_overlay_parameters().logo_index) + self._update_overlay_parameters() + return self._overlay_parametres.logo_type @logo.setter - def logo(self, logo_index: LogoOverlay): - self._parent_drone._verify_required_blunux_version("1.8.72") - if not isinstance(logo_index, LogoOverlay): - warnings.warn("Invalid logo index, ignoring", RuntimeWarning) - elif logo_index.value not in range(3): - warnings.warn("Logo index out of range, ignoring", RuntimeWarning) + def logo(self, logo_type: blueye.protocol.LogoType): + if not isinstance(logo_type, blueye.protocol.LogoType): + warnings.warn("Invalid logo type, ignoring", RuntimeWarning) else: - self._parent_drone._tcp_client.set_overlay_logo_index(logo_index.value) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.logo_type = logo_type + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property - def depth_unit(self) -> DepthUnitOverlay: + def depth_unit(self) -> blueye.protocol.DepthUnit: """Get or set the depth unit for the overlay - Needs to be set to an instance of the `DepthUnitOverlay` class, if not a RuntimeWarning is - raised. - - Requires Blunux version 1.7.60 or newer. + Needs to be set to an instance of the `blueye.protocol.DepthUnit` enum, if not a + RuntimeWarning is raised. """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return DepthUnitOverlay(self._get_named_overlay_parameters().depth_unit) + self._update_overlay_parameters() + return self._overlay_parametres.depth_unit @depth_unit.setter - def depth_unit(self, unit_index: DepthUnitOverlay): - self._parent_drone._verify_required_blunux_version("1.7.60") - if not isinstance(unit_index, DepthUnitOverlay): - warnings.warn("Invalid depth unit index, ignoring", RuntimeWarning) - elif unit_index.value not in range(2): - warnings.warn("Depth unit index out of range, ignoring", RuntimeWarning) + def depth_unit(self, unit: blueye.protocol.DepthUnit): + if not isinstance(unit, blueye.protocol.DepthUnit): + warnings.warn("Invalid depth unit, ignoring", RuntimeWarning) else: - self._parent_drone._tcp_client.set_overlay_depth_unit(unit_index.value) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.depth_unit = unit + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property - def temperature_unit(self) -> TemperatureUnitOverlay: + def temperature_unit(self) -> blueye.protocol.TemperatureUnit: """Get or set the temperature unit for the overlay - Needs to be set to an instance of the `TemperatureUnitOverlay` class, if not a + Needs to be set to an instance of the `blueye.protocol.TemperatureUnit` enum, if not a RuntimeWarning is raised. - - Requires Blunux version 1.7.60 or newer. """ - self._parent_drone._verify_required_blunux_version("1.7.60") - return TemperatureUnitOverlay(self._get_named_overlay_parameters().temperature_unit) + self._update_overlay_parameters() + return self._overlay_parametres.temperature_unit @temperature_unit.setter - def temperature_unit(self, unit_index: TemperatureUnitOverlay): - self._parent_drone._verify_required_blunux_version("1.7.60") - if not isinstance(unit_index, TemperatureUnitOverlay): - warnings.warn("Invalid temperature unit index, ignoring", RuntimeWarning) - elif unit_index.value not in range(2): - warnings.warn("Temperature unit index out of range, ignoring", RuntimeWarning) + def temperature_unit(self, unit: blueye.protocol.TemperatureUnit): + if not isinstance(unit, blueye.protocol.TemperatureUnit): + warnings.warn("Invalid temperature unit, ignoring", RuntimeWarning) else: - self._parent_drone._tcp_client.set_overlay_temperature_unit(unit_index.value) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.temperature_unit = unit + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def timezone_offset(self) -> int: """Get or set the timezone offset for the overlay Set to the number of minutes (either positive or negative) the timestamp should be offset. - - Requires Blunux version 1.7.60 or newer. """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return self._get_named_overlay_parameters().tz_offset + self._update_overlay_parameters() + return self._overlay_parametres.timezone_offset @timezone_offset.setter def timezone_offset(self, offset: int): - self._parent_drone._verify_required_blunux_version("1.7.60") - self._parent_drone._tcp_client.set_overlay_tz_offset(offset) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.timezone_offset = offset + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def margin_width(self) -> int: @@ -338,20 +235,19 @@ def margin_width(self) -> int: The amount of pixels to use as margin on the right and left side of the overlay. Needs to be a positive integer. - - Requires Blunux version 1.7.60 or newer. """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return self._get_named_overlay_parameters().margin_width + self._update_overlay_parameters() + return self._overlay_parametres.margin_width @margin_width.setter def margin_width(self, width: int): - self._parent_drone._verify_required_blunux_version("1.7.60") if width < 0: warnings.warn("Invalid margin width, ignoring", RuntimeWarning) else: - self._parent_drone._tcp_client.set_overlay_margin_width(width) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.margin_width = width + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def margin_height(self) -> int: @@ -359,42 +255,39 @@ def margin_height(self) -> int: The amount of pixels to use as margin on the top and bottom side of the overlay. Needs to be a positive integer. - - Requires Blunux version 1.7.60 or newer. """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return self._get_named_overlay_parameters().margin_height + self._update_overlay_parameters() + return self._overlay_parametres.margin_height @margin_height.setter def margin_height(self, height: int): - self._parent_drone._verify_required_blunux_version("1.7.60") if height < 0: warnings.warn("Invalid margin height, ignoring", RuntimeWarning) else: - self._parent_drone._tcp_client.set_overlay_margin_height(height) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.margin_height = height + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property - def font_size(self) -> FontSizeOverlay: + def font_size(self) -> blueye.protocol.FontSize: """Get or set the font size for the overlay - Needs to be an instance of the `FontSizeOverlay` class, if not a RuntimeWarning is raised. - - Requires Blunux version 1.7.60 or newer. + Needs to be an instance of the `blueye.protocol.Fontsize` enum, if not a RuntimeWarning is + raised. """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return FontSizeOverlay(self._get_named_overlay_parameters().font_size) + self._update_overlay_parameters() + return self._overlay_parametres.font_size @font_size.setter - def font_size(self, size: FontSizeOverlay): - self._parent_drone._verify_required_blunux_version("1.7.60") - if not isinstance(size, FontSizeOverlay): + def font_size(self, size: blueye.protocol.FontSize): + if not isinstance(size, blueye.protocol.FontSize): warnings.warn("Invalid font size, ignoring", RuntimeWarning) - elif size.value not in range(15, 41): - warnings.warn("Font size out of range, ignoring", RuntimeWarning) else: - self._parent_drone._tcp_client.set_overlay_font_size(size.value) + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.font_size = size + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def title(self) -> str: @@ -405,25 +298,25 @@ def title(self) -> str: raised. Set to an empty string to disable title. - - Requires Blunux version 1.7.60 or newer. """ - self._parent_drone._verify_required_blunux_version("1.7.60") - return self._get_named_overlay_parameters().title.decode("utf-8").rstrip("\x00") + self._update_overlay_parameters() + return self._overlay_parametres.title @title.setter def title(self, input_title: str): - self._parent_drone._verify_required_blunux_version("1.7.60") new_title = input_title if len(input_title) > 63: warnings.warn("Too long title, truncating to 63 characters", RuntimeWarning) new_title = new_title[:63] try: - encoded_title = bytes(new_title, "ascii") + bytes(new_title, "ascii") except UnicodeEncodeError: warnings.warn("Title can only contain ASCII characters, ignoring", RuntimeWarning) return - self._parent_drone._tcp_client.set_overlay_title(encoded_title + b"\x00") + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.title = new_title + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def subtitle(self) -> str: @@ -434,25 +327,25 @@ def subtitle(self) -> str: raised. Set to an empty string to disable the subtitle. - - Requires Blunux version 1.7.60 or newer. """ - self._parent_drone._verify_required_blunux_version("1.7.60") - return self._get_named_overlay_parameters().subtitle.decode("utf-8").rstrip("\x00") + self._update_overlay_parameters() + return self._overlay_parametres.subtitle @subtitle.setter def subtitle(self, input_subtitle: str): - self._parent_drone._verify_required_blunux_version("1.7.60") new_subtitle = input_subtitle if len(input_subtitle) > 63: warnings.warn("Too long subtitle, truncating to 63 characters", RuntimeWarning) new_subtitle = new_subtitle[:63] try: - encoded_subtitle = bytes(new_subtitle, "ascii") + bytes(new_subtitle, "ascii") except UnicodeEncodeError: warnings.warn("Subtitle can only contain ASCII characters, ignoring", RuntimeWarning) return - self._parent_drone._tcp_client.set_overlay_subtitle(encoded_subtitle + b"\x00") + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.subtitle = new_subtitle + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) @property def date_format(self) -> str: @@ -464,13 +357,11 @@ def date_format(self) -> str: https://docs.python.org/3/library/datetime.html#strftime-and-strptime-format-codes for an overview of the available codes. """ - - self._parent_drone._verify_required_blunux_version("1.7.60") - return self._get_named_overlay_parameters().date_format.decode("utf-8").rstrip("\x00") + self._update_overlay_parameters() + return self._overlay_parametres.date_format @date_format.setter def date_format(self, input_format_str: str): - self._parent_drone._verify_required_blunux_version("1.7.60") format_str = input_format_str if len(format_str) > 63: warnings.warn( @@ -478,40 +369,41 @@ def date_format(self, input_format_str: str): ) format_str = format_str[:63] try: - encoded_format_str = bytes(format_str, "ascii") + bytes(format_str, "ascii") except UnicodeEncodeError: warnings.warn( "Date format string can only contain ASCII characters, ignoring", RuntimeWarning ) return - self._parent_drone._tcp_client.set_overlay_date_format(encoded_format_str + b"\x00") + if self._overlay_parametres is None: + self._update_overlay_parameters() + self._overlay_parametres.date_format = format_str + self._parent_drone._req_rep_client.set_overlay_parameters(self._overlay_parametres) - def upload_logo(self, path_to_logo: str): + def upload_logo(self, path_to_logo: str, timeout: float = 1.0): """Upload user selectable logo for watermarking videos and pictures - Set the logo-property to `LogoOverlay.CUSTOM` to enable this logo. + Set the logo-property to `blueye.protocol.LogoType.LOG_TYPE_CUSTOM` to enable this logo. Allowed filetype: JPG or PNG. Max resolution: 2000 px. Max file size: 5 MB. - Requires Blunux version 1.8.72 or newer. - *Exceptions*: * `requests.exceptions.HTTPError` : Status code 400 for invalid files - * `requests.exceptions.ConnectTimeout` : If unable to create a connection within 1s + * `requests.exceptions.ConnectTimeout` : If unable to create a connection within specified + timeout (default 1s) """ - self._parent_drone._verify_required_blunux_version("1.8.72") with open(path_to_logo, "rb") as f: url = f"http://{self._parent_drone._ip}/asset/logo" files = {"image": f} - response = requests.post(url, files=files, timeout=1) + response = requests.post(url, files=files, timeout=timeout) response.raise_for_status() - def download_logo(self, output_directory="."): + def download_logo(self, output_directory=".", timeout: float = 1.0): """Download the original user uploaded logo (PNG or JPG) Select the download directory with the output_directory parameter. @@ -520,82 +412,138 @@ def download_logo(self, output_directory="."): * `requests.exceptions.HTTPError` : If no custom logo is uploaded. - * `requests.exceptions.ConnectTimeout` : If unable to create a connection within 1s + * `requests.exceptions.ConnectTimeout` : If unable to create a connection within specified + timeout (default 1s) """ - self._parent_drone._verify_required_blunux_version("1.8.72") - response = requests.get(f"http://{self._parent_drone._ip}/asset/logo", timeout=1) + response = requests.get(f"http://{self._parent_drone._ip}/asset/logo", timeout=timeout) response.raise_for_status() filename = re.findall('filename="(.+)"', response.headers["Content-Disposition"])[0] with open(f"{output_directory}/{filename}", "wb") as f: f.write(response.content) - def delete_logo(self): + def delete_logo(self, timeout: float = 1.0): """Delete the user uploaded logo from the drone *Exceptions*: * `requests.exceptions.HTTPError` : If an error occurs during deletion - * `requests.exceptions.ConnectTimeout` : If unable to create a connection within 1s + * `requests.exceptions.ConnectTimeout` : If unable to create a connection within specified + timeout (default 1s) """ - self._parent_drone._verify_required_blunux_version("1.8.72") - response = requests.delete(f"http://{self._parent_drone._ip}/asset/logo", timeout=1) + response = requests.delete(f"http://{self._parent_drone._ip}/asset/logo", timeout=timeout) response.raise_for_status() class Camera: - def __init__(self, parent_drone: Drone): - self._state_watcher = parent_drone._state_watcher + def __init__(self, parent_drone: Drone, is_guestport_camera: bool = False): self._parent_drone = parent_drone - self.tilt = Tilt(parent_drone) - self.overlay = Overlay(parent_drone) + self._is_guestport_camera = is_guestport_camera + self._camera_type = ( + blueye.protocol.Camera.CAMERA_GUESTPORT + if is_guestport_camera + else blueye.protocol.Camera.CAMERA_MAIN + ) + if not self._is_guestport_camera: + self.tilt = Tilt(parent_drone) + self.overlay = Overlay(parent_drone) + self._camera_parameters = None + + def _get_record_state(self) -> Optional[blueye.protocol.RecordState]: + record_state_tel = self._parent_drone.telemetry.get(blueye.protocol.RecordStateTel) + if record_state_tel is not None: + return record_state_tel.record_state + else: + return None + + def _update_camera_parameters(self): + self._camera_parameters = self._parent_drone._req_rep_client.get_camera_parameters( + camera=self._camera_type + ) @property - def is_recording(self) -> bool: - """Start or stop a camera recording + def is_recording(self) -> Optional[bool]: + """Get or set the camera recording state *Arguments*: - * is_recording (bool): Set to True to start a recording, set to False to stop the current recording + * start_recording (bool): Set to True to start a recording, set to False to stop the current + recording. *Returns*: - * is_recording (bool): True if the camera is currently recording, False if not + * Recording state (bool): True if the camera is currently recording, False if not """ - state = self._state_watcher.general_state - if state["camera_record_time"] != -1: - return True + record_state = self._get_record_state() + if record_state is None: + return None + if self._is_guestport_camera: + return record_state.guestport_is_recording else: - return False + return record_state.main_is_recording @is_recording.setter def is_recording(self, start_recording: bool): - if start_recording: - self._parent_drone._tcp_client.start_recording() + record_state = self._get_record_state() + if record_state is None: + # TODO: Log this as a warning + return + if self._is_guestport_camera: + self._parent_drone._ctrl_client.set_recording_state( + record_state.main_is_recording, start_recording + ) else: - self._parent_drone._tcp_client.stop_recording() + self._parent_drone._ctrl_client.set_recording_state( + start_recording, record_state.guestport_is_recording + ) @property def bitrate(self) -> int: - """Set or get the camera bitrate + """Set or get the video stream bitrate *Arguments*: - * bitrate (int): Set the camera bitrate in bits, Valid values are in range <1 000 000, 16 000 000> + * bitrate (int): Set the video stream bitrate in bits, valid values are in range + (1 000 000..16 000 000) *Returns*: - * bitrate (int): Get the camera bitrate + * bitrate (int): The H264 video stream bitrate """ - camera_parameters = self._parent_drone._tcp_client.get_camera_parameters() - bitrate = camera_parameters[1] - return bitrate + self._update_camera_parameters() + return self._camera_parameters.h264_bitrate @bitrate.setter def bitrate(self, bitrate: int): - self._parent_drone._tcp_client.set_camera_bitrate(bitrate) + if self._camera_parameters is None: + self._update_camera_parameters() + self._camera_parameters.h264_bitrate = bitrate + self._parent_drone._req_rep_client.set_camera_parameters(self._camera_parameters) + + @property + def bitrate_still_picture(self) -> int: + """Set or get the bitrate for the still picture stream + + *Arguments*: + + * bitrate (int): Set the still picture stream bitrate in bits, valid values are in range + (1 000 000 .. 300 000 000). Default value is 100 000 000. + + *Returns*: + + * bitrate (int): The still picture stream bitrate + """ + self._update_camera_parameters() + return self._camera_parameters.mjpg_bitrate + + @bitrate_still_picture.setter + def bitrate_still_picture(self, bitrate: int): + if self._camera_parameters is None: + self._update_camera_parameters() + self._camera_parameters.mjpg_bitrate = bitrate + self._parent_drone._req_rep_client.set_camera_parameters(self._camera_parameters) @property def exposure(self) -> int: @@ -603,19 +551,23 @@ def exposure(self) -> int: *Arguments*: - * exposure (int): Set the camera exposure_value: 1 = 1/1000th of a second, 5 = 1/200th of a second. Valid values are in the range <1, 5000> + * exposure (int): Set the camera exposure time. Unit is thousandths of a second, ie. + 5 = 5s/1000. Valid values are in the range (1 .. 5000) or -1 for auto + exposure *Returns*: * exposure (int): Get the camera exposure """ - camera_parameters = self._parent_drone._tcp_client.get_camera_parameters() - exposure = camera_parameters[2] - return exposure + self._update_camera_parameters() + return self._camera_parameters.exposure @exposure.setter def exposure(self, exposure: int): - self._parent_drone._tcp_client.set_camera_exposure(exposure) + if self._camera_parameters is None: + self._update_camera_parameters() + self._camera_parameters.exposure = exposure + self._parent_drone._req_rep_client.set_camera_parameters(self._camera_parameters) @property def whitebalance(self) -> int: @@ -623,19 +575,22 @@ def whitebalance(self) -> int: *Arguments*: - * whitebalance (int): Set the camera white balance. Valid values are in the range <2800, 9300> + * white_balance (int): Set the camera white balance. Valid values are in the range + (2800..9300) or -1 for auto white balance *Returns*: - * whitebalance (int): Get the camera white balance + * white_balance (int): Get the camera white balance """ - camera_parameters = self._parent_drone._tcp_client.get_camera_parameters() - whitebalance = camera_parameters[3] - return whitebalance + self._update_camera_parameters() + return self._camera_parameters.white_balance @whitebalance.setter - def whitebalance(self, whitebalance: int): - self._parent_drone._tcp_client.set_camera_whitebalance(whitebalance) + def whitebalance(self, white_balance: int): + if self._camera_parameters is None: + self._update_camera_parameters() + self._camera_parameters.white_balance = white_balance + self._parent_drone._req_rep_client.set_camera_parameters(self._camera_parameters) @property def hue(self) -> int: @@ -643,19 +598,21 @@ def hue(self) -> int: *Arguments*: - * hue (int): Set the camera hue. Valid values are in the range <-40, 40> + * hue (int): Set the camera hue. Valid values are in the range (-40..40) *Returns*: * hue (int): Get the camera hue """ - camera_parameters = self._parent_drone._tcp_client.get_camera_parameters() - hue = camera_parameters[4] - return hue + self._update_camera_parameters() + return self._camera_parameters.hue @hue.setter def hue(self, hue: int): - self._parent_drone._tcp_client.set_camera_hue(hue) + if self._camera_parameters is None: + self._update_camera_parameters() + self._camera_parameters.hue = hue + self._parent_drone._req_rep_client.set_camera_parameters(self._camera_parameters) @property def resolution(self) -> int: @@ -669,13 +626,28 @@ def resolution(self) -> int: * resolution (int): Get the camera resolution """ - camera_parameters = self._parent_drone._tcp_client.get_camera_parameters() - resolution = camera_parameters[5] - return resolution + self._update_camera_parameters() + if self._camera_parameters.resolution == blueye.protocol.Resolution.RESOLUTION_HD_720P: + return 720 + elif ( + self._camera_parameters.resolution == blueye.protocol.Resolution.RESOLUTION_FULLHD_1080P + ): + return 1080 @resolution.setter def resolution(self, resolution: int): - self._parent_drone._tcp_client.set_camera_resolution(resolution) + if resolution not in (720, 1080): + raise ValueError( + f"{resolution} is not a valid resolution. Valid values are 720 or 1080" + ) + if self._camera_parameters is None: + self._update_camera_parameters() + if resolution == 720: + self._camera_parameters.resolution = blueye.protocol.Resolution.RESOLUTION_HD_720P + elif resolution == 1080: + self._camera_parameters.resolution = blueye.protocol.Resolution.RESOLUTION_FULLHD_1080P + + self._parent_drone._req_rep_client.set_camera_parameters(self._camera_parameters) @property def framerate(self) -> int: @@ -689,30 +661,43 @@ def framerate(self) -> int: * framerate (int): Get the camera frame rate """ - camera_parameters = self._parent_drone._tcp_client.get_camera_parameters() - framerate = camera_parameters[6] - return framerate + self._update_camera_parameters() + if self._camera_parameters.framerate == blueye.protocol.Framerate.FRAMERATE_FPS_25: + return 25 + elif self._camera_parameters.framerate == blueye.protocol.Framerate.FRAMERATE_FPS_30: + return 30 @framerate.setter def framerate(self, framerate: int): - self._parent_drone._tcp_client.set_camera_framerate(framerate) + if framerate not in (25, 30): + raise ValueError(f"{framerate} is not a valid framerate. Valid values are 25 or 30") + if self._camera_parameters is None: + self._update_camera_parameters() + if framerate == 25: + self._camera_parameters.framerate = blueye.protocol.Framerate.FRAMERATE_FPS_25 + elif framerate == 30: + self._camera_parameters.framerate = blueye.protocol.Framerate.FRAMERATE_FPS_30 + self._parent_drone._req_rep_client.set_camera_parameters(self._camera_parameters) @property - def record_time(self) -> int: + def record_time(self) -> Optional[int]: """Set or get the duration of the current camera recording *Returns*: * record_time (int): The length in seconds of the current recording, -1 if the camera is not currently recording """ - return self._state_watcher.general_state["camera_record_time"] + record_state = self._get_record_state() + if record_state is None: + return None + if self._is_guestport_camera: + return record_state.guestport_seconds + else: + return record_state.main_seconds def take_picture(self): """Takes a still picture and stores it locally on the drone These pictures can be downloaded with the Blueye App, or by any WebDAV compatible client. - This feature was added with drone version 1.4.7, so if you try to use it with an older - version this method will raise a RunTimeError. """ - self._parent_drone._verify_required_blunux_version("1.4.7") - self._parent_drone._tcp_client.take_still_picture() + self._parent_drone._ctrl_client.take_still_picture() diff --git a/blueye/sdk/connection.py b/blueye/sdk/connection.py new file mode 100644 index 00000000..b2286c93 --- /dev/null +++ b/blueye/sdk/connection.py @@ -0,0 +1,336 @@ +from __future__ import annotations + +import importlib.metadata +import platform +import queue +import threading +import uuid +from typing import Callable, Dict, List, NamedTuple + +import blueye.protocol +import proto +import zmq + + +class WatchdogPublisher(threading.Thread): + def __init__(self, parent_drone: "blueye.sdk.Drone", context: zmq.Context = None): + super().__init__(daemon=True) + self._parent_drone = parent_drone + self._context = context or zmq.Context().instance() + self._socket = self._context.socket(zmq.PUB) + self._socket.connect(f"tcp://{self._parent_drone._ip}:5557") + self._exit_flag = threading.Event() + + def run(self): + duration = 0 + WATCHDOG_DELAY = 1 + while not self._exit_flag.wait(WATCHDOG_DELAY): + self.pet_watchdog(duration) + duration += 1 + + def pet_watchdog(self, duration): + msg = blueye.protocol.WatchdogCtrl( + connection_duration={"value": duration}, client_id=self._parent_drone.client_id + ) + self._socket.send_multipart( + [ + bytes(msg._pb.DESCRIPTOR.full_name, "utf-8"), + blueye.protocol.WatchdogCtrl.serialize(msg), + ] + ) + + def stop(self): + """Stop the watchdog thread started by run()""" + self._exit_flag.set() + + +class Callback(NamedTuple): + """Specifications for callback for telemetry messages""" + + message_filter: List[proto.messages.Message] + function: Callable[[str, proto.message.Message], None] + pass_raw_data: bool + uuid_hex: str + + +class TelemetryClient(threading.Thread): + def __init__(self, parent_drone: "blueye.sdk.Drone", context: zmq.Context = None): + super().__init__(daemon=True) + self._parent_drone = parent_drone + self._context = context or zmq.Context().instance() + self._socket = self._context.socket(zmq.SUB) + self._socket.connect(f"tcp://{self._parent_drone._ip}:5555") + self._socket.setsockopt_string(zmq.SUBSCRIBE, "") + self._exit_flag = threading.Event() + self._state_lock = threading.Lock() + self._callbacks: List[Callback] = [] + self._state: Dict[proto.message.Message, bytes] = {} + """`_state` is dictionary of the latest received messages, where the key is the protobuf + message class, eg. blueye.protocol.DepthTel and the value is the serialized protobuf + message""" + + def run(self): + poller = zmq.Poller() + poller.register(self._socket, zmq.POLLIN) + + while not self._exit_flag.is_set(): + events_to_be_processed = poller.poll(10) + if len(events_to_be_processed) > 0: + msg = self._socket.recv_multipart() + msg_type_name = msg[0].decode("utf-8").replace("blueye.protocol.", "") + try: + msg_type = blueye.protocol.__getattribute__(msg_type_name) + except AttributeError: + # We've received a message we're unable to parse, we disregard this message + # TODO: Log this + continue + msg_payload = msg[1] + with self._state_lock: + self._state[msg_type] = msg_payload + for callback in self._callbacks: + if msg_type in callback.message_filter or callback.message_filter == []: + if callback.pass_raw_data: + callback.function(msg_type_name, msg_payload) + else: + msg_deserialized = msg_type.deserialize(msg_payload) + callback.function(msg_type_name, msg_deserialized) + + def add_callback( + self, + msg_filter: List[proto.message.Message], + callback_function: Callable[[str, proto.message.Message], None], + raw: bool, + ): + uuid_hex = uuid.uuid1().hex + self._callbacks.append(Callback(msg_filter, callback_function, raw, uuid_hex)) + return uuid_hex + + def remove_callback(self, callback_id): + try: + self._callbacks.pop([cb.uuid_hex for cb in self._callbacks].index(callback_id)) + except ValueError: + # No callback registered with the specified id, ignoring + # TODO: Log this + pass + + def get(self, key: proto.message.Message): + with self._state_lock: + return self._state[key] + + def stop(self): + self._exit_flag.set() + + +class CtrlClient(threading.Thread): + def __init__( + self, + parent_drone: "blueye.sdk.Drone", + context: zmq.Context = None, + ): + super().__init__(daemon=True) + self._context = context or zmq.Context().instance() + self._parent_drone = parent_drone + self._drone_pub_socket = self._context.socket(zmq.PUB) + self._drone_pub_socket.connect(f"tcp://{self._parent_drone._ip}:5557") + self._messages_to_send = queue.Queue() + self._exit_flag = threading.Event() + + def run(self): + while not self._exit_flag.is_set(): + try: + msg = self._messages_to_send.get(timeout=0.1) + self._drone_pub_socket.send_multipart( + [ + bytes(msg._pb.DESCRIPTOR.full_name, "utf-8"), + msg.__class__.serialize(msg), + ] + ) + except queue.Empty: + # No messages to send, so we can + continue + + def stop(self): + self._exit_flag.set() + + def set_lights(self, value: float): + msg = blueye.protocol.LightsCtrl(lights={"value": value}) + self._messages_to_send.put(msg) + + def set_water_density(self, value: float): + msg = blueye.protocol.WaterDensityCtrl(density={"value": value}) + self._messages_to_send.put(msg) + + def set_tilt_velocity(self, value: float): + msg = blueye.protocol.TiltVelocityCtrl(velocity={"value": value}) + self._messages_to_send.put(msg) + + def set_tilt_stabilization(self, enabled: bool): + msg = blueye.protocol.TiltStabilizationCtrl(state={"enabled": enabled}) + self._messages_to_send.put(msg) + + def set_motion_input( + self, surge: float, sway: float, heave: float, yaw: float, slow: float, boost: float + ): + msg = blueye.protocol.MotionInputCtrl( + motion_input={ + "surge": surge, + "sway": sway, + "heave": heave, + "yaw": yaw, + "slow": slow, + "boost": boost, + } + ) + self._messages_to_send.put(msg) + + def set_auto_depth_state(self, enabled: bool): + msg = blueye.protocol.AutoDepthCtrl(state={"enabled": enabled}) + self._messages_to_send.put(msg) + + def set_auto_heading_state(self, enabled: bool): + msg = blueye.protocol.AutoHeadingCtrl(state={"enabled": enabled}) + self._messages_to_send.put(msg) + + def set_recording_state(self, main_enabled: bool, guestport_enabled: bool): + msg = blueye.protocol.RecordCtrl( + record_on={"main": main_enabled, "guestport": guestport_enabled} + ) + self._messages_to_send.put(msg) + + def take_still_picture(self): + msg = blueye.protocol.TakePictureCtrl() + self._messages_to_send.put(msg) + + +class ReqRepClient(threading.Thread): + def __init__(self, parent_drone: "blueye.sdk.Drone", context: zmq.Context = None): + super().__init__(daemon=True) + self._context = context or zmq.Context().instance() + self._parent_drone = parent_drone + self._socket = self._context.socket(zmq.REQ) + self._socket.connect(f"tcp://{self._parent_drone._ip}:5556") + self._requests_to_send = queue.Queue() + self._exit_flag = threading.Event() + + @staticmethod + def _get_client_info() -> blueye.protocol.ClientInfo: + client_info = blueye.protocol.ClientInfo( + type="SDK", + version=f"{importlib.metadata.version('blueye.sdk')}", + device_type="Computer", + platform=f"{platform.system()}", + platform_version=f"{platform.release()}", + name=f"{platform.node()}", + ) + return client_info + + def run(self): + while not self._exit_flag.is_set(): + try: + msg, response_type, response_callback_queue = self._requests_to_send.get( + timeout=0.1 + ) + self._socket.send_multipart( + [ + bytes(msg._pb.DESCRIPTOR.full_name, "utf-8"), + msg.__class__.serialize(msg), + ] + ) + except queue.Empty: + # No requests to send, so we can + continue + # TODO: Deal with timeout + resp = self._socket.recv_multipart() + resp_deserialized = response_type.deserialize(resp[1]) + response_callback_queue.put(resp_deserialized) + + def stop(self): + self._exit_flag.set() + + def _send_request_get_response( + self, + request: proto.message.Message, + expected_response: proto.message.Message, + timeout: float, + ): + response_queue = queue.Queue(maxsize=1) + self._requests_to_send.put((request, expected_response, response_queue)) + try: + return response_queue.get(timeout=timeout) + except queue.Empty: + raise blueye.protocol.exceptions.ResponseTimeout( + "No response received from drone before timeout" + ) + + def ping(self, timeout: float) -> blueye.protocol.PingRep: + request = blueye.protocol.PingReq() + return self._send_request_get_response(request, blueye.protocol.PingRep, timeout) + + def get_camera_parameters( + self, camera: blueye.protocol.Camera, timeout: float = 0.05 + ) -> blueye.protocol.CameraParameters: + request = blueye.protocol.GetCameraParametersReq(camera=camera) + response = self._send_request_get_response( + request, blueye.protocol.GetCameraParametersRep, timeout + ) + return response.camera_parameters + + def set_camera_parameters( + self, + parameters: blueye.protocol.CameraParameters, + timeout: float = 0.05, + ): + request = blueye.protocol.SetCameraParametersReq(camera_parameters=parameters) + return self._send_request_get_response( + request, blueye.protocol.SetCameraParametersRep, timeout + ) + + def get_overlay_parameters(self, timeout: float = 0.05) -> blueye.protocol.OverlayParameters: + request = blueye.protocol.GetOverlayParametersReq() + response = self._send_request_get_response( + request, blueye.protocol.GetOverlayParametersRep, timeout + ) + return response.overlay_parameters + + def set_overlay_parameters( + self, parameters: blueye.protocol.OverlayParameters, timeout: float = 0.05 + ): + request = blueye.protocol.SetOverlayParametersReq(overlay_parameters=parameters) + return self._send_request_get_response( + request, blueye.protocol.SetOverlayParametersRep, timeout + ) + + def sync_time(self, time: int, timeout: float = 0.05): + request = blueye.protocol.SyncTimeReq( + time={"unix_timestamp": {"seconds": time, "nanos": 0}} + ) + return self._send_request_get_response(request, blueye.protocol.SyncTimeRep, timeout) + + def connect_client( + self, client_info: blueye.protocol.ClientInfo = None, timeout: float = 0.05 + ) -> blueye.protocol.ConnectClientRep: + client = client_info or self._get_client_info() + request = blueye.protocol.ConnectClientReq(client_info=client) + return self._send_request_get_response(request, blueye.protocol.ConnectClientRep, timeout) + + def disconnect_client( + self, client_id: int, timeout: float = 0.05 + ) -> blueye.protocol.DisconnectClientRep: + request = blueye.protocol.DisconnectClientReq(client_id=client_id) + return self._send_request_get_response( + request, blueye.protocol.DisconnectClientRep, timeout + ) + + def set_telemetry_msg_publish_frequency( + self, msg: proto.message.Message | str, frequency: float, timeout: float = 0.05 + ) -> blueye.protocol.SetPubFrequencyRep: + message_type = ( + msg.meta.full_name.replace("blueye.protocol.", "") + if type(msg) in [proto.message.Message, proto.message.MessageMeta] + else msg.replace("blueye.protocol.", "") + ) + request = blueye.protocol.SetPubFrequencyReq( + message_type=message_type, + frequency=frequency, + ) + return self._send_request_get_response(request, blueye.protocol.SetPubFrequencyRep, timeout) diff --git a/blueye/sdk/constants.py b/blueye/sdk/constants.py index a06f31f9..25445f04 100644 --- a/blueye/sdk/constants.py +++ b/blueye/sdk/constants.py @@ -5,9 +5,9 @@ class WaterDensities: """ - Various typical densities for salt water (in grams/liter) + Various typical densities for salt water (in kilograms/liter) """ - fresh = 997 - brackish = 1011 - salty = 1025 + fresh = 0.997 + brackish = 1.011 + salty = 1.025 diff --git a/blueye/sdk/drone.py b/blueye/sdk/drone.py index 6787604d..72bfa4d6 100755 --- a/blueye/sdk/drone.py +++ b/blueye/sdk/drone.py @@ -1,86 +1,55 @@ #!/usr/bin/env python3 -import socket -import threading +from __future__ import annotations + import time -import warnings from json import JSONDecodeError +from typing import Callable, Dict, List, Optional +import blueye.protocol +import proto import requests -from blueye.protocol import TcpClient, UdpClient -from blueye.protocol.exceptions import ( - MismatchedReply, - NoConnectionToDrone, - ResponseTimeout, -) from packaging import version +from .battery import Battery from .camera import Camera +from .connection import CtrlClient, ReqRepClient, TelemetryClient, WatchdogPublisher from .constants import WaterDensities from .logs import Logs from .motion import Motion -class _DroneStateWatcher(threading.Thread): - """Subscribes to UDP messages from the drone and stores the latest data""" - - def __init__(self, ip: str = "192.168.1.101", udp_timeout: float = 3): - threading.Thread.__init__(self) - self._ip = ip - self._udp_timeout = udp_timeout - self._general_state = None - self._general_state_received = threading.Event() - self._calibration_state = None - self._calibration_state_received = threading.Event() - self._udp_client = UdpClient(drone_ip=self._ip) - self._exit_flag = threading.Event() - self.daemon = True - - @property - def general_state(self) -> dict: - if not self._general_state_received.wait(timeout=self._udp_timeout): - raise TimeoutError("No state message received from drone") - return self._general_state +class Config: + def __init__(self, parent_drone: "Drone"): + self._parent_drone = parent_drone + self._water_density = WaterDensities.salty @property - def calibration_state(self) -> dict: - if not self._calibration_state_received.wait(timeout=self._udp_timeout): - raise TimeoutError("No state message received from drone") - return self._calibration_state - - def run(self): - while not self._exit_flag.is_set(): - data_packet = self._udp_client.get_data_dict() - if data_packet["command_type"] == 1: - self._general_state = data_packet - self._general_state_received.set() - elif data_packet["command_type"] == 2: - self._calibration_state = data_packet - self._calibration_state_received.set() - - def stop(self): - self._exit_flag.set() - + def water_density(self): + """Get or set the current water density for increased pressure sensor accuracy -class SlaveModeWarning(UserWarning): - """Raised when trying to perform action not possible in slave mode""" + Older software versions will assume a water density of 1.025 kilograms per liter. + The WaterDensities class contains typical densities for salty-, brackish-, and fresh water + (these are the same values that the Blueye app uses). + """ + return self._water_density -class _SlaveTcpClient: - """A dummy TCP client that warns you if you use any of its functions""" + @water_density.setter + def water_density(self, density: float): + self._water_density = density + self._parent_drone._ctrl_client.set_water_density(density) - def __getattr__(self, name): - def method(*args): - warnings.warn( - f"Unable to call {name}{args} with client in slave mode", - SlaveModeWarning, - stacklevel=2, - ) + def set_drone_time(self, time: int): + """Set the system for the drone - return method + This method is used to set the system time for the drone. The argument `time` is expected to + be a Unix timestamp (ie. the number of seconds since the epoch). + """ + self._parent_drone._req_rep_client.sync_time(time) -class _NoConnectionTcpClient: - """A TCP client that raises a ConnectionError if you use any of its functions""" +class _NoConnectionClient: + """A client that raises a ConnectionError if you use any of its functions""" def __getattr__(self, name): def method(*args, **kwargs): @@ -92,71 +61,125 @@ def method(*args, **kwargs): return method -class Config: +class Telemetry: def __init__(self, parent_drone: "Drone"): self._parent_drone = parent_drone - self._water_density = WaterDensities.salty - @property - def water_density(self): - """Get or set the current water density for increased pressure sensor accuracy + def set_msg_publish_frequency(self, msg: proto.message.Message, frequency: float): + """Set the publishing frequency of a specific telemetry message - Setting the water density is only supported on drones with software version 1.5 or higher. - Older software versions will assume a water density of 1025 grams per liter. + Raises a RuntimeError if the drone fails to set the frequency. Possible causes could be a + frequency outside the valid range, or an incorrect message type. + + *Arguments*: + + * msg (proto.message.Message): The message to set the frequency of. Needs to be one of the + messages in blueye.protocol that end in Tel, eg. + blueye.protocol.DepthTel + * frequency (float): The frequency in Hz. Valid range is (0 .. 100). - The WaterDensities class contains typical densities for salty-, brackish-, and fresh water - (these are the same values that the Blueye app uses). """ - return self._water_density + resp = self._parent_drone._req_rep_client.set_telemetry_msg_publish_frequency( + msg, frequency + ) + if not resp.success: + raise RuntimeError("Could not set telemetry message frequency") - @water_density.setter - def water_density(self, density: int): - self._parent_drone._verify_required_blunux_version("1.5") - self._water_density = density - self._parent_drone._tcp_client.set_water_density(density) + def add_msg_callback( + self, + msg_filter: List[proto.message.Message], + callback: Callable[[str, proto.message.Message], None], + raw: bool = False, + ) -> str: + """Register a telemetry message callback - def set_drone_time(self, time: int): - """Set the system for the drone + The callback is called each time a message of the type is received + + *Arguments*: + + * msg_filter: A list of message types to register the callback for. + Eg. `[blueye.protocol.DepthTel, blueye.protocol.Imu1Tel]`. If the list is + empty the callback will be registered for all message types + * callback: The callback function. It should be minimal and return as fast as possible to + not block the telemetry communication. It is called with two arguments, the + message type name and the message object + * raw: Pass the raw data instead of the deserialized message to the callback function + + *Returns*: + + * uuid: Callback id. Can be used to remove callback in the future + + """ + uuid_hex = self._parent_drone._telemetry_watcher.add_callback(msg_filter, callback, raw=raw) + return uuid_hex + + def remove_msg_callback(self, callback_id: str) -> Optional[str]: + """Remove a telemetry message callback + + *Arguments*: + + * callback_id: The callback id - This method is used to set the system time for the drone. The argument `time` is expected to - be a Unix timestamp (ie. the number of seconds since the epoch). """ - self._parent_drone._tcp_client.set_system_time(time) + self._parent_drone._telemetry_watcher.remove_callback(callback_id) + + def get( + self, msg_type: proto.message.Message, deserialize=True + ) -> Optional[proto.message.Message | bytes]: + """Get the latest telemetry message of the specified type + + *Arguments*: + + + * msg_type: The message type to get. Eg. blueye.protocol.DepthTel + * deserialize: If True, the message will be deserialized before being returned. If False, + the raw bytes will be returned. + + *Returns*: + + * The latest message of the specified type, or None if no message has been received yet + + """ + try: + msg = self._parent_drone._telemetry_watcher.get(msg_type) + except KeyError: + return None + if deserialize: + return msg_type.deserialize(msg) + else: + return msg class Drone: """A class providing an interface to a Blueye drone's functions - Automatically connects to the drone using the default ip and port when instantiated, this - behaviour can be disabled by setting `autoConnect=False`. - - The drone only supports one client controlling it at a time, but if you pass - `slaveModeEnabled=True` you will still be able to receive data from the drone. + Automatically connects to the drone using the default ip when instantiated, this behaviour can + be disabled by setting `auto_connect=False`. """ def __init__( self, ip="192.168.1.101", - tcpPort=2011, - autoConnect=True, - slaveModeEnabled=False, - udpTimeout=3, + auto_connect=True, + timeout=3, + disconnect_other_clients=False, ): self._ip = ip - self._port = tcpPort - self._slave_mode_enabled = slaveModeEnabled - if slaveModeEnabled: - self._tcp_client = _SlaveTcpClient() - else: - self._tcp_client = _NoConnectionTcpClient() - self._state_watcher = _DroneStateWatcher(ip=self._ip, udp_timeout=udpTimeout) - self.camera = Camera(self) + self.camera = Camera(self, is_guestport_camera=False) self.motion = Motion(self) self.logs = Logs(self) self.config = Config(self) - - if autoConnect is True: - self.connect(timeout=3) + self.battery = Battery(self) + self.telemetry = Telemetry(self) + self.connected = False + self.client_id: int = None + self.in_control: bool = False + self._watchdog_publisher = _NoConnectionClient() + self._telemetry_watcher = _NoConnectionClient() + self._req_rep_client = _NoConnectionClient() + self._ctrl_client = _NoConnectionClient() + if auto_connect is True: + self.connect(timeout=timeout, disconnect_other_clients=disconnect_other_clients) def _verify_required_blunux_version(self, requirement: str): """Verify that Blunux version is higher than requirement @@ -166,36 +189,25 @@ def _verify_required_blunux_version(self, requirement: str): Raises a RuntimeError if the Blunux version of the connected drone does not match or exceed the requirement. """ - - if not self.connection_established: - raise ConnectionError( - "The connection to the drone is not established, try calling the connect method " - "before retrying" - ) if version.parse(self.software_version_short) < version.parse(requirement): raise RuntimeError( f"Blunux version of connected drone is {self.software_version_short}. Version " f"{requirement} or higher is required." ) - @property - def connection_established(self): - if isinstance(self._tcp_client, _NoConnectionTcpClient): - return False - else: - return True - - def _update_drone_info(self): + def _update_drone_info(self, timeout: float = 3): """Request and store information about the connected drone""" try: - response = requests.get(f"http://{self._ip}/diagnostics/drone_info", timeout=3).json() + response = requests.get( + f"http://{self._ip}/diagnostics/drone_info", timeout=timeout + ).json() except ( requests.ConnectTimeout, requests.ReadTimeout, requests.ConnectionError, JSONDecodeError, - ): - raise ConnectionError("Could not establish connection with drone") + ) as e: + raise ConnectionError("Could not establish connection with drone") from e try: self.features = list(filter(None, response["features"].split(","))) except KeyError: @@ -206,55 +218,12 @@ def _update_drone_info(self): self.serial_number = response["serial_number"] self.uuid = response["hardware_id"] - @staticmethod - def _wait_for_udp_communication(timeout: float, ip: str = "192.168.1.101"): - """Simple helper for waiting for drone to come online - - Raises ConnectionError if no connection is established in the specified timeout. - """ - temp_udp_client = UdpClient(drone_ip=ip) - temp_udp_client._sock.settimeout(timeout) - try: - temp_udp_client.get_data_dict() - except socket.timeout as e: - raise ConnectionError("Could not establish connection with drone") from e - - def _connect_to_tcp_socket(self): - try: - self._tcp_client.connect() - except NoConnectionToDrone: - raise ConnectionError("Could not establish connection with drone") - - def _start_watchdog(self): - """Starts the thread for petting the watchdog - - _connect_to_tcp_socket() must be called first""" - try: - self._tcp_client.start() - except RuntimeError: - # Ignore multiple starts - pass - - def _clean_up_tcp_client(self): - """Stops the watchdog thread and closes the TCP socket""" - self._tcp_client.stop() - self._tcp_client._sock.close() - self._tcp_client = _NoConnectionTcpClient() - - def _start_state_watcher_thread(self): - try: - self._state_watcher.start() - except RuntimeError: - # Ignore multiple starts - pass - - def _create_temporary_tcp_client(self): - temp_tcp_client = TcpClient() - temp_tcp_client.connect() - temp_tcp_client.stop() - temp_tcp_client._sock.close() - - def connect(self, timeout: float = None): + def connect( + self, + client_info: blueye.protocol.ClientInfo = None, + timeout: float = 4, + disconnect_other_clients: bool = False, + ): """Start receiving telemetry info from the drone, and publishing watchdog messages When watchdog message are published the thrusters are armed, to stop the drone from moving @@ -262,135 +231,174 @@ def connect(self, timeout: float = None): - *timeout* (float): Seconds to wait for connection """ + # TODO: Deal with exceptions + self._update_drone_info(timeout=timeout) + self._verify_required_blunux_version("3.2") + + self._telemetry_watcher = TelemetryClient(self) + self._ctrl_client = CtrlClient(self) + self._watchdog_publisher = WatchdogPublisher(self) + self._req_rep_client = ReqRepClient(self) + + self._telemetry_watcher.start() + self._req_rep_client.start() + self._ctrl_client.start() + self._watchdog_publisher.start() + + self.ping() + connect_resp = self._req_rep_client.connect_client(client_info=client_info) + self.client_id = connect_resp.client_id + self.in_control = connect_resp.client_id == connect_resp.client_id_in_control + self.connected = True + if disconnect_other_clients and not self.in_control: + self.take_control() + if self.in_control: + # The drone runs from a read-only filesystem, and as such does not keep any state, + # therefore when we connect to it we should send the current time + self.config.set_drone_time(int(time.time())) + self.motion.send_thruster_setpoint(0, 0, 0, 0) - self._update_drone_info() - if version.parse(self.software_version_short) >= version.parse("3.0"): - # Blunux 3.0 requires a TCP message before enabling UDP communication - self._create_temporary_tcp_client() + def disconnect(self): + """Disconnects the connection, allowing another client to take control of the drone""" + try: + self._req_rep_client.disconnect_client(self.client_id) + except blueye.protocol.exceptions.ResponseTimeout: + # If there's no response the connection is likely already closed, so we can just + # continue to stop threads and disconnect + pass + self._watchdog_publisher.stop() + self._telemetry_watcher.stop() + self._req_rep_client.stop() + self._ctrl_client.stop() - self._wait_for_udp_communication(timeout, self._ip) - self._start_state_watcher_thread() - if self._slave_mode_enabled: - # No need to touch the TCP stuff if we're in slave mode so we return early - return + self._watchdog_publisher = _NoConnectionClient() + self._telemetry_watcher = _NoConnectionClient() + self._req_rep_client = _NoConnectionClient() + self._ctrl_client = _NoConnectionClient() - if not self.connection_established: - self._tcp_client = TcpClient(ip=self._ip, port=self._port, autoConnect=False) - self._connect_to_tcp_socket() + self.connected = False - try: - # The drone runs from a read-only filesystem, and as such does not keep any state, - # therefore when we connect to it we should send the current time - self.config.set_drone_time(int(time.time())) + @property + def connected_clients(self) -> Optional[List[blueye.protocol.ConnectedClient]]: + """Get a list of connected clients""" + clients_tel = self.telemetry.get(blueye.protocol.ConnectedClientsTel) + if clients_tel is None: + return None + else: + return list(clients_tel.connected_clients) - self.ping() - self.motion.send_thruster_setpoint(0, 0, 0, 0) + @property + def client_in_control(self) -> Optional[int]: + """Get the client id of the client in control of the drone""" + clients_tel = self.telemetry.get(blueye.protocol.ConnectedClientsTel) + if clients_tel is None: + return None + else: + return clients_tel.client_id_in_control - self._start_watchdog() - except ResponseTimeout as e: - self._clean_up_tcp_client() - raise ConnectionError( - f"Found drone at {self._ip} but was unable to take control of it. " - "Is there another client connected?" - ) from e - except MismatchedReply: - # The connection is out of sync, likely due to a previous connection being - # disconnected mid-transfer. Re-instantiating the connection should solve the issue - self._clean_up_tcp_client() - self.connect(timeout) - except BrokenPipeError: - # Have lost connection to drone, need to reestablish TCP client - self._clean_up_tcp_client() - self.connect(timeout) + def take_control(self, timeout=1): + """Take control of the drone, disconnecting other clients - def disconnect(self): - """Disconnects the TCP connection, allowing another client to take control of the drone""" - if self.connection_established and not self._slave_mode_enabled: - self._clean_up_tcp_client() + Will disconnect other clients until the client is in control of the drone. + Raises a RuntimeError if the client could not take control of the drone in the given time. + """ + start_time = time.time() + client_in_control = self.client_in_control + while self.client_id != client_in_control: + if time.time() - start_time > timeout: + raise RuntimeError("Could not take control of the drone in the given time") + resp = self._req_rep_client.disconnect_client(client_in_control) + client_in_control = resp.client_id_in_control + self.in_control = True @property - def lights(self) -> int: - """Get or set the brightness of the bottom canister lights + def lights(self) -> Optional[float]: + """Get or set the intensity of the drone lights *Arguments*: - * brightness (int): Set the brightness of the bottom canister LED's in the range <0, 255> + * brightness (float): Set the intensity of the drone light (0..1) *Returns*: - * brightness (int): The brightness of the bottom canister LED's in the range <0, 255> + * brightness (float): The intensity of the drone light (0..1) """ - state = self._state_watcher.general_state - return state["lights_upper"] + return self.telemetry.get(blueye.protocol.LightsTel).lights.value @lights.setter - def lights(self, brightness: int): - try: - self._tcp_client.set_lights(brightness, 0) - except ValueError as e: - raise ValueError("Error occured while trying to set lights to: " f"{brightness}") from e + def lights(self, brightness: float): + if not 0 <= brightness <= 1: + raise ValueError("Error occured while trying to set lights to: " f"{brightness}") + self._ctrl_client.set_lights(brightness) @property - def depth(self) -> int: - """Get the current depth in millimeters + def depth(self) -> Optional[float]: + """Get the current depth in meters *Returns*: - * depth (int): The depth in millimeters of water column. + * depth (float): The depth in meters of water column. """ - return self._state_watcher.general_state["depth"] + depth_tel = self.telemetry.get(blueye.protocol.DepthTel) + if depth_tel is None: + return None + else: + return depth_tel.depth.value @property - def pose(self) -> dict: + def pose(self) -> Optional[dict]: """Get the current orientation of the drone *Returns*: * pose (dict): Dictionary with roll, pitch, and yaw in degrees, from 0 to 359. """ + attitude_tel = self.telemetry.get(blueye.protocol.AttitudeTel) + if attitude_tel is None: + return None + attitude = attitude_tel.attitude pose = { - "roll": (self._state_watcher.general_state["roll"] + 360) % 360, - "pitch": (self._state_watcher.general_state["pitch"] + 360) % 360, - "yaw": (self._state_watcher.general_state["yaw"] + 360) % 360, + "roll": (attitude.roll + 360) % 360, + "pitch": (attitude.pitch + 360) % 360, + "yaw": (attitude.yaw + 360) % 360, } return pose @property - def battery_state_of_charge(self) -> int: - """Get the battery state of charge - - *Returns*: - - * state_of_charge (int): Current state of charge of the drone battery in percent, from 0 to 100 - """ - return self._state_watcher.general_state["battery_state_of_charge_rel"] - - @property - def error_flags(self) -> int: + def error_flags(self) -> Optional[Dict[str, bool]]: """Get the error flags *Returns*: - * error_flags (int): The error flags as int + * error_flags (dict): The error flags as bools in a dictionary """ - return self._state_watcher.general_state["error_flags"] + error_flags_tel = self.telemetry.get(blueye.protocol.ErrorFlagsTel) + if error_flags_tel is None: + return None + error_flags_msg = error_flags_tel.error_flags + error_flags = {} + possible_flags = [attr for attr in dir(error_flags_msg) if not attr.startswith("__")] + for flag in possible_flags: + error_flags[flag] = getattr(error_flags_msg, flag) + return error_flags @property - def active_video_streams(self) -> int: + def active_video_streams(self) -> Optional[Dict[str, int]]: """Get the number of currently active connections to the video stream Every client connected to the RTSP stream (does not matter if it's directly from GStreamer, or from the Blueye app) counts as one connection. - Requires Blunux version 1.5.33 or newer. """ + n_streamers_msg_tel = self.telemetry.get(blueye.protocol.NStreamersTel) + if n_streamers_msg_tel is None: + return None + n_streamers_msg = n_streamers_msg_tel.n_streamers + return {"main": n_streamers_msg.main, "guestport": n_streamers_msg.guestport} - self._verify_required_blunux_version("1.5.33") - SPECTATORS_MASK = 0x000000FF00000000 - SPECTATORS_OFFSET = 32 - debug_flags = self._state_watcher._general_state["debug_flags"] - return (debug_flags & SPECTATORS_MASK) >> SPECTATORS_OFFSET + def ping(self, timeout: float = 1.0): + """Ping drone - def ping(self): - """Ping drone, an exception is thrown by TcpClient if drone does not answer""" - self._tcp_client.ping() + Raises a ResponseTimeout exception if the drone does not respond within the timeout period. + """ + self._req_rep_client.ping(timeout) diff --git a/blueye/sdk/motion.py b/blueye/sdk/motion.py index 7d1c5b21..f7cef146 100644 --- a/blueye/sdk/motion.py +++ b/blueye/sdk/motion.py @@ -1,4 +1,7 @@ import threading +from typing import Optional + +import blueye.protocol class Motion: @@ -11,7 +14,6 @@ class Motion: def __init__(self, parent_drone): self._parent_drone = parent_drone - self._state_watcher = parent_drone._state_watcher self.thruster_lock = threading.Lock() self._current_thruster_setpoints = {"surge": 0, "sway": 0, "heave": 0, "yaw": 0} self._current_boost_setpoints = {"slow": 0, "boost": 0} @@ -20,8 +22,8 @@ def __init__(self, parent_drone): def current_thruster_setpoints(self): """Returns the current setpoints for the thrusters - We maintain this state in the SDK since the drone does not report back it's current - setpoint. + We maintain this state in the SDK since the drone expects to receive all of the setpoints at + once. For setting the setpoints you should use the dedicated properties/functions for that, trying to set them directly with this property will raise an AttributeError. @@ -40,7 +42,7 @@ def _send_motion_input_message(self): """Small helper function for building argument list to motion_input command""" thruster_setpoints = self.current_thruster_setpoints.values() boost_setpoints = self._current_boost_setpoints.values() - self._parent_drone._tcp_client.motion_input(*thruster_setpoints, *boost_setpoints) + self._parent_drone._ctrl_client.set_motion_input(*thruster_setpoints, *boost_setpoints) @property def surge(self) -> float: @@ -171,7 +173,7 @@ def slow(self, slow_gain: float): self._send_motion_input_message() @property - def auto_depth_active(self) -> bool: + def auto_depth_active(self) -> Optional[bool]: """Enable or disable the auto depth control mode When auto depth is active, input for the heave direction to the thruster_setpoint function @@ -181,32 +183,24 @@ def auto_depth_active(self) -> bool: *Arguments*: - * active (bool): Activate auto depth mode if active is true, de-activate if false + * Enable (bool): Activate auto depth mode if true, de-activate if false *Returns*: - * active (bool): Returns true if auto depth is active, false if it is not active + * Auto depth state (bool): True if auto depth is active, false if not """ - AUTO_DEPTH_MODE = 3 - AUTO_HEADING_AND_AUTO_DEPTH_MODE = 9 - state = self._state_watcher.general_state - if ( - state["control_mode"] is AUTO_DEPTH_MODE - or state["control_mode"] is AUTO_HEADING_AND_AUTO_DEPTH_MODE - ): - return True + control_mode_tel = self._parent_drone.telemetry.get(blueye.protocol.ControlModeTel) + if control_mode_tel is None: + return None else: - return False + return control_mode_tel.state.auto_depth @auto_depth_active.setter - def auto_depth_active(self, active: bool): - if active: - self._parent_drone._tcp_client.auto_depth_on() - else: - self._parent_drone._tcp_client.auto_depth_off() + def auto_depth_active(self, enable: bool): + self._parent_drone._ctrl_client.set_auto_depth_state(enable) @property - def auto_heading_active(self) -> bool: + def auto_heading_active(self) -> Optional[bool]: """Enable or disable the auto heading control mode When auto heading is active, input for the yaw direction to the thruster_setpoint function @@ -216,26 +210,18 @@ def auto_heading_active(self) -> bool: *Arguments*: - * active (bool): Activate auto heading mode if active is true, de-activate if false + * Enable (bool): Activate auto heading mode if true, de-activate if false *Returns*: - * active (bool): Returns true if auto heading mode is active, false if it is not active + * Auto heading state (bool): True if auto heading mode is active, false if not """ - AUTO_HEADING_MODE = 7 - AUTO_HEADING_AND_AUTO_DEPTH_MODE = 9 - state = self._state_watcher.general_state - if ( - state["control_mode"] is AUTO_HEADING_MODE - or state["control_mode"] is AUTO_HEADING_AND_AUTO_DEPTH_MODE - ): - return True + control_mode_tel = self._parent_drone.telemetry.get(blueye.protocol.ControlModeTel) + if control_mode_tel is None: + return None else: - return False + return control_mode_tel.state.auto_heading @auto_heading_active.setter - def auto_heading_active(self, active: bool): - if active: - self._parent_drone._tcp_client.auto_heading_on() - else: - self._parent_drone._tcp_client.auto_heading_off() + def auto_heading_active(self, enable: bool): + self._parent_drone._ctrl_client.set_auto_heading_state(enable) diff --git a/docs/configuration.md b/docs/configuration.md index b34a6f94..d106b722 100644 --- a/docs/configuration.md +++ b/docs/configuration.md @@ -37,16 +37,16 @@ from blueye.sdk import Drone, WaterDensities myDrone = Drone() # Salt water -myDrone.config.water_density = WaterDensities.salty # 1025 g/L +myDrone.config.water_density = WaterDensities.salty # 1.025 kg/L # Brackish water -myDrone.config.water_density = WaterDensities.brackish # 1011 g/L +myDrone.config.water_density = WaterDensities.brackish # 1.011 kg/L # Fresh water -myDrone.config.water_density = WaterDensities.fresh # 997 g/L +myDrone.config.water_density = WaterDensities.fresh # 0.997 kg/L # Can also be set to arbitrary values -myDrone.config.water_density = 1234 +myDrone.config.water_density = 1.234 ``` ### Configure camera parameters diff --git a/docs/migrating-to-v2.md b/docs/migrating-to-v2.md new file mode 100644 index 00000000..170d574e --- /dev/null +++ b/docs/migrating-to-v2.md @@ -0,0 +1,143 @@ +# Upgrading to v2 +Version 2 of the Blueye SDK (unfortunately) introduces a few breaking changes. The following guide outlines what has changed, and what you need to change to be compatible with the new version. + +## Change of underlying communication protocol +The underlying communications protocol has been changed from UDP/TCP to protobuf messages sent over ZeroMQ sockets. This means that the drone now supports multiple simultaneous clients, and as such, the 'slave-mode' functionality is no longer necessary and has been removed. + +Another added benefit is the ability to list and disconnect other clients connected to the drone. + +## Requirement on Blunux v3.2 or newer +The SDK now requires v3.2 or newer of the Blunux operating system to be installed on the drone to able to connect to it. + +## Dropped support Python 3.7 +One or several of our subdependencies has dropped support for 3.7, and in an effort to reduce the maintenance burden we decided to drop support for 3.7 when adding support for 3.11. + +## New range for lights control +Previously the valid range for the `lights` property was an `int` between 0 and 255, it has now been updated to a `float` in the range 0 to 1. + +```python +# Previously +my_drone.lights = 64 + +# Updated +my_drone.lights = 0.25 +``` + +## Error flags are a dictionary of bools +Error flags are now represented as a dictionary of bools instead of bitflags in an `int`. See the [ErrorFlags message in blueye.protocol](https://github.com/BluEye-Robotics/blueye.protocol/blob/bec6c11dfbe51457fd58646111d8e9ce9ba8a043/blueye/protocol/types/message_formats.py#L1511) for an overview of the possible error states. + +```python +# Previously +depth_read_error: bool = my_drone.error_flags & (1 << 2) + +# Updated +depth_read_error: bool = my_drone.error_flags["depth_read"] +``` + +## Changed return type in `active_video_streams` property +The `active_video_streams` property has been modified to return a dictionary containing `"main"` and `"guestport"` as keys. This change provides the option to be able to read the number of active video streams for both the main camera and (optinally) a guestport camera. +```python +# Previously +streams_on_main_camera = my_drone.active_video_streams + +# Updated +streams_on_main_camera = my_drone.active_video_streams["main"] +``` + +## Water Density Unit changed from g/L to kg/L +The unit for water density has been updated from grams per liter (g/L) to kilograms per liter (kg/L). Make sure to adjust your calculations or conversions accordingly. + +```python +# Previously +density: int = my_drone.config.water_density +print(density) # Will print 1025 + +# Updated +density: float = my_drone.config.water_density +print(density) # Will print 1.025 +``` + +## Camera Stabilization uses on/off instead of toggle +The camera stabilization functionality now uses separate methods for enabling and disabling instead of a single toggle method. Update your code to use the appropriate methods based on the desired behavior. + +```python +# Previously +my_drone.camera.toggle_stabilization() +print(my_drone.camera.stabilization_enabled) + +# Updated +my_drone.camera.stabilization_enabled = True +print(my_drone.camera.stabilization_enabled) +``` + +## `tilt_speed` has been renamed to `tilt_velocity` +The function tilt_speed has been renamed to tilt_velocity to better reflect its purpose and usage. Update your code to use the new function name. +```python +# Previously +my_drone.camera.tilt.set_speed(1) + +# Updated +my_drone.camera.tilt.set_velocity(1) +``` + +## New subclass for battery data +The `battery_state_of_charge` property has been moved to a subclass on the `Drone`-object. In addition the state of charge range for the battery has been adjusted to a scale of 0 to 1, instead of the previous 0 to 100 range. + +```python +# Previously +state_of_charge: int = my_drone.battery_state_of_charge + +# Updated +state_of_charge: float = my_drone.battery.state_of_charge +``` + +## Custom Overlay Classes Replaced with Enums +Custom overlay classes have been replaced with enums defined in the `blueye.protocol` package. Make sure to update your code to use the new enums for overlay functionality. + +```python +# Previously +from blueye.sdk import DepthUnitOverlay, FontSizeOverlay, LogoOverlay, TemperatureUnitOverlay + +my_drone.camera.overlay.depth_unit = DepthUnitOverlay.METERS +my_drone.camera.overlay.font_size = FontSizeOverlay.PX15 +my_drone.camera.overlay.logo = LogoOverlay.BLUEYE +my_drone.camera.overlay.temperature_unit = TemperatureUnitOverlay.CELSIUS + +# Updated +import blueye.protocol as bp + +my_drone.camera.overlay.depth_unit = bp.DepthUnit.DEPTH_UNIT_METERS +my_drone.camera.overlay.font_size = bp.FontSize.FONT_SIZE_PX15 +my_drone.camera.overlay.logo = bp.LogoType.LOGO_TYPE_DEFAULT +my_drone.camera.overlay.temperature_unit = bp.TemperatureUnit.TEMPERATURE_UNIT_CELSIUS +``` + +## Telemetry properties will now return `None` if no data exists +Properties that read telemetry data, such as `lights`, `tilt_angle`, `depth`, `pose`, `battery_state_of_charge`, `error_flags`, `active_video_streams`, `auto_depth_active`, and `auto_heading_active`, will now return `None` if no telemetry message has been received from the drone. Previously if a UDP message had not arrived, a `KeyError` exception would have been raised. + +```python +# Previously +print(my_drone.pose) # If no state message has been received yet this could throw a KeyError + +# Updated +print(my_drone.pose) # This will now print "None" if no AttitudeTel-message has been received. +``` + +## New initialization parameters to the `Drone` object +The `AutoConnect` parameter has been renamed to `auto_connect` for consistency and clarity. +```python +# Previously +my_drone = Drone(AutoConnect = False) + +# Updated +my_drone = Drone(auto_connect = False) +``` + +The `udpTimeout` parameter has been renamed to `timeout` for consistency and clarity. +```python +# Previously +my_drone = Drone(udpTimeout = 5) + +# Updated +my_drone = Drone(timeout = 5) +``` diff --git a/docs/protobuf-protocol.md b/docs/protobuf-protocol.md new file mode 100644 index 00000000..8df7b655 --- /dev/null +++ b/docs/protobuf-protocol.md @@ -0,0 +1,2974 @@ +# Protocol Documentation +## control.proto +Control + +These messages define control messages accepted by the Blueye drone. + + + + +### ActivateGuestPortsCtrl +Activated the guest port power + + + + + + + + +### AutoAltitudeCtrl +Issue a command to set auto altitude to a desired state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [AutoAltitudeState](#blueye-protocol-AutoAltitudeState) | | State of the altitude controller | + + + + + + + + +### AutoDepthCtrl +Issue a command to set auto depth to a desired state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [AutoDepthState](#blueye-protocol-AutoDepthState) | | State of the depth controller | + + + + + + + + +### AutoHeadingCtrl +Issue a command to set auto heading to a desired state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [AutoHeadingState](#blueye-protocol-AutoHeadingState) | | State of the heading controller | + + + + + + + + +### CancelCalibrationCtrl +Issue a command to cancel compass calibration. + + + + + + + + +### DeactivateGuestPortsCtrl +Deactivate the guest port power + + + + + + + + +### FinishCalibrationCtrl +Issue a command to finish compass calibration. + + + + + + + + +### GenericServoCtrl +Issue a command to set a generic servo value. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| servo | [GenericServo](#blueye-protocol-GenericServo) | | Message with the desired servo value. | + + + + + + + + +### GripperCtrl +Issue a command to control the gripper. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| gripper_velocities | [GripperVelocities](#blueye-protocol-GripperVelocities) | | The desired gripping and rotation velocity. | + + + + + + + + +### GuestportLightsCtrl +Issue a command to set the guest port light intensity. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| lights | [Lights](#blueye-protocol-Lights) | | Message with the desired light intensity. | + + + + + + + + +### LaserCtrl +Issue a command to set the laser intensity. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| laser | [Laser](#blueye-protocol-Laser) | | Message with the desired laser intensity. | + + + + + + + + +### LightsCtrl +Issue a command to set the main light intensity. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| lights | [Lights](#blueye-protocol-Lights) | | Message with the desired light intensity. | + + + + + + + + +### MotionInputCtrl +Issue a command to move the drone in the surge, sway, heave, or yaw direction. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| motion_input | [MotionInput](#blueye-protocol-MotionInput) | | Message with the desired movement in each direction. | + + + + + + + + +### MultibeamServoCtrl +Issue a command to set multibeam servo angle. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| servo | [MultibeamServo](#blueye-protocol-MultibeamServo) | | Message with the desired servo angle. | + + + + + + + + +### PilotGPSPositionCtrl +Issue a command with the GPS position of the pilot. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| position | [LatLongPosition](#blueye-protocol-LatLongPosition) | | The GPS position of the pilot. | + + + + + + + + +### PingerConfigurationCtrl +Issue a command to set the pinger configuration. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| configuration | [PingerConfiguration](#blueye-protocol-PingerConfiguration) | | Message with the pinger configuration to set. | + + + + + + + + +### RecordCtrl +Issue a command to start video recording. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| record_on | [RecordOn](#blueye-protocol-RecordOn) | | Message specifying which cameras to record. | + + + + + + + + +### ResetOdometerCtrl +Issue a command to reset the odometer. + + + + + + + + +### ResetPositionCtrl +Issue a command to reset the position estimate. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| settings | [ResetPositionSettings](#blueye-protocol-ResetPositionSettings) | | Reset settings. | + + + + + + + + +### RestartGuestPortsCtrl +Restart the guest ports by turning power on and off + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| restart_info | [GuestPortRestartInfo](#blueye-protocol-GuestPortRestartInfo) | | Message with information about how long to keep the guest ports off. | + + + + + + + + +### StartCalibrationCtrl +Issue a command to start compass calibration. + + + + + + + + +### StationKeepingCtrl +Issue a command to set station keeping to a desired state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [StationKeepingState](#blueye-protocol-StationKeepingState) | | State of the station keeping controller | + + + + + + + + +### SystemTimeCtrl +Issue a command to set the system time on the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| system_time | [SystemTime](#blueye-protocol-SystemTime) | | Message with the system time to set. | + + + + + + + + +### TakePictureCtrl +Issue a command to take a picture. + + + + + + + + +### TiltStabilizationCtrl +Issue a command to enable or disable tilt stabilization. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [TiltStabilizationState](#blueye-protocol-TiltStabilizationState) | | Message with the tilt stabilization state to set. | + + + + + + + + +### TiltVelocityCtrl +Issue a command to tilt the drone camera. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| velocity | [TiltVelocity](#blueye-protocol-TiltVelocity) | | Message with the desired tilt velocity (direction and speed). | + + + + + + + + +### WatchdogCtrl +Issue a watchdog message to indicate that the remote client is connected and working as expected. + +If a watchdog message is not received every second, the drone will turn off lights and other auto +functions to indicate that connection with the client has been lost. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| connection_duration | [ConnectionDuration](#blueye-protocol-ConnectionDuration) | | Message with the number of seconds the client has been connected. | +| client_id | [uint32](#uint32) | | The ID of the client, received in the ConnectClientRep response. | + + + + + + + + +### WaterDensityCtrl +Issue a command to set the water density. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| density | [WaterDensity](#blueye-protocol-WaterDensity) | | Message with the water density to set. | + + + + + + + + +### WeatherVaningCtrl +Issue a command to set station keeping with weather vaning to a desired state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [WeatherVaningState](#blueye-protocol-WeatherVaningState) | | State of the weather vaning controller | + + + + + + + + + + + + + + + + +

Top

+ +## message_formats.proto +Common messages + +These are used for logging as well as building requests and responses. + + + + +### Altitude +Drone altitude over seabed, typically obtained from a DVL. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Drone altitude over seabed (m) | +| is_valid | [bool](#bool) | | If altitude is valid or not | + + + + + + + + +### Attitude +The attitude of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| roll | [float](#float) | | Roll angle (-180°..180°) | +| pitch | [float](#float) | | Pitch angle (-180°..180°) | +| yaw | [float](#float) | | Yaw angle (-180°..180°) | + + + + + + + + +### AutoAltitudeState +Auto altitude state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| enabled | [bool](#bool) | | If auto altitude is enabled | + + + + + + + + +### AutoDepthState +Auto depth state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| enabled | [bool](#bool) | | If auto depth is enabled | + + + + + + + + +### AutoHeadingState +Auto heading state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| enabled | [bool](#bool) | | If auto heading is enabled | + + + + + + + + +### Battery +Essential battery information. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| voltage | [float](#float) | | Battery voltage (V) | +| level | [float](#float) | | Battery level (0..1) | +| temperature | [float](#float) | | Battery temperature (°C) | + + + + + + + + +### BatteryBQ40Z50 +Battery information message. + +Detailed information about all aspects of the connected Blueye Smart Battery, +using the BQ40Z50 BMS. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| voltage | [BatteryBQ40Z50.Voltage](#blueye-protocol-BatteryBQ40Z50-Voltage) | | Voltage of the battery cells | +| temperature | [BatteryBQ40Z50.Temperature](#blueye-protocol-BatteryBQ40Z50-Temperature) | | Temperature of the battery cells | +| status | [BatteryBQ40Z50.BatteryStatus](#blueye-protocol-BatteryBQ40Z50-BatteryStatus) | | Battery status flags | +| current | [float](#float) | | Current (A) | +| average_current | [float](#float) | | Average current (A) | +| relative_state_of_charge | [float](#float) | | Relative state of charge (0..1) | +| absolute_state_of_charge | [float](#float) | | Absolute state of charge (0..1) | +| remaining_capacity | [float](#float) | | Remaining capacity (Ah) | +| full_charge_capacity | [float](#float) | | Full charge capacity (Ah) | +| runtime_to_empty | [uint32](#uint32) | | Runtime to empty (s) | +| average_time_to_empty | [uint32](#uint32) | | Average time to empty (s) | +| average_time_to_full | [uint32](#uint32) | | Average time to full (s) | +| time_to_full_at_current_rate | [uint32](#uint32) | | Time to fully charged at current rate (s) | +| time_to_empty_at_current_rate | [uint32](#uint32) | | Time to empty at current rate (s) | +| charging_current | [float](#float) | | Charging current (A) | +| charging_voltage | [float](#float) | | Charging voltage (V) | +| cycle_count | [uint32](#uint32) | | Number of charging cycles | +| design_capacity | [float](#float) | | Design capacity (Ah) | +| manufacture_date | [google.protobuf.Timestamp](#google-protobuf-Timestamp) | | Manufacture date | +| serial_number | [uint32](#uint32) | | Serial number | +| manufacturer_name | [string](#string) | | Manufacturer name | +| device_name | [string](#string) | | Device name | +| device_chemistry | [string](#string) | | Battery chemistry | + + + + + + + + +### BatteryBQ40Z50.BatteryStatus +Battery status from BQ40Z50 ref data sheet 0x16. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| overcharged_alarm | [bool](#bool) | | | +| terminate_charge_alarm | [bool](#bool) | | | +| over_temperature_alarm | [bool](#bool) | | | +| terminate_discharge_alarm | [bool](#bool) | | | +| remaining_capacity_alarm | [bool](#bool) | | | +| remaining_time_alarm | [bool](#bool) | | | +| initialization | [bool](#bool) | | | +| discharging_or_relax | [bool](#bool) | | | +| fully_charged | [bool](#bool) | | | +| fully_discharged | [bool](#bool) | | | +| error | [BatteryBQ40Z50.BatteryStatus.BatteryError](#blueye-protocol-BatteryBQ40Z50-BatteryStatus-BatteryError) | | Battery error codes | + + + + + + + + +### BatteryBQ40Z50.Temperature +Battery temperature. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| average | [float](#float) | | Average temperature accross cells (°C) | +| cell_1 | [float](#float) | | Cell 1 temperature (°C) | +| cell_2 | [float](#float) | | Cell 2 temperature (°C) | +| cell_3 | [float](#float) | | Cell 3 temperature (°C) | +| cell_4 | [float](#float) | | Cell 4 temperature (°C) | + + + + + + + + +### BatteryBQ40Z50.Voltage +Battery voltage levels. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| total | [float](#float) | | Battery pack voltage level (V) | +| cell_1 | [float](#float) | | Cell 1 voltage level (V) | +| cell_2 | [float](#float) | | Vell 2 voltage level (V) | +| cell_3 | [float](#float) | | Cell 3 voltage level (V) | +| cell_4 | [float](#float) | | Cell 4 voltage level (V) | + + + + + + + + +### BinlogRecord +Wrapper message for each entry in the drone telemetry logfile. + +Each entry contains the unix timestamp in UTC, the monotonic timestamp (time since boot), +and an Any message wrapping the custom Blueye message. + +See separate documentation for the logfile format for more details. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| payload | [google.protobuf.Any](#google-protobuf-Any) | | The log entry payload. | +| unix_timestamp | [google.protobuf.Timestamp](#google-protobuf-Timestamp) | | Unix timestamp in UTC. | +| clock_monotonic | [google.protobuf.Timestamp](#google-protobuf-Timestamp) | | Posix CLOCK_MONOTONIC timestamp. | + + + + + + + + +### CPUTemperature +CPU temperature. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | CPU temperature (°C) | + + + + + + + + +### CalibrationState +Compass calibration state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| status | [CalibrationState.Status](#blueye-protocol-CalibrationState-Status) | | Current calibration status | +| progress_x_positive | [float](#float) | | Progress for the positive X axis (0..1) | +| progress_x_negative | [float](#float) | | Progress for the negative X axis (0..1) | +| progress_y_positive | [float](#float) | | Progress for the positive Y axis (0..1) | +| progress_y_negative | [float](#float) | | Progress for the negative X axis (0..1) | +| progress_z_positive | [float](#float) | | Progress for the positive Z axis (0..1) | +| progress_z_negative | [float](#float) | | Progress for the negative Z axis (0..1) | +| progress_thruster | [float](#float) | | Progress for the thruster calibration (0..1) | + + + + + + + + +### CameraParameters +Camera parameters. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| h264_bitrate | [int32](#int32) | | Bitrate of the h264 stream (bit/sec) | +| mjpg_bitrate | [int32](#int32) | | Bitrate of the MJPG stream used for still pictures (bit/sec) | +| exposure | [int32](#int32) | | Shutter speed (1/10000 * s), -1 for automatic exposure | +| white_balance | [int32](#int32) | | White balance temperature (2800..9300), -1 for automatic white balance | +| hue | [int32](#int32) | | Hue (-40..40), 0 as default | +| gain | [float](#float) | | Iso gain (0..1) | +| resolution | [Resolution](#blueye-protocol-Resolution) | | Stream, recording and image resolution | +| framerate | [Framerate](#blueye-protocol-Framerate) | | Stream and recording framerate | +| camera | [Camera](#blueye-protocol-Camera) | | Which camera the parameters belong to. | + + + + + + + + +### CanisterHumidity +Canister humidity. + +Humidity measured in the top or bottom canister of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| humidity | [float](#float) | | Air humidity (%) | + + + + + + + + +### CanisterTemperature +Canister temperature. + +Temperature measured in the top or bottom canister of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| temperature | [float](#float) | | Temperature (°C) | + + + + + + + + +### ClientInfo +Information about a remote client. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| type | [string](#string) | | The type of client (such as Blueye App, Observer App, SDK, etc) | +| version | [string](#string) | | Client software version string | +| device_type | [string](#string) | | Device type, such as mobile, tablet, or computer | +| platform | [string](#string) | | Platform, such as iOS, Android, Linux, etc | +| platform_version | [string](#string) | | Platform software version string | +| name | [string](#string) | | Name of the client | + + + + + + + + +### ConnectedClient +Information about a connected client with an id assigned by the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| client_id | [uint32](#uint32) | | The assigned client id | +| client_info | [ClientInfo](#blueye-protocol-ClientInfo) | | Client information. | + + + + + + + + +### ConnectionDuration +Connection duration of a remote client. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [int32](#int32) | | time since connected to drone (s) | + + + + + + + + +### ControlForce +Control Force is used for showing the requested control force in each direction in Newtons. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| surge | [float](#float) | | Force in surge (N) | +| sway | [float](#float) | | Force in sway (N) | +| heave | [float](#float) | | Force in heave (N) | +| yaw | [float](#float) | | Moment in yaw (Nm) | + + + + + + + + +### ControlMode +Control mode from drone supervisor + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| auto_depth | [bool](#bool) | | If auto depth is enabled | +| auto_heading | [bool](#bool) | | If auto heading is enabled | +| auto_altitude | [bool](#bool) | | If auto altitude is enabled | +| station_keeping | [bool](#bool) | | If station keeping is enabled | +| weather_vaning | [bool](#bool) | | If weather vaning is enabled | + + + + + + + + +### ControllerHealth +Controller health is used for showing the state of the controller with an relative error and load from 0 to 1. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| depth_error | [float](#float) | | Depth error in meters (m) | +| depth_health | [float](#float) | | Depth controller load (0..1) | +| heading_error | [float](#float) | | Heading error in degrees (°) | +| heading_health | [float](#float) | | Heading controller load (0..1) | + + + + + + + + +### CpProbe +Reading from a Cathodic Protection Potential probe. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| measurement | [float](#float) | | Potential measurement (V) | +| is_measurement_valid | [bool](#bool) | | Indicating if the measurement is valid | + + + + + + + + +### Depth +Water depth of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Drone depth below surface (m) | + + + + + + + + +### DiveTime +Amount of time the drone has been submerged. + +The drone starts incrementing this value when the depth is above 250 mm. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [int32](#int32) | | Number of seconds the drone has been submerged | + + + + + + + + +### DroneInfo +Information about the drone. + +This message contains serial numbers and version informattion for +internal components in the drone. Primarily used for diagnostics, or to +determine the origin of a logfile. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| blunux_version | [string](#string) | | Blunux version string | +| serial_number | [bytes](#bytes) | | Drone serial number | +| hardware_id | [bytes](#bytes) | | Main computer unique identifier | +| model | [Model](#blueye-protocol-Model) | | Drone model | +| mb_serial | [bytes](#bytes) | | Motherboard serial number | +| bb_serial | [bytes](#bytes) | | Backbone serial number | +| ds_serial | [bytes](#bytes) | | Drone stack serial number | +| mb_uid | [bytes](#bytes) | | Motherboard unique identifier | +| bb_uid | [bytes](#bytes) | | Backbone unique identifier | +| gp | [GuestPortInfo](#blueye-protocol-GuestPortInfo) | | GuestPortInfo | +| depth_sensor | [PressureSensorType](#blueye-protocol-PressureSensorType) | | Type of depth sensor that is connected to the drone | + + + + + + + + +### ErrorFlags +Known error states for the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| pmu_comm_ack | [bool](#bool) | | Acknowledge message not received for a message published to internal micro controller | +| pmu_comm_stream | [bool](#bool) | | Error in communication with internal micro controller | +| depth_read | [bool](#bool) | | Error reading depth sensor value | +| depth_spike | [bool](#bool) | | Sudden spike in value read from depth sensor | +| inner_pressure_read | [bool](#bool) | | Error reading inner pressure of the drone | +| inner_pressure_spike | [bool](#bool) | | Sudden spike in inner preassure | +| compass_calibration | [bool](#bool) | | Compass needs calibration | +| tilt_calibration | [bool](#bool) | | Error during calibration of tilt endpoints | +| gp1_read | [bool](#bool) | | Guest port 1 read error | +| gp2_read | [bool](#bool) | | Guest port 2 read error | +| gp3_read | [bool](#bool) | | Guest port 3 read error | +| gp1_not_flashed | [bool](#bool) | | Guest port 1 not flashed | +| gp2_not_flashed | [bool](#bool) | | Guest port 2 not flashed | +| gp3_not_flashed | [bool](#bool) | | Guest port 3 not flashed | +| gp1_unknown_device | [bool](#bool) | | Unknown device on guest port 1 | +| gp2_unknown_device | [bool](#bool) | | Unknown device on guest port 2 | +| gp3_unknown_device | [bool](#bool) | | Unknown device on guest port 3 | +| gp1_device_connection | [bool](#bool) | | Guest port 1 connection error | +| gp2_device_connection | [bool](#bool) | | Guest port 2 connection error | +| gp3_device_connection | [bool](#bool) | | Guest port 3 connection error | +| gp1_device | [bool](#bool) | | Guest port 1 device error | +| gp2_device | [bool](#bool) | | Guest port 2 device error | +| gp3_device | [bool](#bool) | | Guest port 3 device error | +| drone_serial_not_set | [bool](#bool) | | Drone serial number not set | +| drone_serial | [bool](#bool) | | Drone serial number error | +| mb_eeprom_read | [bool](#bool) | | MB eeprom read error | +| bb_eeprom_read | [bool](#bool) | | BB eeprom read error | +| mb_eeprom_not_flashed | [bool](#bool) | | MB eeprom not flashed | +| bb_eeprom_not_flashed | [bool](#bool) | | BB eeprom not flashed | +| main_camera_connection | [bool](#bool) | | We don't get buffers from the main camera | +| main_camera_firmware | [bool](#bool) | | The main camera firmware is wrong | +| guestport_camera_connection | [bool](#bool) | | We don't get buffers from the guestport camera | +| guestport_camera_firmware | [bool](#bool) | | The guestport camera firmware is wrong | +| mb_serial | [bool](#bool) | | MB serial number error | +| bb_serial | [bool](#bool) | | BB serial number error | +| ds_serial | [bool](#bool) | | DS serial number error | +| gp_current_read | [bool](#bool) | | Error reading GP current | +| gp_current | [bool](#bool) | | Max GP current exceeded | +| gp1_bat_current | [bool](#bool) | | Max battery current exceeded on GP1 | +| gp2_bat_current | [bool](#bool) | | Max battery current exceeded on GP2 | +| gp3_bat_current | [bool](#bool) | | Max battery current exceeded on GP3 | +| gp_20v_current | [bool](#bool) | | Max 20V current exceeded on GP | + + + + + + + + +### ForwardDistance +Distance to an object infront of the drone, typically obtained from an 1D +pinger. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Distance in front of drone (m) | +| is_valid | [bool](#bool) | | If distance reading is valid or not | + + + + + + + + +### GenericServo +Servo message used to represent the angle of the servo. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Servo value (0..1) | +| guest_port_number | [GuestPortNumber](#blueye-protocol-GuestPortNumber) | | Guest port the servo is on | + + + + + + + + +### GripperVelocities +Gripper velocity values. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| grip_velocity | [float](#float) | | The gripping velocity (-1.0..1.0) | +| rotate_velocity | [float](#float) | | The rotating velocity (-1.0..1.0) | + + + + + + + + +### GuestPortConnectorInfo +GuestPort connector information. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| device_list | [GuestPortDeviceList](#blueye-protocol-GuestPortDeviceList) | | List of devices on this connector | +| error | [GuestPortError](#blueye-protocol-GuestPortError) | | Guest port error | +| guest_port_number | [GuestPortNumber](#blueye-protocol-GuestPortNumber) | | Guest port the connector is connected to | + + + + + + + + +### GuestPortCurrent +GuestPort current readings. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| gp1_bat | [double](#double) | | Current on GP1 battery voltage (A) | +| gp2_bat | [double](#double) | | Current on GP2 battery voltage (A) | +| gp3_bat | [double](#double) | | Current on GP3 battery voltage (A) | +| gp_20v | [double](#double) | | Current on common 20V supply (A) | + + + + + + + + +### GuestPortDevice +GuestPort device. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| device_id | [GuestPortDeviceID](#blueye-protocol-GuestPortDeviceID) | | Blueye device identifier | +| manufacturer | [string](#string) | | Manufacturer name | +| name | [string](#string) | | Device name | +| serial_number | [string](#string) | | Serial number | +| depth_rating | [float](#float) | | Depth rating (m) | +| required_blunux_version | [string](#string) | | Required Blunux version (x.y.z) | + + + + + + + + +### GuestPortDeviceList +List of guest port devices. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| devices | [GuestPortDevice](#blueye-protocol-GuestPortDevice) | repeated | List of guest port devices | + + + + + + + + +### GuestPortInfo +GuestPort information. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| gp1 | [GuestPortConnectorInfo](#blueye-protocol-GuestPortConnectorInfo) | | GuestPortConnectorInfo 1 | +| gp2 | [GuestPortConnectorInfo](#blueye-protocol-GuestPortConnectorInfo) | | GuestPortConnectorInfo 2 | +| gp3 | [GuestPortConnectorInfo](#blueye-protocol-GuestPortConnectorInfo) | | GuestPortConnectorInfo 3 | + + + + + + + + +### GuestPortRestartInfo +GuestPort restart information. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| power_off_duration | [double](#double) | | Duration to keep the guest ports off (s) | + + + + + + + + +### Imu +Imu data in drone body frame + +x - forward +y - right +z - down + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| accelerometer | [Vector3](#blueye-protocol-Vector3) | | Acceleration (g) | +| gyroscope | [Vector3](#blueye-protocol-Vector3) | | Angular velocity (rad/s) | +| magnetometer | [Vector3](#blueye-protocol-Vector3) | | Magnetic field (μT) | +| temperature | [float](#float) | | Temperature (°C) | + + + + + + + + +### IperfStatus +Connection speed between drone and Surface Unit. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| sent | [float](#float) | | Transfer rate from drone to Surface Unit (Mbit/s) | +| received | [float](#float) | | Transfer rate from Surface Unit to drone (Mbit/s) | + + + + + + + + +### Laser +Laser message used to represent the intensity of connected laser. + +If the laser does not support dimming but only on and off, +a value of 0 turns the laser off, and any value above 0 +turns the laser on. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Laser intensity, any value above 0 turns the laser on (0..1) | + + + + + + + + +### LatLongPosition +Latitude and longitude position in WGS 84 decimal degrees format. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| latitude | [double](#double) | | Latitude (°) | +| longitude | [double](#double) | | Longitude (°) | + + + + + + + + +### Lights +Lights message used to represent the intensity of the main light or external lights. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Light intensity (0..1) | + + + + + + + + +### MedusaSpectrometerData +Medusa gamma ray sensor spectrometer data + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| drone_time | [google.protobuf.Timestamp](#google-protobuf-Timestamp) | | Time stamp when the data is received | +| sensor_time | [google.protobuf.Timestamp](#google-protobuf-Timestamp) | | Time stamp the sensor reports | +| realtime | [float](#float) | | Time the sensor actually measured (s) | +| livetime | [float](#float) | | Time the measurement took (s) | +| total | [uint32](#uint32) | | Total counts inside the spectrum | +| countrate | [uint32](#uint32) | | Counts per second inside the spectrum (rounded) | +| cosmics | [uint32](#uint32) | | Detected counts above the last channel | + + + + + + + + +### MotionInput +Motion input from client. + +Used to indicate the desired motion in each direction. +Typically these values map to the left and right joystick for motion, +and the left and right trigger for the slow and boost modifiers. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| surge | [float](#float) | | Forward (positive) and backwards (negative) movement. (-1..1) | +| sway | [float](#float) | | Right (positive) and left (negative) lateral movement (-1..1) | +| heave | [float](#float) | | Descend (positive) and ascend (negative) movement (-1..1) | +| yaw | [float](#float) | | Left (positive) and right (negative) movement (-1..1) | +| slow | [float](#float) | | Multiplier used to reduce the speed of the motion (0..1) | +| boost | [float](#float) | | Multiplier used to increase the speed of the motion (0..1) | + + + + + + + + +### MultibeamServo +Servo message used to represent the angle of the servo. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| angle | [float](#float) | | Servo degrees (-30..30) | + + + + + + + + +### NStreamers +Number of spectators connected to video stream. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| main | [int32](#int32) | | The number of clients to the main camera stream | +| guestport | [int32](#int32) | | The number of clients to the guestport camera stream | + + + + + + + + +### NavigationSensorStatus +Navigation sensor used in the position observer with validity state + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| sensor_id | [NavigationSensorID](#blueye-protocol-NavigationSensorID) | | Sensor id | +| is_valid | [bool](#bool) | | Sensor validity | + + + + + + + + +### OverlayParameters +Overlay parameters. + +All available parameters that can be used to configure telemetry overlay on video recordings. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| temperature_enabled | [bool](#bool) | | If temperature should be included | +| depth_enabled | [bool](#bool) | | If depth should be included | +| heading_enabled | [bool](#bool) | | If heading should be included | +| tilt_enabled | [bool](#bool) | | If camera tilt angle should be included | +| thickness_enabled | [bool](#bool) | | If camera tilt angle should be included | +| date_enabled | [bool](#bool) | | If date should be included | +| distance_enabled | [bool](#bool) | | If distance should be included | +| altitude_enabled | [bool](#bool) | | If altitude should be included | +| cp_probe_enabled | [bool](#bool) | | If cp-probe should be included | +| medusa_enabled | [bool](#bool) | | If medusa measurement should be included | +| drone_location_enabled | [bool](#bool) | | If the drone location coordinates should be included | +| logo_type | [LogoType](#blueye-protocol-LogoType) | | Which logo should be used | +| depth_unit | [DepthUnit](#blueye-protocol-DepthUnit) | | Which unit should be used for depth: Meter, Feet or None | +| temperature_unit | [TemperatureUnit](#blueye-protocol-TemperatureUnit) | | Which unit should be used for temperature: Celcius or Fahrenheit | +| thickness_unit | [ThicknessUnit](#blueye-protocol-ThicknessUnit) | | Which unit should be used for thickness: Millimeters or Inches | +| timezone_offset | [int32](#int32) | | Timezone offset from UTC (min) | +| margin_width | [int32](#int32) | | Horizontal margins of text elements (px) | +| margin_height | [int32](#int32) | | Vertical margins of text elements (px) | +| font_size | [FontSize](#blueye-protocol-FontSize) | | Font size of text elements | +| title | [string](#string) | | Optional title | +| subtitle | [string](#string) | | Optional subtitle | +| date_format | [string](#string) | | Posix strftime format string for time stamp | +| shading | [float](#float) | | Pixel intensity to subtract from text background (0..1), 0: transparent, 1: black | + + + + + + + + +### PingerConfiguration +Pinger configuration. + +Used to specify the configuration the BR 1D-Pinger. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| mounting_direction | [PingerConfiguration.MountingDirection](#blueye-protocol-PingerConfiguration-MountingDirection) | | Mounting direction of the pinger | + + + + + + + + +### PositionEstimate +Position estimate from the Extended Kalman filter based observer if a DVL is connected. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| northing | [float](#float) | | Position from reset point (m) | +| easting | [float](#float) | | Position from reset point (m) | +| heading | [float](#float) | | Gyro based heading estimate (continous radians) | +| surge_rate | [float](#float) | | Velocity in surge (m/s) | +| sway_rate | [float](#float) | | Velocity in sway (m/s) | +| yaw_rate | [float](#float) | | Rotaion rate in yaw (rad/s) | +| ocean_current | [float](#float) | | Estimated ocean current (m/s) | +| odometer | [float](#float) | | Travelled distance since reset (m) | +| is_valid | [bool](#bool) | | If the estimate can be trusted | +| global_position | [LatLongPosition](#blueye-protocol-LatLongPosition) | | Best estimate of the global position in decimal degrees | +| navigation_sensors | [NavigationSensorStatus](#blueye-protocol-NavigationSensorStatus) | repeated | List of available sensors with status | + + + + + + + + +### RecordOn +Which cameras are supposed to be recording + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| main | [bool](#bool) | | Record the main camera | +| guestport | [bool](#bool) | | Record external camera | + + + + + + + + +### RecordState +Camera recording state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| main_is_recording | [bool](#bool) | | If the main camera is recording | +| main_seconds | [int32](#int32) | | Main record time (s) | +| guestport_is_recording | [bool](#bool) | | If the guestport camera is recording | +| guestport_seconds | [int32](#int32) | | Guestport record time (s) | + + + + + + + + +### Reference +Reference for the control system. Note that the internal heading referece is not relative to North. +Use (ControlHealth.heading_error + pose.yaw) instead. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| surge | [float](#float) | | Reference from joystick surge input (0..1) | +| sway | [float](#float) | | Reference from joystick sway input (0..1) | +| heave | [float](#float) | | Reference from joystick heave input (0..1) | +| yaw | [float](#float) | | Reference from joystick yaw input (0..1) | +| depth | [float](#float) | | Reference drone depth below surface (m) | +| heading | [float](#float) | | Reference used in auto heading mode, gyro based (°) | +| altitude | [float](#float) | | Reference used in auto altitude mode (m) | + + + + + + + + +### ResetPositionSettings +ResetPositionSettings used during reset of the position estimate. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| heading_source_during_reset | [HeadingSource](#blueye-protocol-HeadingSource) | | Option to use the drone compass or due North as heading during reset | +| manual_heading | [float](#float) | | Heading in degrees (0-359) | +| reset_coordinate_source | [ResetCoordinateSource](#blueye-protocol-ResetCoordinateSource) | | Option to use the device GPS or a manual coordinate. | +| reset_coordinate | [LatLongPosition](#blueye-protocol-LatLongPosition) | | Reset coordinate in decimal degrees | + + + + + + + + +### StationKeepingState +Station keeping state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| enabled | [bool](#bool) | | If station keeping is enabled | + + + + + + + + +### StorageSpace +Storage space. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| total_space | [int64](#int64) | | Total bytes of storage space (B) | +| free_space | [int64](#int64) | | Available bytes of storage space (B) | + + + + + + + + +### SystemTime +System time. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| unix_timestamp | [google.protobuf.Timestamp](#google-protobuf-Timestamp) | | Unix timestamp | + + + + + + + + +### ThicknessGauge +Thickness measurement data from a Cygnus Thickness Gauge. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| thickness_measurement | [float](#float) | | Thickness measurement of a steel plate | +| echo_count | [uint32](#uint32) | | Indicating the quality of the reading when invalid (0-3) | +| sound_velocity | [uint32](#uint32) | | Speed of sound in the steel member (m/s) | +| is_measurement_valid | [bool](#bool) | | Indicating if the measurement is valid | + + + + + + + + +### TiltAngle +Angle of tilt camera in degrees. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Tilt angle (°) | + + + + + + + + +### TiltStabilizationState +Tilt stabilization state. + +Blueye drones with mechanical tilt has the ability to enable +camera stabilization. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| enabled | [bool](#bool) | | If tilt stabilization is enabled | + + + + + + + + +### TiltVelocity +Relative velocity of tilt + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Relative angular velocity of tilt (-1..1), negative means down and positive means up | + + + + + + + + +### Vector3 +Vector with 3 elements + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| x | [double](#double) | | x-component | +| y | [double](#double) | | y-component | +| z | [double](#double) | | z-component | + + + + + + + + +### WaterDensity +Water density. + +Used to specify the water density the drone is operating in, +to achieve more accruate depth measurements. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Salinity (kg/l) | + + + + + + + + +### WaterTemperature +Water temperature measured by the drone's combined depth and temperature sensor. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| value | [float](#float) | | Water temperature (°C) | + + + + + + + + +### WeatherVaningState +Weather vaning state. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| enabled | [bool](#bool) | | If weather vaning is enabled | + + + + + + + + + + +### BatteryBQ40Z50.BatteryStatus.BatteryError +Battery errror code from BQ40Z50 BMS data sheet. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| BATTERY_ERROR_UNSPECIFIED | 0 | | +| BATTERY_ERROR_OK | 1 | | +| BATTERY_ERROR_BUSY | 2 | | +| BATTERY_ERROR_RESERVED_COMMAND | 3 | | +| BATTERY_ERROR_UNSUPPORTED_COMMAND | 4 | | +| BATTERY_ERROR_ACCESS_DENIED | 5 | | +| BATTERY_ERROR_OVERFLOW_UNDERFLOW | 6 | | +| BATTERY_ERROR_BAD_SIZE | 7 | | +| BATTERY_ERROR_UNKNOWN_ERROR | 8 | | + + + + + +### CalibrationState.Status +Status of the compass calibration procedure. + +When calibration is started, the status will indicate the active (upfacing) axis. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| STATUS_UNSPECIFIED | 0 | Unspecified status | +| STATUS_NOT_CALIBRATING | 1 | Compass is not currently calibrating | +| STATUS_CALIBRATING_NO_AXIS | 2 | Compass is calibrating but active calibration axis cannot be determined | +| STATUS_CALIBRATING_X_POSITIVE | 3 | Compass is calibrating and the positive X axis is active | +| STATUS_CALIBRATING_X_NEGATIVE | 4 | Compass is calibrating and the negative X axis is active | +| STATUS_CALIBRATING_Y_POSITIVE | 5 | Compass is calibrating and the positive Y axis is active | +| STATUS_CALIBRATING_Y_NEGATIVE | 6 | Compass is calibrating and the negative Y axis is active | +| STATUS_CALIBRATING_Z_POSITIVE | 7 | Compass is calibrating and the positive Z axis is active | +| STATUS_CALIBRATING_Z_NEGATIVE | 8 | Compass is calibrating and the negative Z axis is active | +| STATUS_CALIBRATING_THRUSTER | 9 | Compass is calibrating for thruster interferance | + + + + + +### Camera +Which camera to control. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| CAMERA_UNSPECIFIED | 0 | Camera not specified | +| CAMERA_MAIN | 1 | Main camera | +| CAMERA_GUESTPORT | 2 | Guestport camera | + + + + + +### DepthUnit +Available depth units. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| DEPTH_UNIT_UNSPECIFIED | 0 | Depth unit not specified | +| DEPTH_UNIT_METERS | 1 | Depth should be displayed as meters | +| DEPTH_UNIT_FEET | 2 | Depth should be displayed as feet | + + + + + +### FontSize +Available font sizes for overlay text elements. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| FONT_SIZE_UNSPECIFIED | 0 | Font size not specified | +| FONT_SIZE_PX15 | 1 | 15 px | +| FONT_SIZE_PX20 | 2 | 20 px | +| FONT_SIZE_PX25 | 3 | 25 px | +| FONT_SIZE_PX30 | 4 | 30 px | +| FONT_SIZE_PX35 | 5 | 35 px | +| FONT_SIZE_PX40 | 6 | 40 px | + + + + + +### Framerate +Available camera framerates. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| FRAMERATE_UNSPECIFIED | 0 | Framerate not specified | +| FRAMERATE_FPS_30 | 1 | 30 frames per second | +| FRAMERATE_FPS_25 | 2 | 25 frames per second | + + + + + +### GuestPortDeviceID +GuestPort device ID. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| GUEST_PORT_DEVICE_ID_UNSPECIFIED | 0 | Unspecified | +| GUEST_PORT_DEVICE_ID_BLIND_PLUG | 1 | Blueye blind plug | +| GUEST_PORT_DEVICE_ID_TEST_STATION | 2 | Blueye test station | +| GUEST_PORT_DEVICE_ID_DEBUG_SERIAL | 3 | Blueye debug serial | +| GUEST_PORT_DEVICE_ID_BLUEYE_LIGHT | 4 | Blueye Light | +| GUEST_PORT_DEVICE_ID_BLUEYE_CAM | 5 | Blueye Cam | +| GUEST_PORT_DEVICE_ID_BLUE_ROBOTICS_LUMEN | 6 | Blue Robotics Lumen | +| GUEST_PORT_DEVICE_ID_BLUE_ROBOTICS_NEWTON | 7 | Blue Robotics Newton | +| GUEST_PORT_DEVICE_ID_BLUE_ROBOTICS_PING_SONAR | 8 | Blue Robotics Ping Sonar | +| GUEST_PORT_DEVICE_ID_BLUEPRINT_LAB_REACH_ALPHA | 9 | Blueprint Lab Reach Alpha | +| GUEST_PORT_DEVICE_ID_WATERLINKED_DVL_A50 | 10 | Waterlinked DVL A50 | +| GUEST_PORT_DEVICE_ID_IMPACT_SUBSEA_ISS360 | 11 | Impact Subsea ISS360 Sonar | +| GUEST_PORT_DEVICE_ID_BLUEPRINT_SUBSEA_SEATRAC_X010 | 12 | Blueprint Subsea Seatrac X110 | +| GUEST_PORT_DEVICE_ID_BLUEPRINT_SUBSEA_OCULUS_M750D | 13 | Blueprint Subsea Oculus M750d | +| GUEST_PORT_DEVICE_ID_CYGNUS_MINI_ROV_THICKNESS_GAUGE | 14 | Cygnus Mini ROV Thickness Gauge | +| GUEST_PORT_DEVICE_ID_BLUE_ROBOTICS_PING360_SONAR | 15 | Blue Robotics Ping360 Scanning Imaging Sonar | +| GUEST_PORT_DEVICE_ID_TRITECH_GEMINI_720IM | 16 | Tritech Gemini 720im Multibeam Sonar | +| GUEST_PORT_DEVICE_ID_BLUEYE_LIGHT_PAIR | 17 | Blueye Light Pair | +| GUEST_PORT_DEVICE_ID_TRITECH_GEMINI_MICRON | 18 | Tritech Micron Gemini | +| GUEST_PORT_DEVICE_ID_OCEAN_TOOLS_DIGICP | 19 | Ocean Tools DigiCP | +| GUEST_PORT_DEVICE_ID_TRITECH_GEMINI_720IK | 20 | Tritech Gemini 720ik Multibeam Sonar | +| GUEST_PORT_DEVICE_ID_NORTEK_NUCLEUS_1000 | 21 | Nortek Nucleus 1000 DVL | +| GUEST_PORT_DEVICE_ID_BLUEYE_GENERIC_SERVO | 22 | Blueye Generic Servo | +| GUEST_PORT_DEVICE_ID_BLUEYE_MULTIBEAM_SERVO | 23 | Blueye Multibeam Servo | +| GUEST_PORT_DEVICE_ID_BLUE_ROBOTICS_DETACHABLE_NEWTON | 24 | Detachable Blue Robotics Newton | +| GUEST_PORT_DEVICE_ID_INSITU_AQUA_TROLL_500 | 25 | In-Situ Aqua TROLL 500 | +| GUEST_PORT_DEVICE_ID_MEDUSA_RADIOMETRICS_MS100 | 26 | Medusa Radiometrics Gamma Ray Sensor | +| GUEST_PORT_DEVICE_ID_LASER_TOOLS_SEA_BEAM | 27 | Laser Tools Sea Beam Underwater Laser | +| GUEST_PORT_DEVICE_ID_SPOT_X_LASER_SCALERS | 28 | Spot X Laser Scalers | +| GUEST_PORT_DEVICE_ID_BLUEPRINT_SUBSEA_OCULUS_M1200D | 29 | Blueprint Subsea Oculus M1200d | +| GUEST_PORT_DEVICE_ID_BLUEPRINT_SUBSEA_OCULUS_M3000D | 30 | Blueprint Subsea Oculus M3000d | + + + + + +### GuestPortError +GuestPort error. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| GUEST_PORT_ERROR_UNSPECIFIED | 0 | Unspecified value | +| GUEST_PORT_ERROR_NOT_CONNECTED | 1 | Device not connected | +| GUEST_PORT_ERROR_READ_ERROR | 2 | EEPROM read error | +| GUEST_PORT_ERROR_NOT_FLASHED | 3 | Connector not flashed | +| GUEST_PORT_ERROR_CRC_ERROR | 4 | Wrong CRC for protobuf message | +| GUEST_PORT_ERROR_PARSE_ERROR | 5 | Protobuf message cannot be parsed | + + + + + +### GuestPortNumber +GuestPort number. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| GUEST_PORT_NUMBER_UNSPECIFIED | 0 | Unspecified | +| GUEST_PORT_NUMBER_PORT_1 | 1 | Guest port 1 | +| GUEST_PORT_NUMBER_PORT_2 | 2 | Guest port 2 | +| GUEST_PORT_NUMBER_PORT_3 | 3 | Guest port 3 | + + + + + +### HeadingSource +Heading source used during reset of the position estimate. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| HEADING_SOURCE_UNSPECIFIED | 0 | Unspecified | +| HEADING_SOURCE_DRONE_COMPASS | 1 | Uses the drone compass to set the heading | +| HEADING_SOURCE_MANUAL_INPUT | 2 | Used when the user sets the heading manually | + + + + + +### LogoType +Available logo types. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| LOGO_TYPE_UNSPECIFIED | 0 | Logo type not specified | +| LOGO_TYPE_NONE | 1 | Do not add any logo | +| LOGO_TYPE_DEFAULT | 2 | Add default logo | +| LOGO_TYPE_CUSTOM | 3 | Add user defined logo | + + + + + +### Model +Drone models produced by Blueye + +| Name | Number | Description | +| ---- | ------ | ----------- | +| MODEL_UNSPECIFIED | 0 | ModelName not specified | +| MODEL_PIONEER | 1 | Blueye Pioneer, the first model | +| MODEL_PRO | 2 | Blueye Pro, features camera tilt | +| MODEL_X3 | 3 | Blueye X3, features support for peripherals | + + + + + +### NavigationSensorID +List of navigation sensors that can be used by the position observer + +| Name | Number | Description | +| ---- | ------ | ----------- | +| NAVIGATION_SENSOR_ID_UNSPECIFIED | 0 | Unspecified | +| NAVIGATION_SENSOR_ID_WATERLINKED_DVL_A50 | 1 | Water Linked DVL A50 | +| NAVIGATION_SENSOR_ID_WATERLINKED_UGPS_G2 | 2 | Water Linked UGPS G2 | + + + + + +### PingerConfiguration.MountingDirection + + +| Name | Number | Description | +| ---- | ------ | ----------- | +| MOUNTING_DIRECTION_UNSPECIFIED | 0 | Mounting direction is unspecified | +| MOUNTING_DIRECTION_FORWARDS | 1 | Pointing forwards from the drones perspective | +| MOUNTING_DIRECTION_DOWNWARDS | 2 | Pointing downwards from the drones perspective | + + + + + +### PressureSensorType +Depth sensors used by the drone. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| PRESSURE_SENSOR_TYPE_UNSPECIFIED | 0 | Depth sensor type not specified | +| PRESSURE_SENSOR_TYPE_NOT_CONNECTED | 1 | No se | +| PRESSURE_SENSOR_TYPE_MS5837_30BA26 | 2 | Thh MS5837 30BA26 pressure sensor | +| PRESSURE_SENSOR_TYPE_KELLER_PA7LD | 3 | The extended depth sensor using the Keller PA7LD pressure sensor | +| PRESSURE_SENSOR_TYPE_MS5637_02BA03 | 4 | The internal pressure sensor using the MS5637 02BA03 pressure sensor | + + + + + +### ResetCoordinateSource + + +| Name | Number | Description | +| ---- | ------ | ----------- | +| RESET_COORDINATE_SOURCE_UNSPECIFIED | 0 | Unspecified, fallback to device GPS | +| RESET_COORDINATE_SOURCE_DEVICE_GPS | 1 | Uses the device GPS to set the reset point | +| RESET_COORDINATE_SOURCE_MANUAL | 2 | Uses a coordinate in decimal degrees to set the reset point | + + + + + +### Resolution +Available camera resolutions. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| RESOLUTION_UNSPECIFIED | 0 | Resolution not specified | +| RESOLUTION_FULLHD_1080P | 1 | 1080p Full HD resolution | +| RESOLUTION_HD_720P | 2 | 720p HD resolution | + + + + + +### TemperatureUnit +Available temperature units. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| TEMPERATURE_UNIT_UNSPECIFIED | 0 | Temperature unit not specfied | +| TEMPERATURE_UNIT_CELSIUS | 1 | Temperature should be displayed as Celcius | +| TEMPERATURE_UNIT_FAHRENHEIT | 2 | Temperature should be displayed as Fahrenheit | + + + + + +### ThicknessUnit +Available thickness units. + +| Name | Number | Description | +| ---- | ------ | ----------- | +| THICKNESS_UNIT_UNSPECIFIED | 0 | Thickness unit not specified | +| THICKNESS_UNIT_MILLIMETERS | 1 | Thickness should be displayed as millimeters | +| THICKNESS_UNIT_INCHES | 2 | Thickness should be displayed as inches | + + + + + + + + + + + +

Top

+ +## req_rep.proto +Request reply + +These messages define request / reply messages for the Blueye drone. + + + + +### ConnectClientRep +Response after connecting a client to the drone. + +Contains information about which client is in control, and a list of +all connected clients. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| client_id | [uint32](#uint32) | | The assigned ID of this client. | +| client_id_in_control | [uint32](#uint32) | | The ID of the client in control of the drone. | +| connected_clients | [ConnectedClient](#blueye-protocol-ConnectedClient) | repeated | List of connected clients. | + + + + + + + + +### ConnectClientReq +Connect a new client to the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| client_info | [ClientInfo](#blueye-protocol-ClientInfo) | | Information about the client connecting to the drone. | + + + + + + + + +### DisconnectClientRep +Response after disconnecting a client from the drone. + +Contains information about which clients are connected and in control. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| client_id_in_control | [uint32](#uint32) | | The ID of the client in control of the drone. | +| connected_clients | [ConnectedClient](#blueye-protocol-ConnectedClient) | repeated | List of connected clients. | + + + + + + + + +### DisconnectClientReq +Disconnect a client from the drone. + +This request will remove the client from the list of connected clients. +It allows clients to disconnect instantly, without waiting for a watchdog to +clear the client in control, or promote a new client to be in control. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| client_id | [uint32](#uint32) | | The assigned ID of the client to disconnect. | + + + + + + + + +### GetBatteryRep +Response with essential battery information. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| battery | [Battery](#blueye-protocol-Battery) | | Essential battery information. | + + + + + + + + +### GetBatteryReq +Request essential battery information. + +Can be used to instantly get battery information, +instead of having to wait for the BatteryTel message to be received. + + + + + + + + +### GetCameraParametersRep +Response with the currently set camera parameters. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| camera_parameters | [CameraParameters](#blueye-protocol-CameraParameters) | | The currently set camera parameters. | + + + + + + + + +### GetCameraParametersReq +Request to get the currently set camera parameters. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| camera | [Camera](#blueye-protocol-Camera) | | Which camera to read camera parameters from. | + + + + + + + + +### GetOverlayParametersRep +Response with the currently set video overlay parameters. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| overlay_parameters | [OverlayParameters](#blueye-protocol-OverlayParameters) | | The currently set overlay parameters. | + + + + + + + + +### GetOverlayParametersReq +Request to get currently set video overlay parameters. + + + + + + + + +### PingRep +Response message from a PingReq request. + + + + + + + + +### PingReq +The simplest message to use to test request/reply communication with the drone. + +The drone replies with a PingRep message immediately after receiving the PingReq. + + + + + + + + +### SetCameraParametersRep +Response after setting the camera parameters. + + + + + + + + +### SetCameraParametersReq +Request to set camera parameters. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| camera_parameters | [CameraParameters](#blueye-protocol-CameraParameters) | | The camera parameters to apply. | + + + + + + + + +### SetOverlayParametersRep +Response after setting video overlay parameters. + + + + + + + + +### SetOverlayParametersReq +Request to set video overlay parameters. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| overlay_parameters | [OverlayParameters](#blueye-protocol-OverlayParameters) | | The video overlay parameters to apply. | + + + + + + + + +### SetPubFrequencyRep +Response aftrer updating publish frequency + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| success | [bool](#bool) | | True if message name valid and frequency successfully updated. | + + + + + + + + +### SetPubFrequencyReq +Request to update the publish frequency + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| message_type | [string](#string) | | Message name, f. ex. "AttitudeTel" | +| frequency | [float](#float) | | Publish frequency (max 100 Hz). | + + + + + + + + +### SetThicknessGaugeParametersRep +Response after setting thicknes gauge parameters. + + + + + + + + +### SetThicknessGaugeParametersReq +Request to set parameters for ultrasonic thickness gauge. + +The sound velocity is used to calculate the thickness of the material being measured. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| sound_velocity | [uint32](#uint32) | | Sound velocity in m/s | + + + + + + + + +### SyncTimeRep +Response after setting the system time on the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| success | [bool](#bool) | | If the time was set successfully. | + + + + + + + + +### SyncTimeReq +Request to set the system time on the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| time | [SystemTime](#blueye-protocol-SystemTime) | | The time to set on the drone. | + + + + + + + + + + + + + + + + +

Top

+ +## telemetry.proto +Telemetry + +These messages define telemetry messages from the Blueye drone. + + + + +### AltitudeTel +Receive the current altitude of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| altitude | [Altitude](#blueye-protocol-Altitude) | | The altitude of the drone. | + + + + + + + + +### AttitudeTel +Receive the current attitude of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| attitude | [Attitude](#blueye-protocol-Attitude) | | The attitude of the drone. | + + + + + + + + +### BatteryBQ40Z50Tel +Receive detailed information about a battery using the +BQ40Z50 battery management system. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| battery | [BatteryBQ40Z50](#blueye-protocol-BatteryBQ40Z50) | | Detailed battery information. | + + + + + + + + +### BatteryTel +Receive essential information about the battery status. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| battery | [Battery](#blueye-protocol-Battery) | | Essential battery information. | + + + + + + + + +### CPUTemperatureTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| temperature | [CPUTemperature](#blueye-protocol-CPUTemperature) | | | + + + + + + + + +### CalibratedImuTel +Calibrated IMU data + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| imu | [Imu](#blueye-protocol-Imu) | | | + + + + + + + + +### CalibrationStateTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| calibration_state | [CalibrationState](#blueye-protocol-CalibrationState) | | | + + + + + + + + +### CanisterBottomHumidityTel +Receive humidity information from the bottom canister. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| humidity | [CanisterHumidity](#blueye-protocol-CanisterHumidity) | | Humidity information | + + + + + + + + +### CanisterBottomTemperatureTel +Receive temperature information from the bottom canister. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| temperature | [CanisterTemperature](#blueye-protocol-CanisterTemperature) | | Temperature information. | + + + + + + + + +### CanisterTopHumidityTel +Receive humidity information from the top canister. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| humidity | [CanisterHumidity](#blueye-protocol-CanisterHumidity) | | Humidity information | + + + + + + + + +### CanisterTopTemperatureTel +Receive temperature information from the top canister. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| temperature | [CanisterTemperature](#blueye-protocol-CanisterTemperature) | | Temperature information. | + + + + + + + + +### ConnectedClientsTel +List of connected clients telemetry message. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| client_id_in_control | [uint32](#uint32) | | The client id of the client in control. | +| connected_clients | [ConnectedClient](#blueye-protocol-ConnectedClient) | repeated | List of connected clients. | + + + + + + + + +### ControlForceTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| control_force | [ControlForce](#blueye-protocol-ControlForce) | | | + + + + + + + + +### ControlModeTel +Receive the current state of the control system. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [ControlMode](#blueye-protocol-ControlMode) | | State of the control system. | + + + + + + + + +### ControllerHealthTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| controller_health | [ControllerHealth](#blueye-protocol-ControllerHealth) | | | + + + + + + + + +### CpProbeTel +Cathodic Protection Potential probe telemetry message + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| cp_probe | [CpProbe](#blueye-protocol-CpProbe) | | Reading from cp probe. | + + + + + + + + +### DataStorageSpaceTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| storage_space | [StorageSpace](#blueye-protocol-StorageSpace) | | | + + + + + + + + +### DepthTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| depth | [Depth](#blueye-protocol-Depth) | | | + + + + + + + + +### DiveTimeTel +Receive the dive time of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| dive_time | [DiveTime](#blueye-protocol-DiveTime) | | The current dive time of the drone. | + + + + + + + + +### DroneInfoTel +Receive metadata and information about the connected drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| drone_info | [DroneInfo](#blueye-protocol-DroneInfo) | | Various metadata such as software versions and serial number. | + + + + + + + + +### DroneTimeTel +Receive time information from the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| real_time_clock | [SystemTime](#blueye-protocol-SystemTime) | | The real-time clock of the drone. | +| monotonic_clock | [SystemTime](#blueye-protocol-SystemTime) | | The monotonic clock of the drone (time since power on). | + + + + + + + + +### ErrorFlagsTel +Receive currently set error flags. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| error_flags | [ErrorFlags](#blueye-protocol-ErrorFlags) | | Currently set error flags on the drone. | + + + + + + + + +### ForwardDistanceTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| forward_distance | [ForwardDistance](#blueye-protocol-ForwardDistance) | | | + + + + + + + + +### GenericServoTel +State of a generic servo + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| servo | [GenericServo](#blueye-protocol-GenericServo) | | Servo state | + + + + + + + + +### GuestPortCurrentTel +GuestPort current readings + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| current | [GuestPortCurrent](#blueye-protocol-GuestPortCurrent) | | | + + + + + + + + +### GuestPortLightsTel +Receive the status of any guest port lights connected to the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| lights | [Lights](#blueye-protocol-Lights) | | | + + + + + + + + +### Imu1Tel +Raw IMU data from IMU 1 + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| imu | [Imu](#blueye-protocol-Imu) | | | + + + + + + + + +### Imu2Tel +Raw IMU data from IMU 2 + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| imu | [Imu](#blueye-protocol-Imu) | | | + + + + + + + + +### IperfTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| status | [IperfStatus](#blueye-protocol-IperfStatus) | | | + + + + + + + + +### LaserTel +Receive the status of any lasers connected to the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| laser | [Laser](#blueye-protocol-Laser) | | | + + + + + + + + +### LightsTel +Receive the status of the main lights of the drone. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| lights | [Lights](#blueye-protocol-Lights) | | | + + + + + + + + +### MedusaSpectrometerDataTel +Medusa gamma ray sensor spectrometer data + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| data | [MedusaSpectrometerData](#blueye-protocol-MedusaSpectrometerData) | | | + + + + + + + + +### MultibeamServoTel +State of the servo installed in the multibeam + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| servo | [MultibeamServo](#blueye-protocol-MultibeamServo) | | Multibeam servo state | + + + + + + + + +### NStreamersTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| n_streamers | [NStreamers](#blueye-protocol-NStreamers) | | | + + + + + + + + +### PilotGPSPositionTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| position | [LatLongPosition](#blueye-protocol-LatLongPosition) | | | + + + + + + + + +### PositionEstimateTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| position_estimate | [PositionEstimate](#blueye-protocol-PositionEstimate) | | | + + + + + + + + +### RecordStateTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| record_state | [RecordState](#blueye-protocol-RecordState) | | | + + + + + + + + +### ReferenceTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| reference | [Reference](#blueye-protocol-Reference) | | | + + + + + + + + +### ThicknessGaugeTel +Thickness gauge measurement telemetry message. + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| thickness_gauge | [ThicknessGauge](#blueye-protocol-ThicknessGauge) | | Tickness measurement with a cygnus gauge. | + + + + + + + + +### TiltAngleTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| angle | [TiltAngle](#blueye-protocol-TiltAngle) | | | + + + + + + + + +### TiltStabilizationTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| state | [TiltStabilizationState](#blueye-protocol-TiltStabilizationState) | | | + + + + + + + + +### VideoStorageSpaceTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| storage_space | [StorageSpace](#blueye-protocol-StorageSpace) | | | + + + + + + + + +### WaterTemperatureTel + + + +| Field | Type | Label | Description | +| ----- | ---- | ----- | ----------- | +| temperature | [WaterTemperature](#blueye-protocol-WaterTemperature) | | | + + + + + + + + + + + + + + + +## Scalar Value Types + +| .proto Type | Notes | C++ | Java | Python | Go | C# | PHP | Ruby | +| ----------- | ----- | --- | ---- | ------ | -- | -- | --- | ---- | +| double | | double | double | float | float64 | double | float | Float | +| float | | float | float | float | float32 | float | float | Float | +| int32 | Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint32 instead. | int32 | int | int | int32 | int | integer | Bignum or Fixnum (as required) | +| int64 | Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint64 instead. | int64 | long | int/long | int64 | long | integer/string | Bignum | +| uint32 | Uses variable-length encoding. | uint32 | int | int/long | uint32 | uint | integer | Bignum or Fixnum (as required) | +| uint64 | Uses variable-length encoding. | uint64 | long | int/long | uint64 | ulong | integer/string | Bignum or Fixnum (as required) | +| sint32 | Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int32s. | int32 | int | int | int32 | int | integer | Bignum or Fixnum (as required) | +| sint64 | Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int64s. | int64 | long | int/long | int64 | long | integer/string | Bignum | +| fixed32 | Always four bytes. More efficient than uint32 if values are often greater than 2^28. | uint32 | int | int | uint32 | uint | integer | Bignum or Fixnum (as required) | +| fixed64 | Always eight bytes. More efficient than uint64 if values are often greater than 2^56. | uint64 | long | int/long | uint64 | ulong | integer/string | Bignum | +| sfixed32 | Always four bytes. | int32 | int | int | int32 | int | integer | Bignum or Fixnum (as required) | +| sfixed64 | Always eight bytes. | int64 | long | int/long | int64 | long | integer/string | Bignum | +| bool | | bool | boolean | boolean | bool | bool | boolean | TrueClass/FalseClass | +| string | A string must always contain UTF-8 encoded or 7-bit ASCII text. | string | String | str/unicode | string | string | string | String (UTF-8) | +| bytes | May contain any arbitrary sequence of bytes. | string | ByteString | str | []byte | ByteString | string | String (ASCII-8BIT) | diff --git a/docs/quick_start.md b/docs/quick_start.md index cbf2dd9d..a4369d90 100644 --- a/docs/quick_start.md +++ b/docs/quick_start.md @@ -1,5 +1,5 @@ ## Installation -The SDK requires Python 3.7.1 or higher. Since many operating systems do not package the newest +The SDK requires Python 3.8 or higher. Since many operating systems do not package the newest version of Python we recommend using [`pyenv`](https://github.com/pyenv/pyenv) or something similar for configuring multiple python versions on the same system. Pyenv also has the added benefit of managing your virtual environments for you, though you are of course free to use other tools for @@ -10,7 +10,7 @@ The instructions below show the necessary steps to get started with the SDK on a ??? abstract "Windows" **Install Python** - Install Python 3.7.1 or higher, you can find the latest python versions [here](https://www.python.org/downloads/). + Install Python 3.8 or higher, you can find the latest python versions [here](https://www.python.org/downloads/). Remember to check the option "Add Python to path" when installing. **Install virtualenv for managing Python versions (optional)** @@ -189,8 +189,8 @@ from blueye.sdk import Drone # When the Drone object is instantiatied a connection to the drone is established myDrone = Drone() -# Setting the lights property to 10 -myDrone.lights = 10 +# Setting the lights property to 0.1 (10 %) +myDrone.lights = 0.1 time.sleep(2) @@ -199,7 +199,7 @@ print(f"Current light intensity: {myDrone.lights}") myDrone.lights = 0 # Properties can also be used for reading telemetry data from the drone -print(f"Current depth in millimeters: {myDrone.depth}") +print(f"Current depth in meters: {myDrone.depth}") ``` For an overview of the properties that are available for controlling and reading data from the drone, go to the [`Reference section`](../../reference/blueye/sdk/drone) of the documentation. diff --git a/docs/telemetry-callback.md b/docs/telemetry-callback.md new file mode 100644 index 00000000..4f83ad10 --- /dev/null +++ b/docs/telemetry-callback.md @@ -0,0 +1,17 @@ +# Subscribing to a telemetry message + +The drone publishes all of its telemetry data as protobuf encoded messages transmitted via a ZeroMQ socket. You can find the protobuf message definitions in the [Protocol Definitions](https://github.com/BluEye-Robotics/ProtocolDefinitions/) repository, and the generated python definitions are located in the [blueye.protocol](https://github.com/BluEye-Robotics/blueye.protocol) repository. + +## Adding a callback +To add a callback we need to use the [`add_msg_callback`](../../reference/blueye/sdk/drone/#add_msg_callback) function, and provide it with a list of telemetry messages types we want it to trigger on, as well as a function handle to call. All available telemetry messages can be found in [telemetry.proto](../protobuf-protocol/#telemetryproto) + +## Removing a callback +A callback is removed with [`remove_msg_callback`](../../reference/blueye/sdk/drone/#remove_msg_callback) using the ID returned when creating the callback. + +## Adjusting the publishing frequency of a telemetry message +By using the [`set_msg_publish_frequency`](../../reference/blueye/sdk/drone/#set_msg_publish_frequency) function we can alter how often the drone should publish the specified telemetry message. The valid frequency range is 0 to 100 Hz. + +## Example +The following example illustrates how can use a callback to print the depth reported by the drone. + +{{code_from_file("../examples/print_depth.py", "python")}} diff --git a/examples/gamepad_controller.py b/examples/gamepad_controller.py index b52a3293..f15b0914 100644 --- a/examples/gamepad_controller.py +++ b/examples/gamepad_controller.py @@ -31,7 +31,7 @@ def handle_y_button(self, value): if self.drone.lights > 0: self.drone.lights = 0 else: - self.drone.lights = 10 + self.drone.lights = 0.1 def handle_b_button(self, value): """Toggles autoheading""" diff --git a/examples/print_depth.py b/examples/print_depth.py new file mode 100644 index 00000000..b9038861 --- /dev/null +++ b/examples/print_depth.py @@ -0,0 +1,36 @@ +"""print_depth.py + +This example program demonstrates how one can add a callback function to a telemetry message, as +well as how to adjust the frequency of that telemetry message, and how to remove the callback. +""" +import time + +import blueye.protocol as bp + +from blueye.sdk import Drone + + +def callback_depth(msg_type: str, msg: bp.DepthTel): + """Callback for the depth telemetry message + + This function is called once for every DepthTel message received by the telemetry watcher + """ + print(f"Got a {msg_type} message with depth: {msg.depth.value:.3f}") + + +if __name__ == "__main__": + # Instantiate a drone object + my_drone = Drone() + + # Add a callback for the DepthTel message, storing the ID for later use + callback_id = my_drone.telemetry.add_msg_callback([bp.DepthTel], callback_depth) + + # Adjust the publishing frequency to 5 Hz + my_drone.telemetry.set_msg_publish_frequency(bp.DepthTel, 5) + + # Callback is triggered by a separate thread while we sleep here + time.sleep(5) + + # Remove the callback using the ID we stored when it was created (not really necessary here + # since the my_drone object goes out of scope immediately afterwards) + my_drone.telemetry.remove_msg_callback(callback_id) diff --git a/examples/print_imu.py b/examples/print_imu.py new file mode 100644 index 00000000..abdb0883 --- /dev/null +++ b/examples/print_imu.py @@ -0,0 +1,30 @@ +import time + +import blueye.protocol as bp + +from blueye.sdk import Drone + + +def callback_imu_raw(msg_type, msg): + print(f"Raw {msg_type}\n{msg}") + + +def callback_imu_calibrated(msg_type, msg): + print(f"{msg_type}:\n{msg}") + + +if __name__ == "__main__": + my_drone = Drone() + my_drone.telemetry.set_msg_publish_frequency(bp.Imu1Tel, 10) + my_drone.telemetry.set_msg_publish_frequency(bp.Imu2Tel, 10) + my_drone.telemetry.set_msg_publish_frequency(bp.CalibratedImuTel, 10) + + cb_raw = my_drone.telemetry.add_msg_callback([bp.Imu1Tel, bp.Imu2Tel], callback_imu_raw) + cb_calibrated = my_drone.telemetry.add_msg_callback( + [bp.CalibratedImuTel], callback_imu_calibrated + ) + + time.sleep(3) + + my_drone.telemetry.remove_msg_callback(cb_raw) + my_drone.telemetry.remove_msg_callback(cb_calibrated) diff --git a/examples/print_status.py b/examples/print_status.py index 85353332..ef61a0c7 100644 --- a/examples/print_status.py +++ b/examples/print_status.py @@ -10,12 +10,12 @@ def print_state(screen: ManagedScreen, drone: Drone): """Updates and prints some of the information from the drone""" - screen.print_at(f"Lights: {drone.lights * 100 // 255:3d} %", 2, 1) + screen.print_at(f"Lights: {drone.lights * 100:5.1f} %", 2, 1) screen.print_at(f"Auto-depth: {'On' if drone.motion.auto_depth_active else 'Off':>5}", 2, 3) screen.print_at(f"Auto-heading: {'On' if drone.motion.auto_heading_active else 'Off':>3}", 2, 4) - screen.print_at(f"Depth: {drone.depth} mm", 2, 6) + screen.print_at(f"Depth: {drone.depth:3.3f} m ", 2, 6) screen.print_at(f"Roll: {drone.pose['roll']:7.2f}°", 2, 8) screen.print_at(f"Pitch: {drone.pose['pitch']:6.2f}°", 2, 9) @@ -35,5 +35,6 @@ def state_printer(drone: Drone): if __name__ == "__main__": - myDrone = Drone(slaveModeEnabled=True) + myDrone = Drone() + sleep(1) # Wait until data is updated state_printer(myDrone) diff --git a/examples/profiler.py b/examples/profiler.py new file mode 100644 index 00000000..d9d8806a --- /dev/null +++ b/examples/profiler.py @@ -0,0 +1,59 @@ +#!/usr/bin/env python3 +import time + +from blueye.sdk import Drone + +last_message = {} +message_size = {} +message_number = {} +message_number_unique = {} +first_time = None +last_time = None + + +def parse_message(payload_msg_name, data): + global first_time, last_time + + if payload_msg_name not in last_message: + message_size[payload_msg_name] = 0 + message_number[payload_msg_name] = 0 + message_number_unique[payload_msg_name] = 1 + last_message[payload_msg_name] = data + + message_number[payload_msg_name] += 1 + message_size[payload_msg_name] += len(data) + if data != last_message[payload_msg_name]: + message_number_unique[payload_msg_name] += 1 + + if first_time is None: + first_time = time.time() + last_time = time.time() + last_message[payload_msg_name] = data + + +myDrone = Drone() + +print("Listening to protobuf messages") + +loop_time = time.time() +myDrone.telemetry.add_msg_callback([], parse_message, raw=True) +while True: + if time.time() - loop_time > 1: + loop_time = time.time() + + time_diff = last_time - first_time + total_size = sum(message_size.values()) + bytes_per_second = total_size / time_diff + + mn = sorted(message_number.items(), key=lambda item: -item[1]) + for k, v in mn: + freq = v / time_diff + print(f"{k:28} unique/all:{message_number_unique[k]:8} / {v:8} {freq:.2f} Hz") + print("====") + ms = sorted(message_size.items(), key=lambda item: -item[1]) + for k, v in ms: + percentage = v / total_size * 100 + print(f"{k:28} : {v:8} {percentage:.0f}%") + print("====") + print(f"Time logged: {time_diff:.0f} s") + print(f"bytes per s: {bytes_per_second:.0f}") diff --git a/poetry.lock b/poetry.lock index 5725a08c..a941b8a8 100644 --- a/poetry.lock +++ b/poetry.lock @@ -38,7 +38,7 @@ pyyaml = "*" name = "atomicwrites" version = "1.4.1" description = "Atomic file writes." -category = "main" +category = "dev" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" files = [ @@ -49,7 +49,7 @@ files = [ name = "attrs" version = "23.1.0" description = "Classes Without Boilerplate" -category = "main" +category = "dev" optional = false python-versions = ">=3.7" files = [ @@ -57,9 +57,6 @@ files = [ {file = "attrs-23.1.0.tar.gz", hash = "sha256:6279836d581513a26f1bf235f9acd333bc9115683f14f7e8fae46c98fc50e015"}, ] -[package.dependencies] -importlib-metadata = {version = "*", markers = "python_version < \"3.8\""} - [package.extras] cov = ["attrs[tests]", "coverage[toml] (>=5.3)"] dev = ["attrs[docs,tests]", "pre-commit"] @@ -109,7 +106,6 @@ packaging = ">=22.0" pathspec = ">=0.9.0" platformdirs = ">=2" tomli = {version = ">=1.1.0", markers = "python_version < \"3.11\""} -typed-ast = {version = ">=1.4.2", markers = "python_version < \"3.8\" and implementation_name == \"cpython\""} typing-extensions = {version = ">=3.10.0.0", markers = "python_version < \"3.10\""} [package.extras] @@ -120,33 +116,110 @@ uvloop = ["uvloop (>=0.15.2)"] [[package]] name = "blueye-protocol" -version = "1.5.0" -description = "Python protocol definition for the Blueye Pioneer" +version = "2.2.0" +description = "Python protocol definition for the Blueye drones" category = "main" optional = false -python-versions = ">=3.7,<4.0" +python-versions = ">=3.8,<4.0" files = [ - {file = "blueye.protocol-1.5.0-py3-none-any.whl", hash = "sha256:fb42943326450143340a080c36a672386018bf213bd1d4cdc587b2ee220580bb"}, - {file = "blueye.protocol-1.5.0.tar.gz", hash = "sha256:add1e0a860d4c8fdfa0a8107695976c70b82fe082d82aff16b731c59abad4523"}, + {file = "blueye_protocol-2.2.0-py3-none-any.whl", hash = "sha256:d1a9718db20efa9436c064cb52c36f25ee47f8a9d38014a495ed42925a690c7e"}, + {file = "blueye_protocol-2.2.0.tar.gz", hash = "sha256:9b0ffeba04133475576bd09917d29b3f3ed708c44c9a43f219dc48555a59410d"}, ] [package.dependencies] -numpy = ">=1.17,<2.0" -pytest-timeout = ">=1.4.2,<2.0.0" +numpy = ">=1.23,<2.0" +proto-plus = ">=1.22.1,<2.0.0" setuptools = ">=40" [[package]] name = "certifi" -version = "2022.12.7" +version = "2023.5.7" description = "Python package for providing Mozilla's CA Bundle." category = "main" optional = false python-versions = ">=3.6" files = [ - {file = "certifi-2022.12.7-py3-none-any.whl", hash = "sha256:4ad3232f5e926d6718ec31cfc1fcadfde020920e278684144551c91769c7bc18"}, - {file = "certifi-2022.12.7.tar.gz", hash = "sha256:35824b4c3a97115964b408844d64aa14db1cc518f6562e8d7261699d1350a9e3"}, + {file = "certifi-2023.5.7-py3-none-any.whl", hash = "sha256:c6c2e98f5c7869efca1f8916fed228dd91539f9f1b444c314c06eef02980c716"}, + {file = "certifi-2023.5.7.tar.gz", hash = "sha256:0f0d56dc5a6ad56fd4ba36484d6cc34451e1c6548c61daad8c320169f91eddc7"}, ] +[[package]] +name = "cffi" +version = "1.15.1" +description = "Foreign Function Interface for Python calling C code." +category = "main" +optional = false +python-versions = "*" +files = [ + {file = "cffi-1.15.1-cp27-cp27m-macosx_10_9_x86_64.whl", hash = "sha256:a66d3508133af6e8548451b25058d5812812ec3798c886bf38ed24a98216fab2"}, + {file = "cffi-1.15.1-cp27-cp27m-manylinux1_i686.whl", hash = "sha256:470c103ae716238bbe698d67ad020e1db9d9dba34fa5a899b5e21577e6d52ed2"}, + {file = "cffi-1.15.1-cp27-cp27m-manylinux1_x86_64.whl", hash = "sha256:9ad5db27f9cabae298d151c85cf2bad1d359a1b9c686a275df03385758e2f914"}, + {file = "cffi-1.15.1-cp27-cp27m-win32.whl", hash = "sha256:b3bbeb01c2b273cca1e1e0c5df57f12dce9a4dd331b4fa1635b8bec26350bde3"}, + {file = "cffi-1.15.1-cp27-cp27m-win_amd64.whl", hash = "sha256:e00b098126fd45523dd056d2efba6c5a63b71ffe9f2bbe1a4fe1716e1d0c331e"}, + {file = "cffi-1.15.1-cp27-cp27mu-manylinux1_i686.whl", hash = "sha256:d61f4695e6c866a23a21acab0509af1cdfd2c013cf256bbf5b6b5e2695827162"}, + {file = "cffi-1.15.1-cp27-cp27mu-manylinux1_x86_64.whl", hash = "sha256:ed9cb427ba5504c1dc15ede7d516b84757c3e3d7868ccc85121d9310d27eed0b"}, + {file = "cffi-1.15.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:39d39875251ca8f612b6f33e6b1195af86d1b3e60086068be9cc053aa4376e21"}, + {file = "cffi-1.15.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:285d29981935eb726a4399badae8f0ffdff4f5050eaa6d0cfc3f64b857b77185"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3eb6971dcff08619f8d91607cfc726518b6fa2a9eba42856be181c6d0d9515fd"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:21157295583fe8943475029ed5abdcf71eb3911894724e360acff1d61c1d54bc"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5635bd9cb9731e6d4a1132a498dd34f764034a8ce60cef4f5319c0541159392f"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2012c72d854c2d03e45d06ae57f40d78e5770d252f195b93f581acf3ba44496e"}, + {file = "cffi-1.15.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd86c085fae2efd48ac91dd7ccffcfc0571387fe1193d33b6394db7ef31fe2a4"}, + {file = "cffi-1.15.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:fa6693661a4c91757f4412306191b6dc88c1703f780c8234035eac011922bc01"}, + {file = "cffi-1.15.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:59c0b02d0a6c384d453fece7566d1c7e6b7bae4fc5874ef2ef46d56776d61c9e"}, + {file = "cffi-1.15.1-cp310-cp310-win32.whl", hash = "sha256:cba9d6b9a7d64d4bd46167096fc9d2f835e25d7e4c121fb2ddfc6528fb0413b2"}, + {file = "cffi-1.15.1-cp310-cp310-win_amd64.whl", hash = "sha256:ce4bcc037df4fc5e3d184794f27bdaab018943698f4ca31630bc7f84a7b69c6d"}, + {file = "cffi-1.15.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3d08afd128ddaa624a48cf2b859afef385b720bb4b43df214f85616922e6a5ac"}, + {file = "cffi-1.15.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:3799aecf2e17cf585d977b780ce79ff0dc9b78d799fc694221ce814c2c19db83"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a591fe9e525846e4d154205572a029f653ada1a78b93697f3b5a8f1f2bc055b9"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3548db281cd7d2561c9ad9984681c95f7b0e38881201e157833a2342c30d5e8c"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:91fc98adde3d7881af9b59ed0294046f3806221863722ba7d8d120c575314325"}, + {file = "cffi-1.15.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:94411f22c3985acaec6f83c6df553f2dbe17b698cc7f8ae751ff2237d96b9e3c"}, + {file = "cffi-1.15.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:03425bdae262c76aad70202debd780501fabeaca237cdfddc008987c0e0f59ef"}, + {file = "cffi-1.15.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:cc4d65aeeaa04136a12677d3dd0b1c0c94dc43abac5860ab33cceb42b801c1e8"}, + {file = "cffi-1.15.1-cp311-cp311-win32.whl", hash = "sha256:a0f100c8912c114ff53e1202d0078b425bee3649ae34d7b070e9697f93c5d52d"}, + {file = "cffi-1.15.1-cp311-cp311-win_amd64.whl", hash = "sha256:04ed324bda3cda42b9b695d51bb7d54b680b9719cfab04227cdd1e04e5de3104"}, + {file = "cffi-1.15.1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:50a74364d85fd319352182ef59c5c790484a336f6db772c1a9231f1c3ed0cbd7"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e263d77ee3dd201c3a142934a086a4450861778baaeeb45db4591ef65550b0a6"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:cec7d9412a9102bdc577382c3929b337320c4c4c4849f2c5cdd14d7368c5562d"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4289fc34b2f5316fbb762d75362931e351941fa95fa18789191b33fc4cf9504a"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:173379135477dc8cac4bc58f45db08ab45d228b3363adb7af79436135d028405"}, + {file = "cffi-1.15.1-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:6975a3fac6bc83c4a65c9f9fcab9e47019a11d3d2cf7f3c0d03431bf145a941e"}, + {file = "cffi-1.15.1-cp36-cp36m-win32.whl", hash = "sha256:2470043b93ff09bf8fb1d46d1cb756ce6132c54826661a32d4e4d132e1977adf"}, + {file = "cffi-1.15.1-cp36-cp36m-win_amd64.whl", hash = "sha256:30d78fbc8ebf9c92c9b7823ee18eb92f2e6ef79b45ac84db507f52fbe3ec4497"}, + {file = "cffi-1.15.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:198caafb44239b60e252492445da556afafc7d1e3ab7a1fb3f0584ef6d742375"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5ef34d190326c3b1f822a5b7a45f6c4535e2f47ed06fec77d3d799c450b2651e"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8102eaf27e1e448db915d08afa8b41d6c7ca7a04b7d73af6514df10a3e74bd82"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5df2768244d19ab7f60546d0c7c63ce1581f7af8b5de3eb3004b9b6fc8a9f84b"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a8c4917bd7ad33e8eb21e9a5bbba979b49d9a97acb3a803092cbc1133e20343c"}, + {file = "cffi-1.15.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0e2642fe3142e4cc4af0799748233ad6da94c62a8bec3a6648bf8ee68b1c7426"}, + {file = "cffi-1.15.1-cp37-cp37m-win32.whl", hash = "sha256:e229a521186c75c8ad9490854fd8bbdd9a0c9aa3a524326b55be83b54d4e0ad9"}, + {file = "cffi-1.15.1-cp37-cp37m-win_amd64.whl", hash = "sha256:a0b71b1b8fbf2b96e41c4d990244165e2c9be83d54962a9a1d118fd8657d2045"}, + {file = "cffi-1.15.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:320dab6e7cb2eacdf0e658569d2575c4dad258c0fcc794f46215e1e39f90f2c3"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1e74c6b51a9ed6589199c787bf5f9875612ca4a8a0785fb2d4a84429badaf22a"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a5c84c68147988265e60416b57fc83425a78058853509c1b0629c180094904a5"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3b926aa83d1edb5aa5b427b4053dc420ec295a08e40911296b9eb1b6170f6cca"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:87c450779d0914f2861b8526e035c5e6da0a3199d8f1add1a665e1cbc6fc6d02"}, + {file = "cffi-1.15.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4f2c9f67e9821cad2e5f480bc8d83b8742896f1242dba247911072d4fa94c192"}, + {file = "cffi-1.15.1-cp38-cp38-win32.whl", hash = "sha256:8b7ee99e510d7b66cdb6c593f21c043c248537a32e0bedf02e01e9553a172314"}, + {file = "cffi-1.15.1-cp38-cp38-win_amd64.whl", hash = "sha256:00a9ed42e88df81ffae7a8ab6d9356b371399b91dbdf0c3cb1e84c03a13aceb5"}, + {file = "cffi-1.15.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:54a2db7b78338edd780e7ef7f9f6c442500fb0d41a5a4ea24fff1c929d5af585"}, + {file = "cffi-1.15.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:fcd131dd944808b5bdb38e6f5b53013c5aa4f334c5cad0c72742f6eba4b73db0"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7473e861101c9e72452f9bf8acb984947aa1661a7704553a9f6e4baa5ba64415"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6c9a799e985904922a4d207a94eae35c78ebae90e128f0c4e521ce339396be9d"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3bcde07039e586f91b45c88f8583ea7cf7a0770df3a1649627bf598332cb6984"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:33ab79603146aace82c2427da5ca6e58f2b3f2fb5da893ceac0c42218a40be35"}, + {file = "cffi-1.15.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5d598b938678ebf3c67377cdd45e09d431369c3b1a5b331058c338e201f12b27"}, + {file = "cffi-1.15.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:db0fbb9c62743ce59a9ff687eb5f4afbe77e5e8403d6697f7446e5f609976f76"}, + {file = "cffi-1.15.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:98d85c6a2bef81588d9227dde12db8a7f47f639f4a17c9ae08e773aa9c697bf3"}, + {file = "cffi-1.15.1-cp39-cp39-win32.whl", hash = "sha256:40f4774f5a9d4f5e344f31a32b5096977b5d48560c5592e2f3d2c4374bd543ee"}, + {file = "cffi-1.15.1-cp39-cp39-win_amd64.whl", hash = "sha256:70df4e3b545a17496c9b3f41f5115e69a4f2e77e94e1d2a8e1070bc0c38c8a3c"}, + {file = "cffi-1.15.1.tar.gz", hash = "sha256:d400bfb9a37b1351253cb402671cea7e89bdecc294e8016a707f6d1d8ac934f9"}, +] + +[package.dependencies] +pycparser = "*" + [[package]] name = "cfgv" version = "3.3.1" @@ -258,13 +331,12 @@ files = [ [package.dependencies] colorama = {version = "*", markers = "platform_system == \"Windows\""} -importlib-metadata = {version = "*", markers = "python_version < \"3.8\""} [[package]] name = "colorama" version = "0.4.6" description = "Cross-platform colored terminal text." -category = "main" +category = "dev" optional = false python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,!=3.6.*,>=2.7" files = [ @@ -272,65 +344,140 @@ files = [ {file = "colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44"}, ] +[[package]] +name = "contourpy" +version = "1.0.7" +description = "Python library for calculating contours of 2D quadrilateral grids" +category = "main" +optional = true +python-versions = ">=3.8" +files = [ + {file = "contourpy-1.0.7-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:95c3acddf921944f241b6773b767f1cbce71d03307270e2d769fd584d5d1092d"}, + {file = "contourpy-1.0.7-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:fc1464c97579da9f3ab16763c32e5c5d5bb5fa1ec7ce509a4ca6108b61b84fab"}, + {file = "contourpy-1.0.7-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8acf74b5d383414401926c1598ed77825cd530ac7b463ebc2e4f46638f56cce6"}, + {file = "contourpy-1.0.7-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1c71fdd8f1c0f84ffd58fca37d00ca4ebaa9e502fb49825484da075ac0b0b803"}, + {file = "contourpy-1.0.7-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f99e9486bf1bb979d95d5cffed40689cb595abb2b841f2991fc894b3452290e8"}, + {file = "contourpy-1.0.7-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:87f4d8941a9564cda3f7fa6a6cd9b32ec575830780677932abdec7bcb61717b0"}, + {file = "contourpy-1.0.7-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:9e20e5a1908e18aaa60d9077a6d8753090e3f85ca25da6e25d30dc0a9e84c2c6"}, + {file = "contourpy-1.0.7-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:a877ada905f7d69b2a31796c4b66e31a8068b37aa9b78832d41c82fc3e056ddd"}, + {file = "contourpy-1.0.7-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:6381fa66866b0ea35e15d197fc06ac3840a9b2643a6475c8fff267db8b9f1e69"}, + {file = "contourpy-1.0.7-cp310-cp310-win32.whl", hash = "sha256:3c184ad2433635f216645fdf0493011a4667e8d46b34082f5a3de702b6ec42e3"}, + {file = "contourpy-1.0.7-cp310-cp310-win_amd64.whl", hash = "sha256:3caea6365b13119626ee996711ab63e0c9d7496f65641f4459c60a009a1f3e80"}, + {file = "contourpy-1.0.7-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ed33433fc3820263a6368e532f19ddb4c5990855e4886088ad84fd7c4e561c71"}, + {file = "contourpy-1.0.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:38e2e577f0f092b8e6774459317c05a69935a1755ecfb621c0a98f0e3c09c9a5"}, + {file = "contourpy-1.0.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ae90d5a8590e5310c32a7630b4b8618cef7563cebf649011da80874d0aa8f414"}, + {file = "contourpy-1.0.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:130230b7e49825c98edf0b428b7aa1125503d91732735ef897786fe5452b1ec2"}, + {file = "contourpy-1.0.7-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:58569c491e7f7e874f11519ef46737cea1d6eda1b514e4eb5ac7dab6aa864d02"}, + {file = "contourpy-1.0.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:54d43960d809c4c12508a60b66cb936e7ed57d51fb5e30b513934a4a23874fae"}, + {file = "contourpy-1.0.7-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:152fd8f730c31fd67fe0ffebe1df38ab6a669403da93df218801a893645c6ccc"}, + {file = "contourpy-1.0.7-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:9056c5310eb1daa33fc234ef39ebfb8c8e2533f088bbf0bc7350f70a29bde1ac"}, + {file = "contourpy-1.0.7-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:a9d7587d2fdc820cc9177139b56795c39fb8560f540bba9ceea215f1f66e1566"}, + {file = "contourpy-1.0.7-cp311-cp311-win32.whl", hash = "sha256:4ee3ee247f795a69e53cd91d927146fb16c4e803c7ac86c84104940c7d2cabf0"}, + {file = "contourpy-1.0.7-cp311-cp311-win_amd64.whl", hash = "sha256:5caeacc68642e5f19d707471890f037a13007feba8427eb7f2a60811a1fc1350"}, + {file = "contourpy-1.0.7-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:fd7dc0e6812b799a34f6d12fcb1000539098c249c8da54f3566c6a6461d0dbad"}, + {file = "contourpy-1.0.7-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:0f9d350b639db6c2c233d92c7f213d94d2e444d8e8fc5ca44c9706cf72193772"}, + {file = "contourpy-1.0.7-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:e96a08b62bb8de960d3a6afbc5ed8421bf1a2d9c85cc4ea73f4bc81b4910500f"}, + {file = "contourpy-1.0.7-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:031154ed61f7328ad7f97662e48660a150ef84ee1bc8876b6472af88bf5a9b98"}, + {file = "contourpy-1.0.7-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2e9ebb4425fc1b658e13bace354c48a933b842d53c458f02c86f371cecbedecc"}, + {file = "contourpy-1.0.7-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:efb8f6d08ca7998cf59eaf50c9d60717f29a1a0a09caa46460d33b2924839dbd"}, + {file = "contourpy-1.0.7-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:6c180d89a28787e4b73b07e9b0e2dac7741261dbdca95f2b489c4f8f887dd810"}, + {file = "contourpy-1.0.7-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:b8d587cc39057d0afd4166083d289bdeff221ac6d3ee5046aef2d480dc4b503c"}, + {file = "contourpy-1.0.7-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:769eef00437edf115e24d87f8926955f00f7704bede656ce605097584f9966dc"}, + {file = "contourpy-1.0.7-cp38-cp38-win32.whl", hash = "sha256:62398c80ef57589bdbe1eb8537127321c1abcfdf8c5f14f479dbbe27d0322e66"}, + {file = "contourpy-1.0.7-cp38-cp38-win_amd64.whl", hash = "sha256:57119b0116e3f408acbdccf9eb6ef19d7fe7baf0d1e9aaa5381489bc1aa56556"}, + {file = "contourpy-1.0.7-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:30676ca45084ee61e9c3da589042c24a57592e375d4b138bd84d8709893a1ba4"}, + {file = "contourpy-1.0.7-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:3e927b3868bd1e12acee7cc8f3747d815b4ab3e445a28d2e5373a7f4a6e76ba1"}, + {file = "contourpy-1.0.7-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:366a0cf0fc079af5204801786ad7a1c007714ee3909e364dbac1729f5b0849e5"}, + {file = "contourpy-1.0.7-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:89ba9bb365446a22411f0673abf6ee1fea3b2cf47b37533b970904880ceb72f3"}, + {file = "contourpy-1.0.7-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:71b0bf0c30d432278793d2141362ac853859e87de0a7dee24a1cea35231f0d50"}, + {file = "contourpy-1.0.7-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e7281244c99fd7c6f27c1c6bfafba878517b0b62925a09b586d88ce750a016d2"}, + {file = "contourpy-1.0.7-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:b6d0f9e1d39dbfb3977f9dd79f156c86eb03e57a7face96f199e02b18e58d32a"}, + {file = "contourpy-1.0.7-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:7f6979d20ee5693a1057ab53e043adffa1e7418d734c1532e2d9e915b08d8ec2"}, + {file = "contourpy-1.0.7-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:5dd34c1ae752515318224cba7fc62b53130c45ac6a1040c8b7c1a223c46e8967"}, + {file = "contourpy-1.0.7-cp39-cp39-win32.whl", hash = "sha256:c5210e5d5117e9aec8c47d9156d1d3835570dd909a899171b9535cb4a3f32693"}, + {file = "contourpy-1.0.7-cp39-cp39-win_amd64.whl", hash = "sha256:60835badb5ed5f4e194a6f21c09283dd6e007664a86101431bf870d9e86266c4"}, + {file = "contourpy-1.0.7-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:ce41676b3d0dd16dbcfabcc1dc46090aaf4688fd6e819ef343dbda5a57ef0161"}, + {file = "contourpy-1.0.7-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5a011cf354107b47c58ea932d13b04d93c6d1d69b8b6dce885e642531f847566"}, + {file = "contourpy-1.0.7-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:31a55dccc8426e71817e3fe09b37d6d48ae40aae4ecbc8c7ad59d6893569c436"}, + {file = "contourpy-1.0.7-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:69f8ff4db108815addd900a74df665e135dbbd6547a8a69333a68e1f6e368ac2"}, + {file = "contourpy-1.0.7-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:efe99298ba37e37787f6a2ea868265465410822f7bea163edcc1bd3903354ea9"}, + {file = "contourpy-1.0.7-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:a1e97b86f73715e8670ef45292d7cc033548266f07d54e2183ecb3c87598888f"}, + {file = "contourpy-1.0.7-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cc331c13902d0f50845099434cd936d49d7a2ca76cb654b39691974cb1e4812d"}, + {file = "contourpy-1.0.7-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:24847601071f740837aefb730e01bd169fbcaa610209779a78db7ebb6e6a7051"}, + {file = "contourpy-1.0.7-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:abf298af1e7ad44eeb93501e40eb5a67abbf93b5d90e468d01fc0c4451971afa"}, + {file = "contourpy-1.0.7-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:64757f6460fc55d7e16ed4f1de193f362104285c667c112b50a804d482777edd"}, + {file = "contourpy-1.0.7.tar.gz", hash = "sha256:d8165a088d31798b59e91117d1f5fc3df8168d8b48c4acc10fc0df0d0bdbcc5e"}, +] + +[package.dependencies] +numpy = ">=1.16" + +[package.extras] +bokeh = ["bokeh", "chromedriver", "selenium"] +docs = ["furo", "sphinx-copybutton"] +mypy = ["contourpy[bokeh]", "docutils-stubs", "mypy (==0.991)", "types-Pillow"] +test = ["Pillow", "matplotlib", "pytest"] +test-no-images = ["pytest"] + [[package]] name = "coverage" -version = "7.2.5" +version = "7.2.6" description = "Code coverage measurement for Python" category = "dev" optional = false python-versions = ">=3.7" files = [ - {file = "coverage-7.2.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:883123d0bbe1c136f76b56276074b0c79b5817dd4238097ffa64ac67257f4b6c"}, - {file = "coverage-7.2.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:d2fbc2a127e857d2f8898aaabcc34c37771bf78a4d5e17d3e1f5c30cd0cbc62a"}, - {file = "coverage-7.2.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5f3671662dc4b422b15776cdca89c041a6349b4864a43aa2350b6b0b03bbcc7f"}, - {file = "coverage-7.2.5-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:780551e47d62095e088f251f5db428473c26db7829884323e56d9c0c3118791a"}, - {file = "coverage-7.2.5-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:066b44897c493e0dcbc9e6a6d9f8bbb6607ef82367cf6810d387c09f0cd4fe9a"}, - {file = "coverage-7.2.5-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:b9a4ee55174b04f6af539218f9f8083140f61a46eabcaa4234f3c2a452c4ed11"}, - {file = "coverage-7.2.5-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:706ec567267c96717ab9363904d846ec009a48d5f832140b6ad08aad3791b1f5"}, - {file = "coverage-7.2.5-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:ae453f655640157d76209f42c62c64c4d4f2c7f97256d3567e3b439bd5c9b06c"}, - {file = "coverage-7.2.5-cp310-cp310-win32.whl", hash = "sha256:f81c9b4bd8aa747d417407a7f6f0b1469a43b36a85748145e144ac4e8d303cb5"}, - {file = "coverage-7.2.5-cp310-cp310-win_amd64.whl", hash = "sha256:dc945064a8783b86fcce9a0a705abd7db2117d95e340df8a4333f00be5efb64c"}, - {file = "coverage-7.2.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:40cc0f91c6cde033da493227797be2826cbf8f388eaa36a0271a97a332bfd7ce"}, - {file = "coverage-7.2.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:a66e055254a26c82aead7ff420d9fa8dc2da10c82679ea850d8feebf11074d88"}, - {file = "coverage-7.2.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c10fbc8a64aa0f3ed136b0b086b6b577bc64d67d5581acd7cc129af52654384e"}, - {file = "coverage-7.2.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9a22cbb5ede6fade0482111fa7f01115ff04039795d7092ed0db43522431b4f2"}, - {file = "coverage-7.2.5-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:292300f76440651529b8ceec283a9370532f4ecba9ad67d120617021bb5ef139"}, - {file = "coverage-7.2.5-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:7ff8f3fb38233035028dbc93715551d81eadc110199e14bbbfa01c5c4a43f8d8"}, - {file = "coverage-7.2.5-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:a08c7401d0b24e8c2982f4e307124b671c6736d40d1c39e09d7a8687bddf83ed"}, - {file = "coverage-7.2.5-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:ef9659d1cda9ce9ac9585c045aaa1e59223b143f2407db0eaee0b61a4f266fb6"}, - {file = "coverage-7.2.5-cp311-cp311-win32.whl", hash = "sha256:30dcaf05adfa69c2a7b9f7dfd9f60bc8e36b282d7ed25c308ef9e114de7fc23b"}, - {file = "coverage-7.2.5-cp311-cp311-win_amd64.whl", hash = "sha256:97072cc90f1009386c8a5b7de9d4fc1a9f91ba5ef2146c55c1f005e7b5c5e068"}, - {file = "coverage-7.2.5-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:bebea5f5ed41f618797ce3ffb4606c64a5de92e9c3f26d26c2e0aae292f015c1"}, - {file = "coverage-7.2.5-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:828189fcdda99aae0d6bf718ea766b2e715eabc1868670a0a07bf8404bf58c33"}, - {file = "coverage-7.2.5-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6e8a95f243d01ba572341c52f89f3acb98a3b6d1d5d830efba86033dd3687ade"}, - {file = "coverage-7.2.5-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e8834e5f17d89e05697c3c043d3e58a8b19682bf365048837383abfe39adaed5"}, - {file = "coverage-7.2.5-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:d1f25ee9de21a39b3a8516f2c5feb8de248f17da7eead089c2e04aa097936b47"}, - {file = "coverage-7.2.5-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:1637253b11a18f453e34013c665d8bf15904c9e3c44fbda34c643fbdc9d452cd"}, - {file = "coverage-7.2.5-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:8e575a59315a91ccd00c7757127f6b2488c2f914096077c745c2f1ba5b8c0969"}, - {file = "coverage-7.2.5-cp37-cp37m-win32.whl", hash = "sha256:509ecd8334c380000d259dc66feb191dd0a93b21f2453faa75f7f9cdcefc0718"}, - {file = "coverage-7.2.5-cp37-cp37m-win_amd64.whl", hash = "sha256:12580845917b1e59f8a1c2ffa6af6d0908cb39220f3019e36c110c943dc875b0"}, - {file = "coverage-7.2.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:b5016e331b75310610c2cf955d9f58a9749943ed5f7b8cfc0bb89c6134ab0a84"}, - {file = "coverage-7.2.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:373ea34dca98f2fdb3e5cb33d83b6d801007a8074f992b80311fc589d3e6b790"}, - {file = "coverage-7.2.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a063aad9f7b4c9f9da7b2550eae0a582ffc7623dca1c925e50c3fbde7a579771"}, - {file = "coverage-7.2.5-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:38c0a497a000d50491055805313ed83ddba069353d102ece8aef5d11b5faf045"}, - {file = "coverage-7.2.5-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a2b3b05e22a77bb0ae1a3125126a4e08535961c946b62f30985535ed40e26614"}, - {file = "coverage-7.2.5-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:0342a28617e63ad15d96dca0f7ae9479a37b7d8a295f749c14f3436ea59fdcb3"}, - {file = "coverage-7.2.5-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:cf97ed82ca986e5c637ea286ba2793c85325b30f869bf64d3009ccc1a31ae3fd"}, - {file = "coverage-7.2.5-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:c2c41c1b1866b670573657d584de413df701f482574bad7e28214a2362cb1fd1"}, - {file = "coverage-7.2.5-cp38-cp38-win32.whl", hash = "sha256:10b15394c13544fce02382360cab54e51a9e0fd1bd61ae9ce012c0d1e103c813"}, - {file = "coverage-7.2.5-cp38-cp38-win_amd64.whl", hash = "sha256:a0b273fe6dc655b110e8dc89b8ec7f1a778d78c9fd9b4bda7c384c8906072212"}, - {file = "coverage-7.2.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:5c587f52c81211d4530fa6857884d37f514bcf9453bdeee0ff93eaaf906a5c1b"}, - {file = "coverage-7.2.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:4436cc9ba5414c2c998eaedee5343f49c02ca93b21769c5fdfa4f9d799e84200"}, - {file = "coverage-7.2.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6599bf92f33ab041e36e06d25890afbdf12078aacfe1f1d08c713906e49a3fe5"}, - {file = "coverage-7.2.5-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:857abe2fa6a4973f8663e039ead8d22215d31db613ace76e4a98f52ec919068e"}, - {file = "coverage-7.2.5-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f6f5cab2d7f0c12f8187a376cc6582c477d2df91d63f75341307fcdcb5d60303"}, - {file = "coverage-7.2.5-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:aa387bd7489f3e1787ff82068b295bcaafbf6f79c3dad3cbc82ef88ce3f48ad3"}, - {file = "coverage-7.2.5-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:156192e5fd3dbbcb11cd777cc469cf010a294f4c736a2b2c891c77618cb1379a"}, - {file = "coverage-7.2.5-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:bd3b4b8175c1db502adf209d06136c000df4d245105c8839e9d0be71c94aefe1"}, - {file = "coverage-7.2.5-cp39-cp39-win32.whl", hash = "sha256:ddc5a54edb653e9e215f75de377354e2455376f416c4378e1d43b08ec50acc31"}, - {file = "coverage-7.2.5-cp39-cp39-win_amd64.whl", hash = "sha256:338aa9d9883aaaad53695cb14ccdeb36d4060485bb9388446330bef9c361c252"}, - {file = "coverage-7.2.5-pp37.pp38.pp39-none-any.whl", hash = "sha256:8877d9b437b35a85c18e3c6499b23674684bf690f5d96c1006a1ef61f9fdf0f3"}, - {file = "coverage-7.2.5.tar.gz", hash = "sha256:f99ef080288f09ffc687423b8d60978cf3a465d3f404a18d1a05474bd8575a47"}, + {file = "coverage-7.2.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:496b86f1fc9c81a1cd53d8842ef712e950a4611bba0c42d33366a7b91ba969ec"}, + {file = "coverage-7.2.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:fbe6e8c0a9a7193ba10ee52977d4d5e7652957c1f56ccefed0701db8801a2a3b"}, + {file = "coverage-7.2.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76d06b721c2550c01a60e5d3093f417168658fb454e5dfd9a23570e9bffe39a1"}, + {file = "coverage-7.2.6-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:77a04b84d01f0e12c66f16e69e92616442dc675bbe51b90bfb074b1e5d1c7fbd"}, + {file = "coverage-7.2.6-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:35db06450272473eab4449e9c2ad9bc6a0a68dab8e81a0eae6b50d9c2838767e"}, + {file = "coverage-7.2.6-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:6727a0d929ff0028b1ed8b3e7f8701670b1d7032f219110b55476bb60c390bfb"}, + {file = "coverage-7.2.6-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:aac1d5fdc5378f6bac2c0c7ebe7635a6809f5b4376f6cf5d43243c1917a67087"}, + {file = "coverage-7.2.6-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:1c9e4a5eb1bbc3675ee57bc31f8eea4cd7fb0cbcbe4912cf1cb2bf3b754f4a80"}, + {file = "coverage-7.2.6-cp310-cp310-win32.whl", hash = "sha256:71f739f97f5f80627f1fee2331e63261355fd1e9a9cce0016394b6707ac3f4ec"}, + {file = "coverage-7.2.6-cp310-cp310-win_amd64.whl", hash = "sha256:fde5c7a9d9864d3e07992f66767a9817f24324f354caa3d8129735a3dc74f126"}, + {file = "coverage-7.2.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:bc7b667f8654376e9353dd93e55e12ce2a59fb6d8e29fce40de682273425e044"}, + {file = "coverage-7.2.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:697f4742aa3f26c107ddcb2b1784a74fe40180014edbd9adaa574eac0529914c"}, + {file = "coverage-7.2.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:541280dde49ce74a4262c5e395b48ea1207e78454788887118c421cb4ffbfcac"}, + {file = "coverage-7.2.6-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6e7f1a8328eeec34c54f1d5968a708b50fc38d31e62ca8b0560e84a968fbf9a9"}, + {file = "coverage-7.2.6-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4bbd58eb5a2371bf160590f4262109f66b6043b0b991930693134cb617bc0169"}, + {file = "coverage-7.2.6-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ae82c5f168d2a39a5d69a12a69d4dc23837a43cf2ca99be60dfe59996ea6b113"}, + {file = "coverage-7.2.6-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:f5440cdaf3099e7ab17a5a7065aed59aff8c8b079597b61c1f8be6f32fe60636"}, + {file = "coverage-7.2.6-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:a6f03f87fea579d55e0b690d28f5042ec1368650466520fbc400e7aeaf09e995"}, + {file = "coverage-7.2.6-cp311-cp311-win32.whl", hash = "sha256:dc4d5187ef4d53e0d4c8eaf530233685667844c5fb0b855fea71ae659017854b"}, + {file = "coverage-7.2.6-cp311-cp311-win_amd64.whl", hash = "sha256:c93d52c3dc7b9c65e39473704988602300e3cc1bad08b5ab5b03ca98bbbc68c1"}, + {file = "coverage-7.2.6-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:42c692b55a647a832025a4c048007034fe77b162b566ad537ce65ad824b12a84"}, + {file = "coverage-7.2.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7786b2fa7809bf835f830779ad285215a04da76293164bb6745796873f0942d"}, + {file = "coverage-7.2.6-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:25bad4196104761bc26b1dae9b57383826542ec689ff0042f7f4f4dd7a815cba"}, + {file = "coverage-7.2.6-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2692306d3d4cb32d2cceed1e47cebd6b1d2565c993d6d2eda8e6e6adf53301e6"}, + {file = "coverage-7.2.6-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:392154d09bd4473b9d11351ab5d63391f3d5d24d752f27b3be7498b0ee2b5226"}, + {file = "coverage-7.2.6-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:fa079995432037b5e2ef5ddbb270bcd2ded9f52b8e191a5de11fe59a00ea30d8"}, + {file = "coverage-7.2.6-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:d712cefff15c712329113b01088ba71bbcef0f7ea58478ca0bbec63a824844cb"}, + {file = "coverage-7.2.6-cp37-cp37m-win32.whl", hash = "sha256:004948e296149644d208964300cb3d98affc5211e9e490e9979af4030b0d6473"}, + {file = "coverage-7.2.6-cp37-cp37m-win_amd64.whl", hash = "sha256:c1d7a31603c3483ac49c1726723b0934f88f2c011c660e6471e7bd735c2fa110"}, + {file = "coverage-7.2.6-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:3436927d1794fa6763b89b60c896f9e3bd53212001026ebc9080d23f0c2733c1"}, + {file = "coverage-7.2.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:44c9b9f1a245f3d0d202b1a8fa666a80b5ecbe4ad5d0859c0fb16a52d9763224"}, + {file = "coverage-7.2.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4e3783a286d5a93a2921396d50ce45a909aa8f13eee964465012f110f0cbb611"}, + {file = "coverage-7.2.6-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3cff6980fe7100242170092bb40d2b1cdad79502cd532fd26b12a2b8a5f9aee0"}, + {file = "coverage-7.2.6-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c534431153caffc7c495c3eddf7e6a6033e7f81d78385b4e41611b51e8870446"}, + {file = "coverage-7.2.6-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:3062fd5c62df988cea9f2972c593f77fed1182bfddc5a3b12b1e606cb7aba99e"}, + {file = "coverage-7.2.6-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:6284a2005e4f8061c58c814b1600ad0074ccb0289fe61ea709655c5969877b70"}, + {file = "coverage-7.2.6-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:97729e6828643f168a2a3f07848e1b1b94a366b13a9f5aba5484c2215724edc8"}, + {file = "coverage-7.2.6-cp38-cp38-win32.whl", hash = "sha256:dc11b42fa61ff1e788dd095726a0aed6aad9c03d5c5984b54cb9e1e67b276aa5"}, + {file = "coverage-7.2.6-cp38-cp38-win_amd64.whl", hash = "sha256:cbcc874f454ee51f158afd604a315f30c0e31dff1d5d5bf499fc529229d964dd"}, + {file = "coverage-7.2.6-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:d3cacc6a665221108ecdf90517a8028d07a2783df3417d12dcfef1c517e67478"}, + {file = "coverage-7.2.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:272ab31228a9df857ab5df5d67936d8861464dc89c5d3fab35132626e9369379"}, + {file = "coverage-7.2.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9a8723ccec4e564d4b9a79923246f7b9a8de4ec55fa03ec4ec804459dade3c4f"}, + {file = "coverage-7.2.6-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5906f6a84b47f995cd1bf0aca1c72d591c55ee955f98074e93660d64dfc66eb9"}, + {file = "coverage-7.2.6-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:52c139b7ab3f0b15f9aad0a3fedef5a1f8c0b2bdc291d88639ca2c97d3682416"}, + {file = "coverage-7.2.6-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:a5ffd45c6b93c23a8507e2f436983015c6457aa832496b6a095505ca2f63e8f1"}, + {file = "coverage-7.2.6-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:4f3c7c19581d471af0e9cb49d928172cd8492cd78a2b7a4e82345d33662929bb"}, + {file = "coverage-7.2.6-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:2e8c0e79820cdd67978e1120983786422d279e07a381dbf89d03bbb23ec670a6"}, + {file = "coverage-7.2.6-cp39-cp39-win32.whl", hash = "sha256:13cde6bb0e58fb67d09e2f373de3899d1d1e866c5a9ff05d93615f2f54fbd2bb"}, + {file = "coverage-7.2.6-cp39-cp39-win_amd64.whl", hash = "sha256:6b9f64526286255735847aed0221b189486e0b9ed943446936e41b7e44b08783"}, + {file = "coverage-7.2.6-pp37.pp38.pp39-none-any.whl", hash = "sha256:6babcbf1e66e46052442f10833cfc4a0d3554d8276aa37af8531a83ed3c1a01d"}, + {file = "coverage-7.2.6.tar.gz", hash = "sha256:2025f913f2edb0272ef15d00b1f335ff8908c921c8eb2013536fcaf61f5a683d"}, ] [package.extras] @@ -425,25 +572,24 @@ files = [ ] [package.dependencies] -importlib-metadata = {version = "*", markers = "python_version < \"3.8\""} mccabe = ">=0.6.0,<0.7.0" pycodestyle = ">=2.7.0,<2.8.0" pyflakes = ">=2.3.0,<2.4.0" [[package]] name = "fonttools" -version = "4.38.0" +version = "4.39.4" description = "Tools to manipulate font files" category = "main" optional = true -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "fonttools-4.38.0-py3-none-any.whl", hash = "sha256:820466f43c8be8c3009aef8b87e785014133508f0de64ec469e4efb643ae54fb"}, - {file = "fonttools-4.38.0.zip", hash = "sha256:2bb244009f9bf3fa100fc3ead6aeb99febe5985fa20afbfbaa2f8946c2fbdaf1"}, + {file = "fonttools-4.39.4-py3-none-any.whl", hash = "sha256:106caf6167c4597556b31a8d9175a3fdc0356fdcd70ab19973c3b0d4c893c461"}, + {file = "fonttools-4.39.4.zip", hash = "sha256:dba8d7cdb8e2bac1b3da28c5ed5960de09e59a2fe7e63bb73f5a59e57b0430d2"}, ] [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)"] +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 (>=15.0.0)", "xattr", "zopfli (>=0.1.4)"] graphite = ["lz4 (>=1.7.4.2)"] interpolatable = ["munkres", "scipy"] lxml = ["lxml (>=4.0,<5)"] @@ -453,7 +599,7 @@ repacker = ["uharfbuzz (>=0.23.0)"] symfont = ["sympy"] type1 = ["xattr"] ufo = ["fs (>=2.2.0,<3)"] -unicode = ["unicodedata2 (>=14.0.0)"] +unicode = ["unicodedata2 (>=15.0.0)"] woff = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "zopfli (>=0.1.4)"] [[package]] @@ -530,7 +676,6 @@ files = [ [package.dependencies] gitdb = ">=4.0.1,<5" -typing-extensions = {version = ">=3.7.4.3", markers = "python_version < \"3.8\""} [[package]] name = "hug" @@ -579,7 +724,7 @@ files = [ name = "importlib-metadata" version = "6.6.0" description = "Read metadata from Python packages" -category = "main" +category = "dev" optional = false python-versions = ">=3.7" files = [ @@ -588,7 +733,6 @@ files = [ ] [package.dependencies] -typing-extensions = {version = ">=3.6.4", markers = "python_version < \"3.8\""} zipp = ">=0.5" [package.extras] @@ -596,11 +740,30 @@ docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "rst.linker 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 = "importlib-resources" +version = "5.12.0" +description = "Read resources from Python packages" +category = "main" +optional = true +python-versions = ">=3.7" +files = [ + {file = "importlib_resources-5.12.0-py3-none-any.whl", hash = "sha256:7b1deeebbf351c7578e09bf2f63fa2ce8b5ffec296e0d349139d43cca061a81a"}, + {file = "importlib_resources-5.12.0.tar.gz", hash = "sha256:4be82589bf5c1d7999aedf2a45159d10cb3ca4f19b2271f8792bc8e6da7b22f6"}, +] + +[package.dependencies] +zipp = {version = ">=3.1.0", markers = "python_version < \"3.10\""} + +[package.extras] +docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] +testing = ["flake8 (<5)", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=1.3)", "pytest-flake8", "pytest-mypy (>=0.9.1)"] + [[package]] name = "iniconfig" version = "2.0.0" description = "brain-dead simple config-ini parsing" -category = "main" +category = "dev" optional = false python-versions = ">=3.7" files = [ @@ -716,9 +879,6 @@ files = [ {file = "kiwisolver-1.4.4.tar.gz", hash = "sha256:d41997519fcba4a1e46eb4a2fe31bc12f0ff957b2b81bac28db24744f333e955"}, ] -[package.dependencies] -typing-extensions = {version = "*", markers = "python_version < \"3.8\""} - [[package]] name = "livereload" version = "2.6.3" @@ -841,7 +1001,6 @@ files = [ ] [package.dependencies] -importlib-metadata = {version = "*", markers = "python_version < \"3.8\""} MarkupSafe = ">=0.9.2" [package.extras] @@ -929,57 +1088,65 @@ files = [ [[package]] name = "matplotlib" -version = "3.5.3" +version = "3.7.1" description = "Python plotting package" category = "main" optional = true -python-versions = ">=3.7" -files = [ - {file = "matplotlib-3.5.3-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:a206a1b762b39398efea838f528b3a6d60cdb26fe9d58b48265787e29cd1d693"}, - {file = "matplotlib-3.5.3-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:cd45a6f3e93a780185f70f05cf2a383daed13c3489233faad83e81720f7ede24"}, - {file = "matplotlib-3.5.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:d62880e1f60e5a30a2a8484432bcb3a5056969dc97258d7326ad465feb7ae069"}, - {file = "matplotlib-3.5.3-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9ab29589cef03bc88acfa3a1490359000c18186fc30374d8aa77d33cc4a51a4a"}, - {file = "matplotlib-3.5.3-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2886cc009f40e2984c083687251821f305d811d38e3df8ded414265e4583f0c5"}, - {file = "matplotlib-3.5.3-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c995f7d9568f18b5db131ab124c64e51b6820a92d10246d4f2b3f3a66698a15b"}, - {file = "matplotlib-3.5.3-cp310-cp310-win32.whl", hash = "sha256:6bb93a0492d68461bd458eba878f52fdc8ac7bdb6c4acdfe43dba684787838c2"}, - {file = "matplotlib-3.5.3-cp310-cp310-win_amd64.whl", hash = "sha256:2e6d184ebe291b9e8f7e78bbab7987d269c38ea3e062eace1fe7d898042ef804"}, - {file = "matplotlib-3.5.3-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:6ea6aef5c4338e58d8d376068e28f80a24f54e69f09479d1c90b7172bad9f25b"}, - {file = "matplotlib-3.5.3-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:839d47b8ead7ad9669aaacdbc03f29656dc21f0d41a6fea2d473d856c39c8b1c"}, - {file = "matplotlib-3.5.3-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:3b4fa56159dc3c7f9250df88f653f085068bcd32dcd38e479bba58909254af7f"}, - {file = "matplotlib-3.5.3-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:94ff86af56a3869a4ae26a9637a849effd7643858a1a04dd5ee50e9ab75069a7"}, - {file = "matplotlib-3.5.3-cp37-cp37m-win32.whl", hash = "sha256:35a8ad4dddebd51f94c5d24bec689ec0ec66173bf614374a1244c6241c1595e0"}, - {file = "matplotlib-3.5.3-cp37-cp37m-win_amd64.whl", hash = "sha256:43e9d3fa077bf0cc95ded13d331d2156f9973dce17c6f0c8b49ccd57af94dbd9"}, - {file = "matplotlib-3.5.3-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:22227c976ad4dc8c5a5057540421f0d8708c6560744ad2ad638d48e2984e1dbc"}, - {file = "matplotlib-3.5.3-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:bf618a825deb6205f015df6dfe6167a5d9b351203b03fab82043ae1d30f16511"}, - {file = "matplotlib-3.5.3-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:9befa5954cdbc085e37d974ff6053da269474177921dd61facdad8023c4aeb51"}, - {file = "matplotlib-3.5.3-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f3840c280ebc87a48488a46f760ea1c0c0c83fcf7abbe2e6baf99d033fd35fd8"}, - {file = "matplotlib-3.5.3-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:dacddf5bfcec60e3f26ec5c0ae3d0274853a258b6c3fc5ef2f06a8eb23e042be"}, - {file = "matplotlib-3.5.3-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:b428076a55fb1c084c76cb93e68006f27d247169f056412607c5c88828d08f88"}, - {file = "matplotlib-3.5.3-cp38-cp38-win32.whl", hash = "sha256:874df7505ba820e0400e7091199decf3ff1fde0583652120c50cd60d5820ca9a"}, - {file = "matplotlib-3.5.3-cp38-cp38-win_amd64.whl", hash = "sha256:b28de401d928890187c589036857a270a032961411934bdac4cf12dde3d43094"}, - {file = "matplotlib-3.5.3-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:3211ba82b9f1518d346f6309df137b50c3dc4421b4ed4815d1d7eadc617f45a1"}, - {file = "matplotlib-3.5.3-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:6fe807e8a22620b4cd95cfbc795ba310dc80151d43b037257250faf0bfcd82bc"}, - {file = "matplotlib-3.5.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:5c096363b206a3caf43773abebdbb5a23ea13faef71d701b21a9c27fdcef72f4"}, - {file = "matplotlib-3.5.3-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0bcdfcb0f976e1bac6721d7d457c17be23cf7501f977b6a38f9d38a3762841f7"}, - {file = "matplotlib-3.5.3-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:1e64ac9be9da6bfff0a732e62116484b93b02a0b4d4b19934fb4f8e7ad26ad6a"}, - {file = "matplotlib-3.5.3-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:73dd93dc35c85dece610cca8358003bf0760d7986f70b223e2306b4ea6d1406b"}, - {file = "matplotlib-3.5.3-cp39-cp39-win32.whl", hash = "sha256:879c7e5fce4939c6aa04581dfe08d57eb6102a71f2e202e3314d5fbc072fd5a0"}, - {file = "matplotlib-3.5.3-cp39-cp39-win_amd64.whl", hash = "sha256:ab8d26f07fe64f6f6736d635cce7bfd7f625320490ed5bfc347f2cdb4fae0e56"}, - {file = "matplotlib-3.5.3-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:99482b83ebf4eb6d5fc6813d7aacdefdd480f0d9c0b52dcf9f1cc3b2c4b3361a"}, - {file = "matplotlib-3.5.3-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:f814504e459c68118bf2246a530ed953ebd18213dc20e3da524174d84ed010b2"}, - {file = "matplotlib-3.5.3-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:57f1b4e69f438a99bb64d7f2c340db1b096b41ebaa515cf61ea72624279220ce"}, - {file = "matplotlib-3.5.3-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:d2484b350bf3d32cae43f85dcfc89b3ed7bd2bcd781ef351f93eb6fb2cc483f9"}, - {file = "matplotlib-3.5.3.tar.gz", hash = "sha256:339cac48b80ddbc8bfd05daae0a3a73414651a8596904c2a881cfd1edb65f26c"}, +python-versions = ">=3.8" +files = [ + {file = "matplotlib-3.7.1-cp310-cp310-macosx_10_12_universal2.whl", hash = "sha256:95cbc13c1fc6844ab8812a525bbc237fa1470863ff3dace7352e910519e194b1"}, + {file = "matplotlib-3.7.1-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:08308bae9e91aca1ec6fd6dda66237eef9f6294ddb17f0d0b3c863169bf82353"}, + {file = "matplotlib-3.7.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:544764ba51900da4639c0f983b323d288f94f65f4024dc40ecb1542d74dc0500"}, + {file = "matplotlib-3.7.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:56d94989191de3fcc4e002f93f7f1be5da476385dde410ddafbb70686acf00ea"}, + {file = "matplotlib-3.7.1-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e99bc9e65901bb9a7ce5e7bb24af03675cbd7c70b30ac670aa263240635999a4"}, + {file = "matplotlib-3.7.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eb7d248c34a341cd4c31a06fd34d64306624c8cd8d0def7abb08792a5abfd556"}, + {file = "matplotlib-3.7.1-cp310-cp310-win32.whl", hash = "sha256:ce463ce590f3825b52e9fe5c19a3c6a69fd7675a39d589e8b5fbe772272b3a24"}, + {file = "matplotlib-3.7.1-cp310-cp310-win_amd64.whl", hash = "sha256:3d7bc90727351fb841e4d8ae620d2d86d8ed92b50473cd2b42ce9186104ecbba"}, + {file = "matplotlib-3.7.1-cp311-cp311-macosx_10_12_universal2.whl", hash = "sha256:770a205966d641627fd5cf9d3cb4b6280a716522cd36b8b284a8eb1581310f61"}, + {file = "matplotlib-3.7.1-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:f67bfdb83a8232cb7a92b869f9355d677bce24485c460b19d01970b64b2ed476"}, + {file = "matplotlib-3.7.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2bf092f9210e105f414a043b92af583c98f50050559616930d884387d0772aba"}, + {file = "matplotlib-3.7.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:89768d84187f31717349c6bfadc0e0d8c321e8eb34522acec8a67b1236a66332"}, + {file = "matplotlib-3.7.1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:83111e6388dec67822e2534e13b243cc644c7494a4bb60584edbff91585a83c6"}, + {file = "matplotlib-3.7.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a867bf73a7eb808ef2afbca03bcdb785dae09595fbe550e1bab0cd023eba3de0"}, + {file = "matplotlib-3.7.1-cp311-cp311-win32.whl", hash = "sha256:fbdeeb58c0cf0595efe89c05c224e0a502d1aa6a8696e68a73c3efc6bc354304"}, + {file = "matplotlib-3.7.1-cp311-cp311-win_amd64.whl", hash = "sha256:c0bd19c72ae53e6ab979f0ac6a3fafceb02d2ecafa023c5cca47acd934d10be7"}, + {file = "matplotlib-3.7.1-cp38-cp38-macosx_10_12_universal2.whl", hash = "sha256:6eb88d87cb2c49af00d3bbc33a003f89fd9f78d318848da029383bfc08ecfbfb"}, + {file = "matplotlib-3.7.1-cp38-cp38-macosx_10_12_x86_64.whl", hash = "sha256:cf0e4f727534b7b1457898c4f4ae838af1ef87c359b76dcd5330fa31893a3ac7"}, + {file = "matplotlib-3.7.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:46a561d23b91f30bccfd25429c3c706afe7d73a5cc64ef2dfaf2b2ac47c1a5dc"}, + {file = "matplotlib-3.7.1-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:8704726d33e9aa8a6d5215044b8d00804561971163563e6e6591f9dcf64340cc"}, + {file = "matplotlib-3.7.1-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:4cf327e98ecf08fcbb82685acaf1939d3338548620ab8dfa02828706402c34de"}, + {file = "matplotlib-3.7.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:617f14ae9d53292ece33f45cba8503494ee199a75b44de7717964f70637a36aa"}, + {file = "matplotlib-3.7.1-cp38-cp38-win32.whl", hash = "sha256:7c9a4b2da6fac77bcc41b1ea95fadb314e92508bf5493ceff058e727e7ecf5b0"}, + {file = "matplotlib-3.7.1-cp38-cp38-win_amd64.whl", hash = "sha256:14645aad967684e92fc349493fa10c08a6da514b3d03a5931a1bac26e6792bd1"}, + {file = "matplotlib-3.7.1-cp39-cp39-macosx_10_12_universal2.whl", hash = "sha256:81a6b377ea444336538638d31fdb39af6be1a043ca5e343fe18d0f17e098770b"}, + {file = "matplotlib-3.7.1-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:28506a03bd7f3fe59cd3cd4ceb2a8d8a2b1db41afede01f66c42561b9be7b4b7"}, + {file = "matplotlib-3.7.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:8c587963b85ce41e0a8af53b9b2de8dddbf5ece4c34553f7bd9d066148dc719c"}, + {file = "matplotlib-3.7.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8bf26ade3ff0f27668989d98c8435ce9327d24cffb7f07d24ef609e33d582439"}, + {file = "matplotlib-3.7.1-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:def58098f96a05f90af7e92fd127d21a287068202aa43b2a93476170ebd99e87"}, + {file = "matplotlib-3.7.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f883a22a56a84dba3b588696a2b8a1ab0d2c3d41be53264115c71b0a942d8fdb"}, + {file = "matplotlib-3.7.1-cp39-cp39-win32.whl", hash = "sha256:4f99e1b234c30c1e9714610eb0c6d2f11809c9c78c984a613ae539ea2ad2eb4b"}, + {file = "matplotlib-3.7.1-cp39-cp39-win_amd64.whl", hash = "sha256:3ba2af245e36990facf67fde840a760128ddd71210b2ab6406e640188d69d136"}, + {file = "matplotlib-3.7.1-pp38-pypy38_pp73-macosx_10_12_x86_64.whl", hash = "sha256:3032884084f541163f295db8a6536e0abb0db464008fadca6c98aaf84ccf4717"}, + {file = "matplotlib-3.7.1-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3a2cb34336110e0ed8bb4f650e817eed61fa064acbefeb3591f1b33e3a84fd96"}, + {file = "matplotlib-3.7.1-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b867e2f952ed592237a1828f027d332d8ee219ad722345b79a001f49df0936eb"}, + {file = "matplotlib-3.7.1-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:57bfb8c8ea253be947ccb2bc2d1bb3862c2bccc662ad1b4626e1f5e004557042"}, + {file = "matplotlib-3.7.1-pp39-pypy39_pp73-macosx_10_12_x86_64.whl", hash = "sha256:438196cdf5dc8d39b50a45cb6e3f6274edbcf2254f85fa9b895bf85851c3a613"}, + {file = "matplotlib-3.7.1-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:21e9cff1a58d42e74d01153360de92b326708fb205250150018a52c70f43c290"}, + {file = "matplotlib-3.7.1-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:75d4725d70b7c03e082bbb8a34639ede17f333d7247f56caceb3801cb6ff703d"}, + {file = "matplotlib-3.7.1-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:97cc368a7268141afb5690760921765ed34867ffb9655dd325ed207af85c7529"}, + {file = "matplotlib-3.7.1.tar.gz", hash = "sha256:7b73305f25eab4541bd7ee0b96d87e53ae9c9f1823be5659b806cd85786fe882"}, ] [package.dependencies] +contourpy = ">=1.0.1" cycler = ">=0.10" fonttools = ">=4.22.0" +importlib-resources = {version = ">=3.2.0", markers = "python_version < \"3.10\""} kiwisolver = ">=1.0.1" -numpy = ">=1.17" +numpy = ">=1.20" packaging = ">=20.0" pillow = ">=6.2.0" -pyparsing = ">=2.2.1" +pyparsing = ">=2.3.1" python-dateutil = ">=2.7" [[package]] @@ -1096,14 +1263,14 @@ files = [ [[package]] name = "nodeenv" -version = "1.7.0" +version = "1.8.0" description = "Node.js virtual environment builder" category = "dev" optional = false python-versions = ">=2.7,!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,!=3.6.*" files = [ - {file = "nodeenv-1.7.0-py2.py3-none-any.whl", hash = "sha256:27083a7b96a25f2f5e1d8cb4b6317ee8aeda3bdd121394e5ac54e498028a042e"}, - {file = "nodeenv-1.7.0.tar.gz", hash = "sha256:e0e7f7dfb85fc5394c6fe1e8fa98131a2473e04311a45afb6508f7cf1836fa2b"}, + {file = "nodeenv-1.8.0-py2.py3-none-any.whl", hash = "sha256:df865724bb3c3adc86b3876fa209771517b0cfe596beff01a92700e0e8be4cec"}, + {file = "nodeenv-1.8.0.tar.gz", hash = "sha256:d51e0c37e64fbf47d017feac3145cdbb58836d7eee8c6f6d3b6880c5456227d2"}, ] [package.dependencies] @@ -1111,43 +1278,40 @@ setuptools = "*" [[package]] name = "numpy" -version = "1.21.6" -description = "NumPy is the fundamental package for array computing with Python." +version = "1.24.3" +description = "Fundamental package for array computing in Python" category = "main" optional = false -python-versions = ">=3.7,<3.11" -files = [ - {file = "numpy-1.21.6-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:8737609c3bbdd48e380d463134a35ffad3b22dc56295eff6f79fd85bd0eeeb25"}, - {file = "numpy-1.21.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:fdffbfb6832cd0b300995a2b08b8f6fa9f6e856d562800fea9182316d99c4e8e"}, - {file = "numpy-1.21.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:3820724272f9913b597ccd13a467cc492a0da6b05df26ea09e78b171a0bb9da6"}, - {file = "numpy-1.21.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f17e562de9edf691a42ddb1eb4a5541c20dd3f9e65b09ded2beb0799c0cf29bb"}, - {file = "numpy-1.21.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5f30427731561ce75d7048ac254dbe47a2ba576229250fb60f0fb74db96501a1"}, - {file = "numpy-1.21.6-cp310-cp310-win32.whl", hash = "sha256:d4bf4d43077db55589ffc9009c0ba0a94fa4908b9586d6ccce2e0b164c86303c"}, - {file = "numpy-1.21.6-cp310-cp310-win_amd64.whl", hash = "sha256:d136337ae3cc69aa5e447e78d8e1514be8c3ec9b54264e680cf0b4bd9011574f"}, - {file = "numpy-1.21.6-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:6aaf96c7f8cebc220cdfc03f1d5a31952f027dda050e5a703a0d1c396075e3e7"}, - {file = "numpy-1.21.6-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:67c261d6c0a9981820c3a149d255a76918278a6b03b6a036800359aba1256d46"}, - {file = "numpy-1.21.6-cp37-cp37m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:a6be4cb0ef3b8c9250c19cc122267263093eee7edd4e3fa75395dfda8c17a8e2"}, - {file = "numpy-1.21.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7c4068a8c44014b2d55f3c3f574c376b2494ca9cc73d2f1bd692382b6dffe3db"}, - {file = "numpy-1.21.6-cp37-cp37m-win32.whl", hash = "sha256:7c7e5fa88d9ff656e067876e4736379cc962d185d5cd808014a8a928d529ef4e"}, - {file = "numpy-1.21.6-cp37-cp37m-win_amd64.whl", hash = "sha256:bcb238c9c96c00d3085b264e5c1a1207672577b93fa666c3b14a45240b14123a"}, - {file = "numpy-1.21.6-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:82691fda7c3f77c90e62da69ae60b5ac08e87e775b09813559f8901a88266552"}, - {file = "numpy-1.21.6-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:643843bcc1c50526b3a71cd2ee561cf0d8773f062c8cbaf9ffac9fdf573f83ab"}, - {file = "numpy-1.21.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:357768c2e4451ac241465157a3e929b265dfac85d9214074985b1786244f2ef3"}, - {file = "numpy-1.21.6-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:9f411b2c3f3d76bba0865b35a425157c5dcf54937f82bbeb3d3c180789dd66a6"}, - {file = "numpy-1.21.6-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:4aa48afdce4660b0076a00d80afa54e8a97cd49f457d68a4342d188a09451c1a"}, - {file = "numpy-1.21.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d6a96eef20f639e6a97d23e57dd0c1b1069a7b4fd7027482a4c5c451cd7732f4"}, - {file = "numpy-1.21.6-cp38-cp38-win32.whl", hash = "sha256:5c3c8def4230e1b959671eb959083661b4a0d2e9af93ee339c7dada6759a9470"}, - {file = "numpy-1.21.6-cp38-cp38-win_amd64.whl", hash = "sha256:bf2ec4b75d0e9356edea834d1de42b31fe11f726a81dfb2c2112bc1eaa508fcf"}, - {file = "numpy-1.21.6-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:4391bd07606be175aafd267ef9bea87cf1b8210c787666ce82073b05f202add1"}, - {file = "numpy-1.21.6-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:67f21981ba2f9d7ba9ade60c9e8cbaa8cf8e9ae51673934480e45cf55e953673"}, - {file = "numpy-1.21.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:ee5ec40fdd06d62fe5d4084bef4fd50fd4bb6bfd2bf519365f569dc470163ab0"}, - {file = "numpy-1.21.6-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:1dbe1c91269f880e364526649a52eff93ac30035507ae980d2fed33aaee633ac"}, - {file = "numpy-1.21.6-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:d9caa9d5e682102453d96a0ee10c7241b72859b01a941a397fd965f23b3e016b"}, - {file = "numpy-1.21.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:58459d3bad03343ac4b1b42ed14d571b8743dc80ccbf27444f266729df1d6f5b"}, - {file = "numpy-1.21.6-cp39-cp39-win32.whl", hash = "sha256:7f5ae4f304257569ef3b948810816bc87c9146e8c446053539947eedeaa32786"}, - {file = "numpy-1.21.6-cp39-cp39-win_amd64.whl", hash = "sha256:e31f0bb5928b793169b87e3d1e070f2342b22d5245c755e2b81caa29756246c3"}, - {file = "numpy-1.21.6-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:dd1c8f6bd65d07d3810b90d02eba7997e32abbdf1277a481d698969e921a3be0"}, - {file = "numpy-1.21.6.zip", hash = "sha256:ecb55251139706669fdec2ff073c98ef8e9a84473e51e716211b41aa0f18e656"}, +python-versions = ">=3.8" +files = [ + {file = "numpy-1.24.3-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:3c1104d3c036fb81ab923f507536daedc718d0ad5a8707c6061cdfd6d184e570"}, + {file = "numpy-1.24.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:202de8f38fc4a45a3eea4b63e2f376e5f2dc64ef0fa692838e31a808520efaf7"}, + {file = "numpy-1.24.3-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8535303847b89aa6b0f00aa1dc62867b5a32923e4d1681a35b5eef2d9591a463"}, + {file = "numpy-1.24.3-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2d926b52ba1367f9acb76b0df6ed21f0b16a1ad87c6720a1121674e5cf63e2b6"}, + {file = "numpy-1.24.3-cp310-cp310-win32.whl", hash = "sha256:f21c442fdd2805e91799fbe044a7b999b8571bb0ab0f7850d0cb9641a687092b"}, + {file = "numpy-1.24.3-cp310-cp310-win_amd64.whl", hash = "sha256:ab5f23af8c16022663a652d3b25dcdc272ac3f83c3af4c02eb8b824e6b3ab9d7"}, + {file = "numpy-1.24.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:9a7721ec204d3a237225db3e194c25268faf92e19338a35f3a224469cb6039a3"}, + {file = "numpy-1.24.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d6cc757de514c00b24ae8cf5c876af2a7c3df189028d68c0cb4eaa9cd5afc2bf"}, + {file = "numpy-1.24.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76e3f4e85fc5d4fd311f6e9b794d0c00e7002ec122be271f2019d63376f1d385"}, + {file = "numpy-1.24.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a1d3c026f57ceaad42f8231305d4653d5f05dc6332a730ae5c0bea3513de0950"}, + {file = "numpy-1.24.3-cp311-cp311-win32.whl", hash = "sha256:c91c4afd8abc3908e00a44b2672718905b8611503f7ff87390cc0ac3423fb096"}, + {file = "numpy-1.24.3-cp311-cp311-win_amd64.whl", hash = "sha256:5342cf6aad47943286afa6f1609cad9b4266a05e7f2ec408e2cf7aea7ff69d80"}, + {file = "numpy-1.24.3-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:7776ea65423ca6a15255ba1872d82d207bd1e09f6d0894ee4a64678dd2204078"}, + {file = "numpy-1.24.3-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:ae8d0be48d1b6ed82588934aaaa179875e7dc4f3d84da18d7eae6eb3f06c242c"}, + {file = "numpy-1.24.3-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ecde0f8adef7dfdec993fd54b0f78183051b6580f606111a6d789cd14c61ea0c"}, + {file = "numpy-1.24.3-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4749e053a29364d3452c034827102ee100986903263e89884922ef01a0a6fd2f"}, + {file = "numpy-1.24.3-cp38-cp38-win32.whl", hash = "sha256:d933fabd8f6a319e8530d0de4fcc2e6a61917e0b0c271fded460032db42a0fe4"}, + {file = "numpy-1.24.3-cp38-cp38-win_amd64.whl", hash = "sha256:56e48aec79ae238f6e4395886b5eaed058abb7231fb3361ddd7bfdf4eed54289"}, + {file = "numpy-1.24.3-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:4719d5aefb5189f50887773699eaf94e7d1e02bf36c1a9d353d9f46703758ca4"}, + {file = "numpy-1.24.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:0ec87a7084caa559c36e0a2309e4ecb1baa03b687201d0a847c8b0ed476a7187"}, + {file = "numpy-1.24.3-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ea8282b9bcfe2b5e7d491d0bf7f3e2da29700cec05b49e64d6246923329f2b02"}, + {file = "numpy-1.24.3-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:210461d87fb02a84ef243cac5e814aad2b7f4be953b32cb53327bb49fd77fbb4"}, + {file = "numpy-1.24.3-cp39-cp39-win32.whl", hash = "sha256:784c6da1a07818491b0ffd63c6bbe5a33deaa0e25a20e1b3ea20cf0e43f8046c"}, + {file = "numpy-1.24.3-cp39-cp39-win_amd64.whl", hash = "sha256:d5036197ecae68d7f491fcdb4df90082b0d4960ca6599ba2659957aafced7c17"}, + {file = "numpy-1.24.3-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:352ee00c7f8387b44d19f4cada524586f07379c0d49270f87233983bc5087ca0"}, + {file = "numpy-1.24.3-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1a7d6acc2e7524c9955e5c903160aa4ea083736fde7e91276b0e5d98e6332812"}, + {file = "numpy-1.24.3-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:35400e6a8d102fd07c71ed7dcadd9eb62ee9a6e84ec159bd48c28235bbb0f8e4"}, + {file = "numpy-1.24.3.tar.gz", hash = "sha256:ab344f1bf21f140adab8e47fdbc7c35a477dc01408791f8ba00d018dd0bc5155"}, ] [[package]] @@ -1164,51 +1328,52 @@ files = [ [[package]] name = "pandas" -version = "1.3.5" +version = "1.5.3" description = "Powerful data structures for data analysis, time series, and statistics" category = "main" optional = true -python-versions = ">=3.7.1" -files = [ - {file = "pandas-1.3.5-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:62d5b5ce965bae78f12c1c0df0d387899dd4211ec0bdc52822373f13a3a022b9"}, - {file = "pandas-1.3.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:adfeb11be2d54f275142c8ba9bf67acee771b7186a5745249c7d5a06c670136b"}, - {file = "pandas-1.3.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:60a8c055d58873ad81cae290d974d13dd479b82cbb975c3e1fa2cf1920715296"}, - {file = "pandas-1.3.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fd541ab09e1f80a2a1760032d665f6e032d8e44055d602d65eeea6e6e85498cb"}, - {file = "pandas-1.3.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2651d75b9a167cc8cc572cf787ab512d16e316ae00ba81874b560586fa1325e0"}, - {file = "pandas-1.3.5-cp310-cp310-win_amd64.whl", hash = "sha256:aaf183a615ad790801fa3cf2fa450e5b6d23a54684fe386f7e3208f8b9bfbef6"}, - {file = "pandas-1.3.5-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:344295811e67f8200de2390093aeb3c8309f5648951b684d8db7eee7d1c81fb7"}, - {file = "pandas-1.3.5-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:552020bf83b7f9033b57cbae65589c01e7ef1544416122da0c79140c93288f56"}, - {file = "pandas-1.3.5-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5cce0c6bbeb266b0e39e35176ee615ce3585233092f685b6a82362523e59e5b4"}, - {file = "pandas-1.3.5-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7d28a3c65463fd0d0ba8bbb7696b23073efee0510783340a44b08f5e96ffce0c"}, - {file = "pandas-1.3.5-cp37-cp37m-win32.whl", hash = "sha256:a62949c626dd0ef7de11de34b44c6475db76995c2064e2d99c6498c3dba7fe58"}, - {file = "pandas-1.3.5-cp37-cp37m-win_amd64.whl", hash = "sha256:8025750767e138320b15ca16d70d5cdc1886e8f9cc56652d89735c016cd8aea6"}, - {file = "pandas-1.3.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:fe95bae4e2d579812865db2212bb733144e34d0c6785c0685329e5b60fcb85dd"}, - {file = "pandas-1.3.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5f261553a1e9c65b7a310302b9dbac31cf0049a51695c14ebe04e4bfd4a96f02"}, - {file = "pandas-1.3.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8b6dbec5f3e6d5dc80dcfee250e0a2a652b3f28663492f7dab9a24416a48ac39"}, - {file = "pandas-1.3.5-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d3bc49af96cd6285030a64779de5b3688633a07eb75c124b0747134a63f4c05f"}, - {file = "pandas-1.3.5-cp38-cp38-win32.whl", hash = "sha256:b6b87b2fb39e6383ca28e2829cddef1d9fc9e27e55ad91ca9c435572cdba51bf"}, - {file = "pandas-1.3.5-cp38-cp38-win_amd64.whl", hash = "sha256:a395692046fd8ce1edb4c6295c35184ae0c2bbe787ecbe384251da609e27edcb"}, - {file = "pandas-1.3.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:bd971a3f08b745a75a86c00b97f3007c2ea175951286cdda6abe543e687e5f2f"}, - {file = "pandas-1.3.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:37f06b59e5bc05711a518aa10beaec10942188dccb48918bb5ae602ccbc9f1a0"}, - {file = "pandas-1.3.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2c21778a688d3712d35710501f8001cdbf96eb70a7c587a3d5613573299fdca6"}, - {file = "pandas-1.3.5-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3345343206546545bc26a05b4602b6a24385b5ec7c75cb6059599e3d56831da2"}, - {file = "pandas-1.3.5-cp39-cp39-win32.whl", hash = "sha256:c69406a2808ba6cf580c2255bcf260b3f214d2664a3a4197d0e640f573b46fd3"}, - {file = "pandas-1.3.5-cp39-cp39-win_amd64.whl", hash = "sha256:32e1a26d5ade11b547721a72f9bfc4bd113396947606e00d5b4a5b79b3dcb006"}, - {file = "pandas-1.3.5.tar.gz", hash = "sha256:1e4285f5de1012de20ca46b188ccf33521bff61ba5c5ebd78b4fb28e5416a9f1"}, +python-versions = ">=3.8" +files = [ + {file = "pandas-1.5.3-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:3749077d86e3a2f0ed51367f30bf5b82e131cc0f14260c4d3e499186fccc4406"}, + {file = "pandas-1.5.3-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:972d8a45395f2a2d26733eb8d0f629b2f90bebe8e8eddbb8829b180c09639572"}, + {file = "pandas-1.5.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:50869a35cbb0f2e0cd5ec04b191e7b12ed688874bd05dd777c19b28cbea90996"}, + {file = "pandas-1.5.3-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c3ac844a0fe00bfaeb2c9b51ab1424e5c8744f89860b138434a363b1f620f354"}, + {file = "pandas-1.5.3-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7a0a56cef15fd1586726dace5616db75ebcfec9179a3a55e78f72c5639fa2a23"}, + {file = "pandas-1.5.3-cp310-cp310-win_amd64.whl", hash = "sha256:478ff646ca42b20376e4ed3fa2e8d7341e8a63105586efe54fa2508ee087f328"}, + {file = "pandas-1.5.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6973549c01ca91ec96199e940495219c887ea815b2083722821f1d7abfa2b4dc"}, + {file = "pandas-1.5.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c39a8da13cede5adcd3be1182883aea1c925476f4e84b2807a46e2775306305d"}, + {file = "pandas-1.5.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f76d097d12c82a535fda9dfe5e8dd4127952b45fea9b0276cb30cca5ea313fbc"}, + {file = "pandas-1.5.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e474390e60ed609cec869b0da796ad94f420bb057d86784191eefc62b65819ae"}, + {file = "pandas-1.5.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5f2b952406a1588ad4cad5b3f55f520e82e902388a6d5a4a91baa8d38d23c7f6"}, + {file = "pandas-1.5.3-cp311-cp311-win_amd64.whl", hash = "sha256:bc4c368f42b551bf72fac35c5128963a171b40dce866fb066540eeaf46faa003"}, + {file = "pandas-1.5.3-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:14e45300521902689a81f3f41386dc86f19b8ba8dd5ac5a3c7010ef8d2932813"}, + {file = "pandas-1.5.3-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:9842b6f4b8479e41968eced654487258ed81df7d1c9b7b870ceea24ed9459b31"}, + {file = "pandas-1.5.3-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:26d9c71772c7afb9d5046e6e9cf42d83dd147b5cf5bcb9d97252077118543792"}, + {file = "pandas-1.5.3-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5fbcb19d6fceb9e946b3e23258757c7b225ba450990d9ed63ccceeb8cae609f7"}, + {file = "pandas-1.5.3-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:565fa34a5434d38e9d250af3c12ff931abaf88050551d9fbcdfafca50d62babf"}, + {file = "pandas-1.5.3-cp38-cp38-win32.whl", hash = "sha256:87bd9c03da1ac870a6d2c8902a0e1fd4267ca00f13bc494c9e5a9020920e1d51"}, + {file = "pandas-1.5.3-cp38-cp38-win_amd64.whl", hash = "sha256:41179ce559943d83a9b4bbacb736b04c928b095b5f25dd2b7389eda08f46f373"}, + {file = "pandas-1.5.3-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:c74a62747864ed568f5a82a49a23a8d7fe171d0c69038b38cedf0976831296fa"}, + {file = "pandas-1.5.3-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:c4c00e0b0597c8e4f59e8d461f797e5d70b4d025880516a8261b2817c47759ee"}, + {file = "pandas-1.5.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:a50d9a4336a9621cab7b8eb3fb11adb82de58f9b91d84c2cd526576b881a0c5a"}, + {file = "pandas-1.5.3-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dd05f7783b3274aa206a1af06f0ceed3f9b412cf665b7247eacd83be41cf7bf0"}, + {file = "pandas-1.5.3-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9f69c4029613de47816b1bb30ff5ac778686688751a5e9c99ad8c7031f6508e5"}, + {file = "pandas-1.5.3-cp39-cp39-win32.whl", hash = "sha256:7cec0bee9f294e5de5bbfc14d0573f65526071029d036b753ee6507d2a21480a"}, + {file = "pandas-1.5.3-cp39-cp39-win_amd64.whl", hash = "sha256:dfd681c5dc216037e0b0a2c821f5ed99ba9f03ebcf119c7dac0e9a7b960b9ec9"}, + {file = "pandas-1.5.3.tar.gz", hash = "sha256:74a3fd7e5a7ec052f183273dc7b0acd3a863edf7520f5d3a1765c04ffdb3b0b1"}, ] [package.dependencies] numpy = [ - {version = ">=1.17.3", markers = "platform_machine != \"aarch64\" and platform_machine != \"arm64\" and python_version < \"3.10\""}, - {version = ">=1.19.2", markers = "platform_machine == \"aarch64\" and python_version < \"3.10\""}, - {version = ">=1.20.0", markers = "platform_machine == \"arm64\" and python_version < \"3.10\""}, + {version = ">=1.20.3", markers = "python_version < \"3.10\""}, {version = ">=1.21.0", markers = "python_version >= \"3.10\""}, + {version = ">=1.23.2", markers = "python_version >= \"3.11\""}, ] -python-dateutil = ">=2.7.3" -pytz = ">=2017.3" +python-dateutil = ">=2.8.1" +pytz = ">=2020.1" [package.extras] -test = ["hypothesis (>=3.58)", "pytest (>=6.0)", "pytest-xdist"] +test = ["hypothesis (>=5.5.3)", "pytest (>=6.0)", "pytest-xdist (>=1.31)"] [[package]] name = "pathspec" @@ -1322,28 +1487,25 @@ tests = ["check-manifest", "coverage", "defusedxml", "markdown2", "olefile", "pa [[package]] name = "platformdirs" -version = "3.5.0" +version = "3.5.1" description = "A small Python package for determining appropriate platform-specific dirs, e.g. a \"user data dir\"." category = "dev" optional = false python-versions = ">=3.7" files = [ - {file = "platformdirs-3.5.0-py3-none-any.whl", hash = "sha256:47692bc24c1958e8b0f13dd727307cff1db103fca36399f457da8e05f222fdc4"}, - {file = "platformdirs-3.5.0.tar.gz", hash = "sha256:7954a68d0ba23558d753f73437c55f89027cf8f5108c19844d4b82e5af396335"}, + {file = "platformdirs-3.5.1-py3-none-any.whl", hash = "sha256:e2378146f1964972c03c085bb5662ae80b2b8c06226c54b2ff4aa9483e8a13a5"}, + {file = "platformdirs-3.5.1.tar.gz", hash = "sha256:412dae91f52a6f84830f39a8078cecd0e866cb72294a5c66808e74d5e88d251f"}, ] -[package.dependencies] -typing-extensions = {version = ">=4.5", markers = "python_version < \"3.8\""} - [package.extras] -docs = ["furo (>=2023.3.27)", "proselint (>=0.13)", "sphinx (>=6.1.3)", "sphinx-autodoc-typehints (>=1.23,!=1.23.4)"] +docs = ["furo (>=2023.3.27)", "proselint (>=0.13)", "sphinx (>=6.2.1)", "sphinx-autodoc-typehints (>=1.23,!=1.23.4)"] test = ["appdirs (==1.4.4)", "covdefaults (>=2.3)", "pytest (>=7.3.1)", "pytest-cov (>=4)", "pytest-mock (>=3.10)"] [[package]] name = "pluggy" version = "1.0.0" description = "plugin and hook calling mechanisms for python" -category = "main" +category = "dev" optional = false python-versions = ">=3.6" files = [ @@ -1351,9 +1513,6 @@ files = [ {file = "pluggy-1.0.0.tar.gz", hash = "sha256:4224373bacce55f955a878bf9cfa763c1e360858e330072059e10bad68531159"}, ] -[package.dependencies] -importlib-metadata = {version = ">=0.12", markers = "python_version < \"3.8\""} - [package.extras] dev = ["pre-commit", "tox"] testing = ["pytest", "pytest-benchmark"] @@ -1397,18 +1556,58 @@ files = [ "aspy.yaml" = "*" cfgv = ">=2.0.0" identify = ">=1.0.0" -importlib-metadata = {version = "*", markers = "python_version < \"3.8\""} nodeenv = ">=0.11.1" pyyaml = "*" six = "*" toml = "*" virtualenv = ">=15.2" +[[package]] +name = "proto-plus" +version = "1.22.2" +description = "Beautiful, Pythonic protocol buffers." +category = "main" +optional = false +python-versions = ">=3.6" +files = [ + {file = "proto-plus-1.22.2.tar.gz", hash = "sha256:0e8cda3d5a634d9895b75c573c9352c16486cb75deb0e078b5fda34db4243165"}, + {file = "proto_plus-1.22.2-py3-none-any.whl", hash = "sha256:de34e52d6c9c6fcd704192f09767cb561bb4ee64e70eede20b0834d841f0be4d"}, +] + +[package.dependencies] +protobuf = ">=3.19.0,<5.0.0dev" + +[package.extras] +testing = ["google-api-core[grpc] (>=1.31.5)"] + +[[package]] +name = "protobuf" +version = "4.23.1" +description = "" +category = "main" +optional = false +python-versions = ">=3.7" +files = [ + {file = "protobuf-4.23.1-cp310-abi3-win32.whl", hash = "sha256:410bcc0a5b279f634d3e16082ce221dfef7c3392fac723500e2e64d1806dd2be"}, + {file = "protobuf-4.23.1-cp310-abi3-win_amd64.whl", hash = "sha256:32e78beda26d7a101fecf15d7a4a792278a0d26a31bc327ff05564a9d68ab8ee"}, + {file = "protobuf-4.23.1-cp37-abi3-macosx_10_9_universal2.whl", hash = "sha256:f9510cac91e764e86acd74e2b7f7bc5e6127a7f3fb646d7c8033cfb84fd1176a"}, + {file = "protobuf-4.23.1-cp37-abi3-manylinux2014_aarch64.whl", hash = "sha256:346990f634272caac1f09efbcfbbacb23098b1f606d172534c6fa2d9758bb436"}, + {file = "protobuf-4.23.1-cp37-abi3-manylinux2014_x86_64.whl", hash = "sha256:3ce113b3f3362493bddc9069c2163a38f240a9ed685ff83e7bcb756b05e1deb0"}, + {file = "protobuf-4.23.1-cp37-cp37m-win32.whl", hash = "sha256:2036a3a1e7fc27f973fa0a7888dce712393af644f4695385f117886abc792e39"}, + {file = "protobuf-4.23.1-cp37-cp37m-win_amd64.whl", hash = "sha256:3b8905eafe4439076e1f58e9d1fa327025fd2777cf90f14083092ae47f77b0aa"}, + {file = "protobuf-4.23.1-cp38-cp38-win32.whl", hash = "sha256:5b9cd6097e6acae48a68cb29b56bc79339be84eca65b486910bb1e7a30e2b7c1"}, + {file = "protobuf-4.23.1-cp38-cp38-win_amd64.whl", hash = "sha256:decf119d54e820f298ee6d89c72d6b289ea240c32c521f00433f9dc420595f38"}, + {file = "protobuf-4.23.1-cp39-cp39-win32.whl", hash = "sha256:91fac0753c3c4951fbb98a93271c43cc7cf3b93cf67747b3e600bb1e5cc14d61"}, + {file = "protobuf-4.23.1-cp39-cp39-win_amd64.whl", hash = "sha256:ac50be82491369a9ec3710565777e4da87c6d2e20404e0abb1f3a8f10ffd20f0"}, + {file = "protobuf-4.23.1-py3-none-any.whl", hash = "sha256:65f0ac96ef67d7dd09b19a46aad81a851b6f85f89725577f16de38f2d68ad477"}, + {file = "protobuf-4.23.1.tar.gz", hash = "sha256:95789b569418a3e32a53f43d7763be3d490a831e9c08042539462b6d972c2d7e"}, +] + [[package]] name = "py" version = "1.11.0" description = "library with cross-python path, ini-parsing, io, code, log facilities" -category = "main" +category = "dev" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" files = [ @@ -1428,6 +1627,18 @@ files = [ {file = "pycodestyle-2.7.0.tar.gz", hash = "sha256:c389c1d06bf7904078ca03399a4816f974a1d590090fecea0c63ec26ebaf1cef"}, ] +[[package]] +name = "pycparser" +version = "2.21" +description = "C parser in Python" +category = "main" +optional = false +python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" +files = [ + {file = "pycparser-2.21-py2.py3-none-any.whl", hash = "sha256:8ee45429555515e1f6b185e78100aea234072576aa43ab53aefcae078162fca9"}, + {file = "pycparser-2.21.tar.gz", hash = "sha256:e644fdec12f7872f86c58ff790da456218b10f863970249516d60a5eaca77206"}, +] + [[package]] name = "pyfiglet" version = "0.8.post1" @@ -1469,14 +1680,14 @@ plugins = ["importlib-metadata"] [[package]] name = "pymdown-extensions" -version = "9.11" +version = "10.0.1" description = "Extension pack for Python Markdown." category = "dev" optional = false python-versions = ">=3.7" files = [ - {file = "pymdown_extensions-9.11-py3-none-any.whl", hash = "sha256:a499191d8d869f30339de86fcf072a787e86c42b6f16f280f5c2cf174182b7f3"}, - {file = "pymdown_extensions-9.11.tar.gz", hash = "sha256:f7e86c1d3981f23d9dc43294488ecb54abadd05b0be4bf8f0e15efc90f7853ff"}, + {file = "pymdown_extensions-10.0.1-py3-none-any.whl", hash = "sha256:ae66d84013c5d027ce055693e09a4628b67e9dec5bce05727e45b0918e36f274"}, + {file = "pymdown_extensions-10.0.1.tar.gz", hash = "sha256:b44e1093a43b8a975eae17b03c3a77aad4681b3b56fce60ce746dbef1944c8cb"}, ] [package.dependencies] @@ -1502,7 +1713,7 @@ diagrams = ["jinja2", "railroad-diagrams"] name = "pytest" version = "6.2.5" description = "pytest: simple powerful testing with Python" -category = "main" +category = "dev" optional = false python-versions = ">=3.6" files = [ @@ -1514,7 +1725,6 @@ files = [ atomicwrites = {version = ">=1.0", markers = "sys_platform == \"win32\""} attrs = ">=19.2.0" colorama = {version = "*", markers = "sys_platform == \"win32\""} -importlib-metadata = {version = ">=0.12", markers = "python_version < \"3.8\""} iniconfig = "*" packaging = "*" pluggy = ">=0.12,<2.0" @@ -1562,21 +1772,6 @@ pytest = ">=2.7" [package.extras] dev = ["pre-commit", "tox"] -[[package]] -name = "pytest-timeout" -version = "1.4.2" -description = "py.test plugin to abort hanging tests" -category = "main" -optional = false -python-versions = "*" -files = [ - {file = "pytest-timeout-1.4.2.tar.gz", hash = "sha256:20b3113cf6e4e80ce2d403b6fb56e9e1b871b510259206d40ff8d609f48bda76"}, - {file = "pytest_timeout-1.4.2-py2.py3-none-any.whl", hash = "sha256:541d7aa19b9a6b4e475c759fd6073ef43d7cdc9a92d95644c260076eb257a063"}, -] - -[package.dependencies] -pytest = ">=3.6.0" - [[package]] name = "python-dateutil" version = "2.8.2" @@ -1693,6 +1888,96 @@ files = [ [package.dependencies] pyyaml = "*" +[[package]] +name = "pyzmq" +version = "25.0.2" +description = "Python bindings for 0MQ" +category = "main" +optional = false +python-versions = ">=3.6" +files = [ + {file = "pyzmq-25.0.2-cp310-cp310-macosx_10_15_universal2.whl", hash = "sha256:ac178e666c097c8d3deb5097b58cd1316092fc43e8ef5b5fdb259b51da7e7315"}, + {file = "pyzmq-25.0.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:659e62e1cbb063151c52f5b01a38e1df6b54feccfa3e2509d44c35ca6d7962ee"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8280ada89010735a12b968ec3ea9a468ac2e04fddcc1cede59cb7f5178783b9c"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a9b5eeb5278a8a636bb0abdd9ff5076bcbb836cd2302565df53ff1fa7d106d54"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9a2e5fe42dfe6b73ca120b97ac9f34bfa8414feb15e00e37415dbd51cf227ef6"}, + {file = "pyzmq-25.0.2-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:827bf60e749e78acb408a6c5af6688efbc9993e44ecc792b036ec2f4b4acf485"}, + {file = "pyzmq-25.0.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:7b504ae43d37e282301da586529e2ded8b36d4ee2cd5e6db4386724ddeaa6bbc"}, + {file = "pyzmq-25.0.2-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:cb1f69a0a2a2b1aae8412979dd6293cc6bcddd4439bf07e4758d864ddb112354"}, + {file = "pyzmq-25.0.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:2b9c9cc965cdf28381e36da525dcb89fc1571d9c54800fdcd73e3f73a2fc29bd"}, + {file = "pyzmq-25.0.2-cp310-cp310-win32.whl", hash = "sha256:24abbfdbb75ac5039205e72d6c75f10fc39d925f2df8ff21ebc74179488ebfca"}, + {file = "pyzmq-25.0.2-cp310-cp310-win_amd64.whl", hash = "sha256:6a821a506822fac55d2df2085a52530f68ab15ceed12d63539adc32bd4410f6e"}, + {file = "pyzmq-25.0.2-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:9af0bb0277e92f41af35e991c242c9c71920169d6aa53ade7e444f338f4c8128"}, + {file = "pyzmq-25.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:54a96cf77684a3a537b76acfa7237b1e79a8f8d14e7f00e0171a94b346c5293e"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88649b19ede1cab03b96b66c364cbbf17c953615cdbc844f7f6e5f14c5e5261c"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:715cff7644a80a7795953c11b067a75f16eb9fc695a5a53316891ebee7f3c9d5"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:312b3f0f066b4f1d17383aae509bacf833ccaf591184a1f3c7a1661c085063ae"}, + {file = "pyzmq-25.0.2-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:d488c5c8630f7e782e800869f82744c3aca4aca62c63232e5d8c490d3d66956a"}, + {file = "pyzmq-25.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:38d9f78d69bcdeec0c11e0feb3bc70f36f9b8c44fc06e5d06d91dc0a21b453c7"}, + {file = "pyzmq-25.0.2-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:3059a6a534c910e1d5d068df42f60d434f79e6cc6285aa469b384fa921f78cf8"}, + {file = "pyzmq-25.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:6526d097b75192f228c09d48420854d53dfbc7abbb41b0e26f363ccb26fbc177"}, + {file = "pyzmq-25.0.2-cp311-cp311-win32.whl", hash = "sha256:5c5fbb229e40a89a2fe73d0c1181916f31e30f253cb2d6d91bea7927c2e18413"}, + {file = "pyzmq-25.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:ed15e3a2c3c2398e6ae5ce86d6a31b452dfd6ad4cd5d312596b30929c4b6e182"}, + {file = "pyzmq-25.0.2-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:032f5c8483c85bf9c9ca0593a11c7c749d734ce68d435e38c3f72e759b98b3c9"}, + {file = "pyzmq-25.0.2-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:374b55516393bfd4d7a7daa6c3b36d6dd6a31ff9d2adad0838cd6a203125e714"}, + {file = "pyzmq-25.0.2-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:08bfcc21b5997a9be4fefa405341320d8e7f19b4d684fb9c0580255c5bd6d695"}, + {file = "pyzmq-25.0.2-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:1a843d26a8da1b752c74bc019c7b20e6791ee813cd6877449e6a1415589d22ff"}, + {file = "pyzmq-25.0.2-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:b48616a09d7df9dbae2f45a0256eee7b794b903ddc6d8657a9948669b345f220"}, + {file = "pyzmq-25.0.2-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:d4427b4a136e3b7f85516c76dd2e0756c22eec4026afb76ca1397152b0ca8145"}, + {file = "pyzmq-25.0.2-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:26b0358e8933990502f4513c991c9935b6c06af01787a36d133b7c39b1df37fa"}, + {file = "pyzmq-25.0.2-cp36-cp36m-win32.whl", hash = "sha256:c8fedc3ccd62c6b77dfe6f43802057a803a411ee96f14e946f4a76ec4ed0e117"}, + {file = "pyzmq-25.0.2-cp36-cp36m-win_amd64.whl", hash = "sha256:2da6813b7995b6b1d1307329c73d3e3be2fd2d78e19acfc4eff2e27262732388"}, + {file = "pyzmq-25.0.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:a35960c8b2f63e4ef67fd6731851030df68e4b617a6715dd11b4b10312d19fef"}, + {file = "pyzmq-25.0.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:eef2a0b880ab40aca5a878933376cb6c1ec483fba72f7f34e015c0f675c90b20"}, + {file = "pyzmq-25.0.2-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:85762712b74c7bd18e340c3639d1bf2f23735a998d63f46bb6584d904b5e401d"}, + {file = "pyzmq-25.0.2-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:64812f29d6eee565e129ca14b0c785744bfff679a4727137484101b34602d1a7"}, + {file = "pyzmq-25.0.2-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:510d8e55b3a7cd13f8d3e9121edf0a8730b87d925d25298bace29a7e7bc82810"}, + {file = "pyzmq-25.0.2-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:b164cc3c8acb3d102e311f2eb6f3c305865ecb377e56adc015cb51f721f1dda6"}, + {file = "pyzmq-25.0.2-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:28fdb9224a258134784a9cf009b59265a9dde79582fb750d4e88a6bcbc6fa3dc"}, + {file = "pyzmq-25.0.2-cp37-cp37m-win32.whl", hash = "sha256:dd771a440effa1c36d3523bc6ba4e54ff5d2e54b4adcc1e060d8f3ca3721d228"}, + {file = "pyzmq-25.0.2-cp37-cp37m-win_amd64.whl", hash = "sha256:9bdc40efb679b9dcc39c06d25629e55581e4c4f7870a5e88db4f1c51ce25e20d"}, + {file = "pyzmq-25.0.2-cp38-cp38-macosx_10_15_universal2.whl", hash = "sha256:1f82906a2d8e4ee310f30487b165e7cc8ed09c009e4502da67178b03083c4ce0"}, + {file = "pyzmq-25.0.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:21ec0bf4831988af43c8d66ba3ccd81af2c5e793e1bf6790eb2d50e27b3c570a"}, + {file = "pyzmq-25.0.2-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:abbce982a17c88d2312ec2cf7673985d444f1beaac6e8189424e0a0e0448dbb3"}, + {file = "pyzmq-25.0.2-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:9e1d2f2d86fc75ed7f8845a992c5f6f1ab5db99747fb0d78b5e4046d041164d2"}, + {file = "pyzmq-25.0.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a2e92ff20ad5d13266bc999a29ed29a3b5b101c21fdf4b2cf420c09db9fb690e"}, + {file = "pyzmq-25.0.2-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:edbbf06cc2719889470a8d2bf5072bb00f423e12de0eb9ffec946c2c9748e149"}, + {file = "pyzmq-25.0.2-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:77942243ff4d14d90c11b2afd8ee6c039b45a0be4e53fb6fa7f5e4fd0b59da39"}, + {file = "pyzmq-25.0.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:ab046e9cb902d1f62c9cc0eca055b1d11108bdc271caf7c2171487298f229b56"}, + {file = "pyzmq-25.0.2-cp38-cp38-win32.whl", hash = "sha256:ad761cfbe477236802a7ab2c080d268c95e784fe30cafa7e055aacd1ca877eb0"}, + {file = "pyzmq-25.0.2-cp38-cp38-win_amd64.whl", hash = "sha256:8560756318ec7c4c49d2c341012167e704b5a46d9034905853c3d1ade4f55bee"}, + {file = "pyzmq-25.0.2-cp39-cp39-macosx_10_15_universal2.whl", hash = "sha256:ab2c056ac503f25a63f6c8c6771373e2a711b98b304614151dfb552d3d6c81f6"}, + {file = "pyzmq-25.0.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:cca8524b61c0eaaa3505382dc9b9a3bc8165f1d6c010fdd1452c224225a26689"}, + {file = "pyzmq-25.0.2-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:cfb9f7eae02d3ac42fbedad30006b7407c984a0eb4189a1322241a20944d61e5"}, + {file = "pyzmq-25.0.2-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:5eaeae038c68748082137d6896d5c4db7927e9349237ded08ee1bbd94f7361c9"}, + {file = "pyzmq-25.0.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4a31992a8f8d51663ebf79df0df6a04ffb905063083d682d4380ab8d2c67257c"}, + {file = "pyzmq-25.0.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:6a979e59d2184a0c8f2ede4b0810cbdd86b64d99d9cc8a023929e40dce7c86cc"}, + {file = "pyzmq-25.0.2-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:1f124cb73f1aa6654d31b183810febc8505fd0c597afa127c4f40076be4574e0"}, + {file = "pyzmq-25.0.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:65c19a63b4a83ae45d62178b70223adeee5f12f3032726b897431b6553aa25af"}, + {file = "pyzmq-25.0.2-cp39-cp39-win32.whl", hash = "sha256:83d822e8687621bed87404afc1c03d83fa2ce39733d54c2fd52d8829edb8a7ff"}, + {file = "pyzmq-25.0.2-cp39-cp39-win_amd64.whl", hash = "sha256:24683285cc6b7bf18ad37d75b9db0e0fefe58404e7001f1d82bf9e721806daa7"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:4a4b4261eb8f9ed71f63b9eb0198dd7c934aa3b3972dac586d0ef502ba9ab08b"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:62ec8d979f56c0053a92b2b6a10ff54b9ec8a4f187db2b6ec31ee3dd6d3ca6e2"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:affec1470351178e892121b3414c8ef7803269f207bf9bef85f9a6dd11cde264"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ffc71111433bd6ec8607a37b9211f4ef42e3d3b271c6d76c813669834764b248"}, + {file = "pyzmq-25.0.2-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:6fadc60970714d86eff27821f8fb01f8328dd36bebd496b0564a500fe4a9e354"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:269968f2a76c0513490aeb3ba0dc3c77b7c7a11daa894f9d1da88d4a0db09835"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:f7c8b8368e84381ae7c57f1f5283b029c888504aaf4949c32e6e6fb256ec9bf0"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:25e6873a70ad5aa31e4a7c41e5e8c709296edef4a92313e1cd5fc87bbd1874e2"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b733076ff46e7db5504c5e7284f04a9852c63214c74688bdb6135808531755a3"}, + {file = "pyzmq-25.0.2-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:a6f6ae12478fdc26a6d5fdb21f806b08fa5403cd02fd312e4cb5f72df078f96f"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:67da1c213fbd208906ab3470cfff1ee0048838365135a9bddc7b40b11e6d6c89"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:531e36d9fcd66f18de27434a25b51d137eb546931033f392e85674c7a7cea853"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:34a6fddd159ff38aa9497b2e342a559f142ab365576284bc8f77cb3ead1f79c5"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b491998ef886662c1f3d49ea2198055a9a536ddf7430b051b21054f2a5831800"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:5d496815074e3e3d183fe2c7fcea2109ad67b74084c254481f87b64e04e9a471"}, + {file = "pyzmq-25.0.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:56a94ab1d12af982b55ca96c6853db6ac85505e820d9458ac76364c1998972f4"}, + {file = "pyzmq-25.0.2.tar.gz", hash = "sha256:6b8c1bbb70e868dc88801aa532cae6bd4e3b5233784692b786f17ad2962e5149"}, +] + +[package.dependencies] +cffi = {version = "*", markers = "implementation_name == \"pypy\""} + [[package]] name = "repackage" version = "0.7.3" @@ -1706,21 +1991,21 @@ files = [ [[package]] name = "requests" -version = "2.29.0" +version = "2.31.0" description = "Python HTTP for Humans." category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "requests-2.29.0-py3-none-any.whl", hash = "sha256:e8f3c9be120d3333921d213eef078af392fba3933ab7ed2d1cba3b56f2568c3b"}, - {file = "requests-2.29.0.tar.gz", hash = "sha256:f2e34a75f4749019bb0e3effb66683630e4ffeaf75819fb51bebef1bf5aef059"}, + {file = "requests-2.31.0-py3-none-any.whl", hash = "sha256:58cd2187c01e70e6e26505bca751777aa9f2ee0b7f4300988b709f44e013003f"}, + {file = "requests-2.31.0.tar.gz", hash = "sha256:942c5a758f98d790eaed1a29cb6eefc7ffb0d1cf7af05c3d2791656dbd6ad1e1"}, ] [package.dependencies] certifi = ">=2017.4.17" charset-normalizer = ">=2,<4" idna = ">=2.5,<4" -urllib3 = ">=1.21.1,<1.27" +urllib3 = ">=1.21.1,<3" [package.extras] socks = ["PySocks (>=1.5.6,!=1.5.7)"] @@ -1748,19 +2033,19 @@ test = ["fixtures", "mock", "purl", "pytest", "requests-futures", "sphinx", "tes [[package]] name = "setuptools" -version = "67.7.2" +version = "67.8.0" description = "Easily download, build, install, upgrade, and uninstall Python packages" category = "main" optional = false python-versions = ">=3.7" files = [ - {file = "setuptools-67.7.2-py3-none-any.whl", hash = "sha256:23aaf86b85ca52ceb801d32703f12d77517b2556af839621c641fca11287952b"}, - {file = "setuptools-67.7.2.tar.gz", hash = "sha256:f104fa03692a2602fa0fec6c6a9e63b6c8a968de13e17c026957dd1f53d80990"}, + {file = "setuptools-67.8.0-py3-none-any.whl", hash = "sha256:5df61bf30bb10c6f756eb19e7c9f3b473051f48db77fddbe06ff2ca307df9a6f"}, + {file = "setuptools-67.8.0.tar.gz", hash = "sha256:62642358adc77ffa87233bc4d2354c4b2682d214048f500964dbe760ccedf102"}, ] [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-lint", "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 = ["build[virtualenv]", "filelock (>=3.4.0)", "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-mypy (>=0.9.1)", "pytest-perf", "pytest-ruff", "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]] @@ -1804,20 +2089,24 @@ widechars = ["wcwidth"] [[package]] name = "termcolor" -version = "1.1.0" -description = "ANSII Color formatting for output in terminal." +version = "2.3.0" +description = "ANSI color formatting for output in terminal" category = "dev" optional = false -python-versions = "*" +python-versions = ">=3.7" files = [ - {file = "termcolor-1.1.0.tar.gz", hash = "sha256:1d6d69ce66211143803fbc56652b41d73b4a400a2891d7bf7a1cdf4c02de613b"}, + {file = "termcolor-2.3.0-py3-none-any.whl", hash = "sha256:3afb05607b89aed0ffe25202399ee0867ad4d3cb4180d98aaf8eefa6a5f7d475"}, + {file = "termcolor-2.3.0.tar.gz", hash = "sha256:b5b08f68937f138fe92f6c089b99f1e2da0ae56c52b78bf7075fd95420fd9a5a"}, ] +[package.extras] +tests = ["pytest", "pytest-cov"] + [[package]] name = "toml" version = "0.10.2" description = "Python Library for Tom's Obvious, Minimal Language" -category = "main" +category = "dev" optional = false python-versions = ">=2.6, !=3.0.*, !=3.1.*, !=3.2.*" files = [ @@ -1839,87 +2128,54 @@ files = [ [[package]] name = "tornado" -version = "6.2" +version = "6.3.2" description = "Tornado is a Python web framework and asynchronous networking library, originally developed at FriendFeed." category = "dev" optional = false -python-versions = ">= 3.7" -files = [ - {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"}, -] - -[[package]] -name = "typed-ast" -version = "1.5.4" -description = "a fork of Python 2 and 3 ast modules with type comment support" -category = "dev" -optional = false -python-versions = ">=3.6" +python-versions = ">= 3.8" files = [ - {file = "typed_ast-1.5.4-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:669dd0c4167f6f2cd9f57041e03c3c2ebf9063d0757dc89f79ba1daa2bfca9d4"}, - {file = "typed_ast-1.5.4-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:211260621ab1cd7324e0798d6be953d00b74e0428382991adfddb352252f1d62"}, - {file = "typed_ast-1.5.4-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:267e3f78697a6c00c689c03db4876dd1efdfea2f251a5ad6555e82a26847b4ac"}, - {file = "typed_ast-1.5.4-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:c542eeda69212fa10a7ada75e668876fdec5f856cd3d06829e6aa64ad17c8dfe"}, - {file = "typed_ast-1.5.4-cp310-cp310-win_amd64.whl", hash = "sha256:a9916d2bb8865f973824fb47436fa45e1ebf2efd920f2b9f99342cb7fab93f72"}, - {file = "typed_ast-1.5.4-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:79b1e0869db7c830ba6a981d58711c88b6677506e648496b1f64ac7d15633aec"}, - {file = "typed_ast-1.5.4-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a94d55d142c9265f4ea46fab70977a1944ecae359ae867397757d836ea5a3f47"}, - {file = "typed_ast-1.5.4-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:183afdf0ec5b1b211724dfef3d2cad2d767cbefac291f24d69b00546c1837fb6"}, - {file = "typed_ast-1.5.4-cp36-cp36m-win_amd64.whl", hash = "sha256:639c5f0b21776605dd6c9dbe592d5228f021404dafd377e2b7ac046b0349b1a1"}, - {file = "typed_ast-1.5.4-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:cf4afcfac006ece570e32d6fa90ab74a17245b83dfd6655a6f68568098345ff6"}, - {file = "typed_ast-1.5.4-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ed855bbe3eb3715fca349c80174cfcfd699c2f9de574d40527b8429acae23a66"}, - {file = "typed_ast-1.5.4-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:6778e1b2f81dfc7bc58e4b259363b83d2e509a65198e85d5700dfae4c6c8ff1c"}, - {file = "typed_ast-1.5.4-cp37-cp37m-win_amd64.whl", hash = "sha256:0261195c2062caf107831e92a76764c81227dae162c4f75192c0d489faf751a2"}, - {file = "typed_ast-1.5.4-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:2efae9db7a8c05ad5547d522e7dbe62c83d838d3906a3716d1478b6c1d61388d"}, - {file = "typed_ast-1.5.4-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:7d5d014b7daa8b0bf2eaef684295acae12b036d79f54178b92a2b6a56f92278f"}, - {file = "typed_ast-1.5.4-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:370788a63915e82fd6f212865a596a0fefcbb7d408bbbb13dea723d971ed8bdc"}, - {file = "typed_ast-1.5.4-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:4e964b4ff86550a7a7d56345c7864b18f403f5bd7380edf44a3c1fb4ee7ac6c6"}, - {file = "typed_ast-1.5.4-cp38-cp38-win_amd64.whl", hash = "sha256:683407d92dc953c8a7347119596f0b0e6c55eb98ebebd9b23437501b28dcbb8e"}, - {file = "typed_ast-1.5.4-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:4879da6c9b73443f97e731b617184a596ac1235fe91f98d279a7af36c796da35"}, - {file = "typed_ast-1.5.4-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:3e123d878ba170397916557d31c8f589951e353cc95fb7f24f6bb69adc1a8a97"}, - {file = "typed_ast-1.5.4-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ebd9d7f80ccf7a82ac5f88c521115cc55d84e35bf8b446fcd7836eb6b98929a3"}, - {file = "typed_ast-1.5.4-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:98f80dee3c03455e92796b58b98ff6ca0b2a6f652120c263efdba4d6c5e58f72"}, - {file = "typed_ast-1.5.4-cp39-cp39-win_amd64.whl", hash = "sha256:0fdbcf2fef0ca421a3f5912555804296f0b0960f0418c440f5d6d3abb549f3e1"}, - {file = "typed_ast-1.5.4.tar.gz", hash = "sha256:39e21ceb7388e4bb37f4c679d72707ed46c2fbf2a5609b8b8ebc4b067d977df2"}, + {file = "tornado-6.3.2-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:c367ab6c0393d71171123ca5515c61ff62fe09024fa6bf299cd1339dc9456829"}, + {file = "tornado-6.3.2-cp38-abi3-macosx_10_9_x86_64.whl", hash = "sha256:b46a6ab20f5c7c1cb949c72c1994a4585d2eaa0be4853f50a03b5031e964fc7c"}, + {file = "tornado-6.3.2-cp38-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c2de14066c4a38b4ecbbcd55c5cc4b5340eb04f1c5e81da7451ef555859c833f"}, + {file = "tornado-6.3.2-cp38-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:05615096845cf50a895026f749195bf0b10b8909f9be672f50b0fe69cba368e4"}, + {file = "tornado-6.3.2-cp38-abi3-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5b17b1cf5f8354efa3d37c6e28fdfd9c1c1e5122f2cb56dac121ac61baa47cbe"}, + {file = "tornado-6.3.2-cp38-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:29e71c847a35f6e10ca3b5c2990a52ce38b233019d8e858b755ea6ce4dcdd19d"}, + {file = "tornado-6.3.2-cp38-abi3-musllinux_1_1_i686.whl", hash = "sha256:834ae7540ad3a83199a8da8f9f2d383e3c3d5130a328889e4cc991acc81e87a0"}, + {file = "tornado-6.3.2-cp38-abi3-musllinux_1_1_x86_64.whl", hash = "sha256:6a0848f1aea0d196a7c4f6772197cbe2abc4266f836b0aac76947872cd29b411"}, + {file = "tornado-6.3.2-cp38-abi3-win32.whl", hash = "sha256:7efcbcc30b7c654eb6a8c9c9da787a851c18f8ccd4a5a3a95b05c7accfa068d2"}, + {file = "tornado-6.3.2-cp38-abi3-win_amd64.whl", hash = "sha256:0c325e66c8123c606eea33084976c832aa4e766b7dff8aedd7587ea44a604cdf"}, + {file = "tornado-6.3.2.tar.gz", hash = "sha256:4b927c4f19b71e627b13f3db2324e4ae660527143f9e1f2e2fb404f3a187e2ba"}, ] [[package]] name = "typing-extensions" -version = "4.5.0" +version = "4.6.2" description = "Backported and Experimental Type Hints for Python 3.7+" -category = "main" +category = "dev" optional = false python-versions = ">=3.7" files = [ - {file = "typing_extensions-4.5.0-py3-none-any.whl", hash = "sha256:fb33085c39dd998ac16d1431ebc293a8b3eedd00fd4a32de0ff79002c19511b4"}, - {file = "typing_extensions-4.5.0.tar.gz", hash = "sha256:5cb5f4a79139d699607b3ef622a1dedafa84e115ab0024e0d9c044a9479ca7cb"}, + {file = "typing_extensions-4.6.2-py3-none-any.whl", hash = "sha256:3a8b36f13dd5fdc5d1b16fe317f5668545de77fa0b8e02006381fd49d731ab98"}, + {file = "typing_extensions-4.6.2.tar.gz", hash = "sha256:06006244c70ac8ee83fa8282cb188f697b8db25bc8b4df07be1873c43897060c"}, ] [[package]] name = "urllib3" -version = "1.26.15" +version = "2.0.2" description = "HTTP library with thread-safe connection pooling, file post, and more." category = "main" optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*, !=3.5.*" +python-versions = ">=3.7" files = [ - {file = "urllib3-1.26.15-py2.py3-none-any.whl", hash = "sha256:aa751d169e23c7479ce47a0cb0da579e3ede798f994f5816a74e4f4500dcea42"}, - {file = "urllib3-1.26.15.tar.gz", hash = "sha256:8a388717b9476f934a21484e8c8e61875ab60644d29b9b39e11e4b9dc1c6b305"}, + {file = "urllib3-2.0.2-py3-none-any.whl", hash = "sha256:d055c2f9d38dc53c808f6fdc8eab7360b6fdbbde02340ed25cfbcd817c62469e"}, + {file = "urllib3-2.0.2.tar.gz", hash = "sha256:61717a1095d7e155cdb737ac7bb2f4324a858a1e2e6466f6d03ff630ca68d3cc"}, ] [package.extras] -brotli = ["brotli (>=1.0.9)", "brotlicffi (>=0.8.0)", "brotlipy (>=0.6.0)"] -secure = ["certifi", "cryptography (>=1.3.4)", "idna (>=2.0.0)", "ipaddress", "pyOpenSSL (>=0.14)", "urllib3-secure-extra"] -socks = ["PySocks (>=1.5.6,!=1.5.7,<2.0)"] +brotli = ["brotli (>=1.0.9)", "brotlicffi (>=0.8.0)"] +secure = ["certifi", "cryptography (>=1.9)", "idna (>=2.0.0)", "pyopenssl (>=17.1.0)", "urllib3-secure-extra"] +socks = ["pysocks (>=1.5.6,!=1.5.7,<2.0)"] +zstd = ["zstandard (>=0.18.0)"] [[package]] name = "virtualenv" @@ -1936,7 +2192,6 @@ files = [ [package.dependencies] distlib = ">=0.3.6,<1" filelock = ">=3.11,<4" -importlib-metadata = {version = ">=6.4.1", markers = "python_version < \"3.8\""} platformdirs = ">=3.2,<4" [package.extras] @@ -2013,18 +2268,18 @@ requests = "*" [[package]] name = "yaspin" -version = "2.1.0" +version = "2.3.0" description = "Yet Another Terminal Spinner" category = "dev" optional = false -python-versions = ">=3.6.2,<4.0.0" +python-versions = ">=3.7.2,<4.0.0" files = [ - {file = "yaspin-2.1.0-py3-none-any.whl", hash = "sha256:d574cbfaf0a349df466c91f7f81b22460ae5ebb15ecb8bf9411d6049923aee8d"}, - {file = "yaspin-2.1.0.tar.gz", hash = "sha256:c8d34eca9fda3f4dfbe59f57f3cf0f3641af3eefbf1544fbeb9b3bacf82c580a"}, + {file = "yaspin-2.3.0-py3-none-any.whl", hash = "sha256:17b5548479b3d5b30adec7a87ffcdcddb403d14a2bb86fbcee97f37951e13427"}, + {file = "yaspin-2.3.0.tar.gz", hash = "sha256:547afd1a9700ac3a29a9f5591c70343bef186ed5dfb5e545a9bb0c77e561a1c9"}, ] [package.dependencies] -termcolor = ">=1.1.0,<2.0.0" +termcolor = ">=2.2,<3.0" [[package]] name = "zipp" @@ -2047,5 +2302,5 @@ examples = ["asciimatics", "inputs", "matplotlib", "pandas", "webdavclient3"] [metadata] lock-version = "2.0" -python-versions = ">=3.7.1, <3.11" -content-hash = "ffee950480bb9363ead081aa22e75c2e33317b8d86e82417f6796a40ce3d3f2a" +python-versions = "^3.8" +content-hash = "373d8e5044fa76468877e8df618605d1094e7e521aa1e12e832fa0af330dffbe" diff --git a/pyproject.toml b/pyproject.toml index 9fe790a2..17732fdc 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,6 +1,6 @@ [tool.poetry] name = "blueye.sdk" -version = "1.0.3" +version = "2.0.0" description = "SDK for controlling a Blueye underwater drone" authors = ["Sindre Hansen ", "Johannes Schrimpf ", @@ -16,7 +16,7 @@ homepage ="https://www.blueyerobotics.com" keywords = ["Blueye", "Pioneer", "Pro", "Robotics", "SDK", "Software Development Kit"] [tool.poetry.dependencies] -python = ">=3.7.1, <3.11" +python = "^3.8" asciimatics = {version = "^1.11.0", optional = true} inputs = {version = "^0.5", optional = true} pandas = {version = "^1.3", optional = true} @@ -25,9 +25,10 @@ webdavclient3 = {version = "^3.14.6", optional = true} requests = "^2.22.0" tabulate = "^0.8.5" packaging = "^22.0" -"blueye.protocol" = "^1.3.4" -numpy = "~1.21.5" +"blueye.protocol" = "^2.2.0" python-dateutil = "^2.8.2" +pyzmq = "^25.0.0" +proto-plus = "^1.22.2" [tool.poetry.dev-dependencies] pytest = "^6.2.5" @@ -99,12 +100,21 @@ custom_dir = "docs/mkdocs_templates" [[tool.portray.mkdocs.nav]] "Configure drone parameters" = "docs/configuration.md" +[[tool.portray.mkdocs.nav]] +"Subscribing to a telemetry message" = "docs/telemetry-callback.md" + +[[tool.portray.mkdocs.nav]] +"Updating from v1 to v2" = "docs/migrating-to-v2.md" + +[[tool.portray.mkdocs.nav]] +"Protobuf protocol" = "docs/protobuf-protocol.md" + [[tool.portray.mkdocs.nav]] "HTTP API" = "docs/http-api.html" [tool.black] line-length = 100 -target-version = ['py37', 'py38', 'py39', 'py310'] +target-version = ['py38', 'py39', 'py310', 'py311'] [tool.pytest.ini_options] markers = "connected_to_drone: a mark for test that can only be run when connected to a drone, useful when developing" diff --git a/tests/conftest.py b/tests/conftest.py index 6e4a558d..6e869627 100644 --- a/tests/conftest.py +++ b/tests/conftest.py @@ -1,8 +1,7 @@ -from unittest.mock import Mock +import blueye.protocol as bp +import pytest import blueye.sdk -import pytest -from blueye.sdk import Drone @pytest.fixture(scope="class") @@ -11,7 +10,7 @@ def real_drone(): Used for integration tests with physical hardware. """ - return Drone() + return blueye.sdk.Drone() @pytest.fixture @@ -23,12 +22,12 @@ def mocked_requests(requests_mock): "features": "lasers,harpoon", "hardware_id": "ea9ac92e1817a1d4", "manufacturer": "Blueye Robotics", - "model_description": "Blueye Pioneer Underwater Drone", - "model_name": "Blueye Pioneer", + "model_description": "Blueye X3 Underwater Drone", + "model_name": "Blueye X3", "model_url": "https://www.blueyerobotics.com", "operating_system": "blunux", - "serial_number": "BYEDP123456", - "sw_version": "1.4.7-warrior-master", + "serial_number": "BYEDP230000", + "sw_version": "3.2.62-honister-master", } requests_mock.get( "http://192.168.1.101/diagnostics/drone_info", @@ -55,41 +54,61 @@ def mocked_requests(requests_mock): @pytest.fixture -def mocked_TcpClient(mocker): - """Fixture for mocking the TcpClient from blueye.protocol +def mocked_ctrl_client(mocker): + return mocker.patch("blueye.sdk.drone.CtrlClient", autospec=True) - Note: This mock is passed create=True, which has the potential to be dangerous since it would - allow you to test against methods that don't exist on the actual class. Due to the way methods - are added to TcpClient (they are instantiated on runtime, depending on which version of the - protocol is requested) mocking the class in the usual way would be quite cumbersome. - """ - return mocker.patch("blueye.sdk.drone.TcpClient", create=True) + +@pytest.fixture +def mocked_telemetry_client(mocker): + return mocker.patch("blueye.sdk.drone.TelemetryClient", autospec=True) @pytest.fixture -def mocked_UdpClient(mocker): - return mocker.patch("blueye.sdk.drone.UdpClient", autospec=True) +def mocked_watchdog_publisher(mocker): + return mocker.patch("blueye.sdk.drone.WatchdogPublisher", autospec=True) @pytest.fixture -def mocked_drone(request, mocker, mocked_TcpClient, mocked_UdpClient, mocked_requests): - drone = blueye.sdk.Drone(autoConnect=False) - drone._wait_for_udp_communication = Mock() - # Mocking out the run function to avoid blowing up the stack when the thread continuously calls - # the get_data_dict function (which won't block since it's mocked). - drone._state_watcher.run = Mock() - drone.connect() - if hasattr(request, "param"): - drone.software_version_short = request.param - return drone +def mocked_req_rep_client(mocker): + return mocker.patch("blueye.sdk.drone.ReqRepClient", autospec=True) @pytest.fixture -def mocked_slave_drone(mocker, mocked_TcpClient, mocked_UdpClient, mocked_requests): - drone = blueye.sdk.Drone(autoConnect=False, slaveModeEnabled=True) - drone._wait_for_udp_communication = Mock() - # Mocking out the run function to avoid blowing up the stack when the thread continuously calls - # the get_data_dict function (which won't block since it's mocked). - drone._state_watcher.run = Mock() - drone.connect() +def mocked_drone( + request, + mocker, + mocked_requests, + mocked_ctrl_client, + mocked_watchdog_publisher, + mocked_req_rep_client, +): + drone = blueye.sdk.Drone() + drone._req_rep_client.get_overlay_parameters.return_value = bp.OverlayParameters( + temperature_enabled=False, + depth_enabled=False, + heading_enabled=False, + tilt_enabled=False, + date_enabled=False, + distance_enabled=False, + altitude_enabled=False, + cp_probe_enabled=False, + drone_location_enabled=False, + logo_type=bp.LogoType.LOGO_TYPE_NONE, + depth_unit=bp.DepthUnit.DEPTH_UNIT_METERS, + temperature_unit=bp.TemperatureUnit.TEMPERATURE_UNIT_CELSIUS, + thickness_unit=bp.ThicknessUnit.THICKNESS_UNIT_MILLIMETERS, + timezone_offset=60, + margin_width=30, + margin_height=15, + font_size=bp.FontSize.FONT_SIZE_PX25, + title="", + subtitle="", + date_format="%m/%d/%Y %I:%M:%S %p", + shading=0, + ) + drone._req_rep_client.connect_client.return_value = bp.ConnectClientRep( + client_id=1, client_id_in_control=1 + ) + if hasattr(request, "param"): + drone.software_version_short = request.param return drone diff --git a/tests/test_overlay_control.py b/tests/test_overlay_control.py index ab59b371..6ff36bc7 100644 --- a/tests/test_overlay_control.py +++ b/tests/test_overlay_control.py @@ -1,342 +1,185 @@ +import blueye.protocol as bp import pytest -from blueye.sdk import DepthUnitOverlay, Drone, FontSizeOverlay, LogoOverlay, TemperatureUnitOverlay - - -class OverlayTestBase: - default_overlay_parameters = ( - 97, # Parameter - 0, # Temperature enabled - 0, # Depth enabled - 0, # Heading enabled - 0, # Tilt enabled - 0, # Date enabled - 0, # Logo index - 0, # Depth unit (index) - 0, # Temperature unit (index) - 60, # Timezone offset - 30, # Margin width - 15, # Margin height - 25, # Font size - # Title - b"\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - # Subtitle - b"\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - # Data format - b"%m/%d/%Y %I:%M:%S %p\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ) - - -@pytest.mark.parametrize("mocked_drone", ["1.7.60"], indirect=True) -class TestOverlay(OverlayTestBase): + +from blueye.sdk import Drone + + +class TestOverlay: def test_enable_temperature(self, mocked_drone: Drone): mocked_drone.camera.overlay.temperature_enabled = True - mocked_drone._tcp_client.set_overlay_temperature_enabled.assert_called_with(1) - mocked_drone.camera.overlay.temperature_enabled = False - mocked_drone._tcp_client.set_overlay_temperature_enabled.assert_called_with(0) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_temperature_state(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.temperature_enabled is False - params[1] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.temperature_enabled is True - def test_enable_depth(self, mocked_drone: Drone): mocked_drone.camera.overlay.depth_enabled = True - mocked_drone._tcp_client.set_overlay_depth_enabled.assert_called_with(1) - mocked_drone.camera.overlay.depth_enabled = False - mocked_drone._tcp_client.set_overlay_depth_enabled.assert_called_with(0) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_depth_state(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.depth_enabled is False - params[2] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.depth_enabled is True - def test_enable_heading(self, mocked_drone: Drone): mocked_drone.camera.overlay.heading_enabled = True - mocked_drone._tcp_client.set_overlay_heading_enabled.assert_called_with(1) - mocked_drone.camera.overlay.heading_enabled = False - mocked_drone._tcp_client.set_overlay_heading_enabled.assert_called_with(0) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_heading_state(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.heading_enabled is False - params[3] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.heading_enabled is True - def test_enable_tilt(self, mocked_drone: Drone): mocked_drone.camera.overlay.tilt_enabled = True - mocked_drone._tcp_client.set_overlay_tilt_enabled.assert_called_with(1) - mocked_drone.camera.overlay.tilt_enabled = False - mocked_drone._tcp_client.set_overlay_tilt_enabled.assert_called_with(0) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_tilt_state(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.tilt_enabled is False - params[4] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.tilt_enabled is True - def test_enable_date(self, mocked_drone: Drone): mocked_drone.camera.overlay.date_enabled = True - mocked_drone._tcp_client.set_overlay_date_enabled.assert_called_with(1) - mocked_drone.camera.overlay.date_enabled = False - mocked_drone._tcp_client.set_overlay_date_enabled.assert_called_with(0) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_date_state(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.date_enabled is False - params[5] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.date_enabled is True - def test_select_depth_unit(self, mocked_drone: Drone): - mocked_drone.camera.overlay.depth_unit = DepthUnitOverlay.METERS - mocked_drone._tcp_client.set_overlay_depth_unit.assert_called_with(0) + mocked_drone.camera.overlay.depth_unit = bp.DepthUnit.DEPTH_UNIT_METERS + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() - mocked_drone.camera.overlay.depth_unit = DepthUnitOverlay.FEET - mocked_drone._tcp_client.set_overlay_depth_unit.assert_called_with(1) - - def test_select_depth_unit_warns_and_ignores_for_out_of_range_value(self, mocked_drone: Drone): + def test_select_depth_unit_warns_and_ignores_for_wrong_type(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): - mocked_drone.camera.overlay.depth_unit = 2 - assert mocked_drone._tcp_client.set_overlay_depth_unit.called is False + mocked_drone.camera.overlay.depth_unit = "wrong type" + assert mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_get_depth_unit(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.depth_unit == DepthUnitOverlay["METERS"] - - params[7] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.depth_unit == DepthUnitOverlay["FEET"] + assert mocked_drone.camera.overlay.depth_unit == bp.DepthUnit.DEPTH_UNIT_METERS def test_select_temp_unit(self, mocked_drone: Drone): - mocked_drone.camera.overlay.temperature_unit = TemperatureUnitOverlay.CELSIUS - mocked_drone._tcp_client.set_overlay_temperature_unit.assert_called_with(0) + mocked_drone.camera.overlay.temperature_unit = bp.TemperatureUnit.TEMPERATURE_UNIT_CELSIUS + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() - mocked_drone.camera.overlay.temperature_unit = TemperatureUnitOverlay.FAHRENHEIT - mocked_drone._tcp_client.set_overlay_temperature_unit.assert_called_with(1) - - def test_select_temp_unit_warns_and_ignores_for_out_of_range_value(self, mocked_drone: Drone): + def test_select_temp_unit_warns_and_ignores_for_wrong_type(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): - mocked_drone.camera.overlay.temperature_unit = 2 - assert mocked_drone._tcp_client.set_overlay_temperature_unit.called is False + mocked_drone.camera.overlay.temperature_unit = "wrong type" + assert mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_get_temp_unit(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.temperature_unit == TemperatureUnitOverlay["CELSIUS"] - - params[8] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.temperature_unit == TemperatureUnitOverlay["FAHRENHEIT"] + assert ( + mocked_drone.camera.overlay.temperature_unit + == bp.TemperatureUnit.TEMPERATURE_UNIT_CELSIUS + ) def test_set_timezone_offset(self, mocked_drone: Drone): mocked_drone.camera.overlay.timezone_offset = 120 - mocked_drone._tcp_client.set_overlay_tz_offset.assert_called_with(120) - mocked_drone.camera.overlay.timezone_offset = -60 - mocked_drone._tcp_client.set_overlay_tz_offset.assert_called_with(-60) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_timezone_offset(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.timezone_offset == 60 - params[9] = -60 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.timezone_offset == -60 - def test_set_margin_width(self, mocked_drone: Drone): mocked_drone.camera.overlay.margin_width = 10 - mocked_drone._tcp_client.set_overlay_margin_width.assert_called_with(10) - mocked_drone.camera.overlay.margin_width = 20 - mocked_drone._tcp_client.set_overlay_margin_width.assert_called_with(20) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_margin_width(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.margin_width == 30 - params[10] = 60 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.margin_width == 60 - def test_sub_zero_margin_width_is_warned_and_ignored(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.margin_width = -10 - mocked_drone._tcp_client.set_overlay_margin_width.called is False + mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_set_margin_height(self, mocked_drone: Drone): mocked_drone.camera.overlay.margin_height = 10 - mocked_drone._tcp_client.set_overlay_margin_height.assert_called_with(10) - mocked_drone.camera.overlay.margin_height = 20 - mocked_drone._tcp_client.set_overlay_margin_height.assert_called_with(20) + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_get_margin_height(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.margin_height == 15 - params[11] = 60 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.margin_height == 60 - def test_sub_zero_margin_height_is_warned_and_ignored(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.margin_height = -10 - mocked_drone._tcp_client.set_overlay_margin_height.called is False + mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_select_font_size(self, mocked_drone: Drone): - mocked_drone.camera.overlay.font_size = FontSizeOverlay.PX15 - mocked_drone._tcp_client.set_overlay_font_size.assert_called_with(15) + mocked_drone.camera.overlay.font_size = bp.FontSize.FONT_SIZE_PX15 + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() - mocked_drone.camera.overlay.font_size = FontSizeOverlay.PX20 - mocked_drone._tcp_client.set_overlay_font_size.assert_called_with(20) - - mocked_drone.camera.overlay.font_size = FontSizeOverlay.PX25 - mocked_drone._tcp_client.set_overlay_font_size.assert_called_with(25) - - mocked_drone.camera.overlay.font_size = FontSizeOverlay.PX30 - mocked_drone._tcp_client.set_overlay_font_size.assert_called_with(30) - - mocked_drone.camera.overlay.font_size = FontSizeOverlay.PX35 - mocked_drone._tcp_client.set_overlay_font_size.assert_called_with(35) - - mocked_drone.camera.overlay.font_size = FontSizeOverlay.PX40 - mocked_drone._tcp_client.set_overlay_font_size.assert_called_with(40) - - def test_select_font_size_warns_and_ignores_for_out_of_range_value(self, mocked_drone: Drone): + def test_select_font_size_warns_and_ignores_for_wrong_type(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): - mocked_drone.camera.overlay.font_size = 100 - assert mocked_drone._tcp_client.set_overlay_font_size.called is False + mocked_drone.camera.overlay.font_size = "wrong type" + assert mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_get_font_size(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.font_size == FontSizeOverlay(25) - - params[12] = 40 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.font_size == FontSizeOverlay(40) + assert mocked_drone.camera.overlay.font_size == bp.FontSize.FONT_SIZE_PX25 def test_set_title(self, mocked_drone: Drone): mocked_drone.camera.overlay.title = "a" * 63 - mocked_drone._tcp_client.set_overlay_title.assert_called_with(b"a" * 63 + b"\x00") + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_set_title_warns_and_ignores_non_ascii(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.title = "æøå" - assert mocked_drone._tcp_client.set_overlay_title.called is False + assert mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_set_title_warns_and_truncates_too_long_title(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.title = "a" * 64 - mocked_drone._tcp_client.set_overlay_title.assert_called_with(b"a" * 63 + b"\x00") + expected_params = mocked_drone._req_rep_client.get_overlay_parameters.return_value + expected_params.title = "a" * 63 + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_with(expected_params) def test_get_title(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.title == "" - params[13] = b"abc" * 21 + b"\x00" - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.title == "abc" * 21 - def test_set_subtitle(self, mocked_drone: Drone): mocked_drone.camera.overlay.subtitle = "a" * 63 - mocked_drone._tcp_client.set_overlay_subtitle.assert_called_with(b"a" * 63 + b"\x00") + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_set_subtitle_warns_and_ignores_non_ascii(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.subtitle = "æøå" - assert mocked_drone._tcp_client.set_overlay_subtitle.called is False + assert mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_set_subtitle_warns_and_truncates_too_long_subtitle(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.subtitle = "a" * 64 - mocked_drone._tcp_client.set_overlay_subtitle.assert_called_with(b"a" * 63 + b"\x00") + expected_params = mocked_drone._req_rep_client.get_overlay_parameters.return_value + expected_params.subtitle = "a" * 63 + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_with(expected_params) def test_get_subtitle(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.subtitle == "" - params[14] = b"abc" * 21 + b"\x00" - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.subtitle == "abc" * 21 - def test_set_date_format(self, mocked_drone: Drone): mocked_drone.camera.overlay.date_format = "a" * 63 - mocked_drone._tcp_client.set_overlay_date_format.assert_called_with(b"a" * 63 + b"\x00") + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_set_date_format_warns_and_ignores_non_ascii(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.date_format = "æøå" - assert mocked_drone._tcp_client.set_overlay_date_format.called is False + assert mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_set_date_format_warns_and_truncates_too_long_date_format(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): mocked_drone.camera.overlay.date_format = "a" * 64 - mocked_drone._tcp_client.set_overlay_date_format.assert_called_with(b"a" * 63 + b"\x00") + expected_params = mocked_drone._req_rep_client.get_overlay_parameters.return_value + expected_params.date_format = "a" * 63 + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_with(expected_params) def test_get_date_format(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params assert mocked_drone.camera.overlay.date_format == "%m/%d/%Y %I:%M:%S %p" - params[15] = b"abc" * 21 + b"\x00" - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.date_format == "abc" * 21 - -@pytest.mark.parametrize("mocked_drone", ["1.8.72"], indirect=True) -class TestOverlayLogoControl(OverlayTestBase): +class TestOverlayLogoControl: def test_select_logo(self, mocked_drone: Drone): - mocked_drone.camera.overlay.logo = LogoOverlay.DISABLED - mocked_drone._tcp_client.set_overlay_logo_index.assert_called_with(0) - - mocked_drone.camera.overlay.logo = LogoOverlay.BLUEYE - mocked_drone._tcp_client.set_overlay_logo_index.assert_called_with(1) - - mocked_drone.camera.overlay.logo = LogoOverlay.CUSTOM - mocked_drone._tcp_client.set_overlay_logo_index.assert_called_with(2) + mocked_drone.camera.overlay.logo = bp.LogoType.LOGO_TYPE_NONE + mocked_drone._req_rep_client.set_overlay_parameters.assert_called_once() def test_select_logo_warns_and_ignores_on_invalid_type(self, mocked_drone: Drone): with pytest.warns(RuntimeWarning): - mocked_drone.camera.overlay.logo = 1 - assert mocked_drone._tcp_client.set_overlay_logo_index.call_count == 0 - - def test_select_logo_warns_and_ignores_for_out_of_range_value(self, mocked_drone: Drone): - with pytest.warns(RuntimeWarning): - mocked_drone.camera.overlay.logo = 3 - assert mocked_drone._tcp_client.set_overlay_logo_index.called is False + mocked_drone.camera.overlay.logo = "wrong type" + assert mocked_drone._req_rep_client.set_overlay_parameters.called is False def test_get_logo_state(self, mocked_drone: Drone): - params = list(self.default_overlay_parameters) - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.logo == LogoOverlay["DISABLED"] - - params[6] = 1 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.logo == LogoOverlay["BLUEYE"] - - params[6] = 2 - mocked_drone._tcp_client.get_overlay_parameters.return_value = params - assert mocked_drone.camera.overlay.logo == LogoOverlay["CUSTOM"] + assert mocked_drone.camera.overlay.logo == bp.LogoType.LOGO_TYPE_NONE def test_upload_logo(self, mocked_drone: Drone, requests_mock, mocker): mocked_drone.software_version_short = "1.8.72" diff --git a/tests/test_sdk.py b/tests/test_sdk.py index 5fbb7f34..f26052d1 100644 --- a/tests/test_sdk.py +++ b/tests/test_sdk.py @@ -1,46 +1,39 @@ +import json from time import time from unittest.mock import Mock, PropertyMock +import blueye.protocol as bp import pytest import requests from freezegun import freeze_time import blueye.sdk from blueye.sdk import Drone +from blueye.sdk.camera import Camera class TestLights: def test_lights_returns_value(self, mocked_drone): - mocked_drone._state_watcher._general_state = {"lights_upper": 0} - mocked_drone._state_watcher._general_state_received.set() + lights_tel = bp.LightsTel(lights={"value": 0}) + lights_tel_serialized = lights_tel.__class__.serialize(lights_tel) + mocked_drone._telemetry_watcher._state[bp.LightsTel] = lights_tel_serialized assert mocked_drone.lights == 0 class TestPose: @pytest.mark.parametrize("old_angle, new_angle", [(0, 0), (180, 180), (-180, 180), (-1, 359)]) def test_angle_conversion(self, mocked_drone, old_angle, new_angle): - mocked_drone._state_watcher._general_state = { - "roll": old_angle, - "pitch": old_angle, - "yaw": old_angle, - } - mocked_drone._state_watcher._general_state_received.set() + attitude_tel = bp.AttitudeTel( + attitude={"roll": old_angle, "pitch": old_angle, "yaw": old_angle} + ) + attitude_tel_serialized = attitude_tel.__class__.serialize(attitude_tel) + mocked_drone._telemetry_watcher._state[bp.AttitudeTel] = attitude_tel_serialized pose = mocked_drone.pose assert pose["roll"] == new_angle assert pose["pitch"] == new_angle assert pose["yaw"] == new_angle -class TestSlaveMode: - def test_warning_is_raised(self, mocker, mocked_slave_drone): - mocked_warn = mocker.patch("warnings.warn", autospec=True) - - # Call function that requires tcp connection - mocked_slave_drone.lights = 0 - - mocked_warn.assert_called_once() - - def test_documentation_opener(mocker): mocked_webbrowser_open = mocker.patch("webbrowser.open", autospec=True) import os @@ -58,8 +51,6 @@ def test_feature_list(mocked_drone): def test_feature_list_is_empty_on_old_versions(mocked_drone, requests_mock): - import json - dummy_drone_info = { "commit_id_csys": "299238949a", "hardware_id": "ea9ac92e1817a1d4", @@ -81,66 +72,57 @@ def test_feature_list_is_empty_on_old_versions(mocked_drone, requests_mock): def test_software_version(mocked_drone): mocked_drone._update_drone_info() - assert mocked_drone.software_version == "1.4.7-warrior-master" - assert mocked_drone.software_version_short == "1.4.7" + assert mocked_drone.software_version == "3.2.62-honister-master" + assert mocked_drone.software_version_short == "3.2.62" -def test_verify_sw_version_raises_connection_error_when_not_connected(mocked_drone: Drone, mocker): - mocker.patch( - "blueye.sdk.Drone.connection_established", new_callable=PropertyMock, return_value=False +def test_connect_fails_on_old_versions(mocked_drone, requests_mock): + mocked_drone.software_version_short = "1.3.2" + dummy_drone_info = { + "commit_id_csys": "299238949a", + "hardware_id": "ea9ac92e1817a1d4", + "manufacturer": "Blueye Robotics", + "model_description": "Blueye Pioneer Underwater Drone", + "model_name": "Blueye Pioneer", + "model_url": "https://www.blueyerobotics.com", + "operating_system": "blunux", + "serial_number": "BYEDP123456", + "sw_version": "1.3.2-rocko-master", + } + requests_mock.get( + "http://192.168.1.101/diagnostics/drone_info", + content=json.dumps(dummy_drone_info).encode(), ) - with pytest.raises(ConnectionError): - mocked_drone._verify_required_blunux_version("1.4.7") - - -def test_if_blunux_newer_than_3_create_tcp_first(mocked_drone: Drone): - mocked_drone.software_version_short = "3.0" - mocked_drone._create_temporary_tcp_client = Mock() - mocked_drone._update_drone_info = Mock() # To avoid overwriting the version number - mocked_drone.connect() - - mocked_drone._create_temporary_tcp_client.assert_called_once() + with pytest.raises(RuntimeError): + mocked_drone.connect() def test_depth_reading(mocked_drone): - depth = 10000 - mocked_drone._state_watcher._general_state = {"depth": depth} - mocked_drone._state_watcher._general_state_received.set() + depth = 10 + depthTel = bp.DepthTel(depth={"value": depth}) + depthTel_serialized = depthTel.__class__.serialize(depthTel) + mocked_drone._telemetry_watcher._state[bp.DepthTel] = depthTel_serialized assert mocked_drone.depth == depth def test_error_flags(mocked_drone): - error_flags = 64 - mocked_drone._state_watcher._general_state = {"error_flags": error_flags} - mocked_drone._state_watcher._general_state_received.set() - assert mocked_drone.error_flags == error_flags - - -def test_timeout_general_state(mocked_drone: Drone): - mocked_drone._state_watcher._udp_timeout = 0.001 - with pytest.raises(TimeoutError): - mocked_drone._state_watcher.general_state - - -def test_timeout_calibration_state(mocked_drone: Drone): - mocked_drone._state_watcher._udp_timeout = 0.001 - with pytest.raises(TimeoutError): - mocked_drone._state_watcher.calibration_state + error_flags_tel = bp.ErrorFlagsTel(error_flags={"depth_read": True}) + error_flags_serialized = error_flags_tel.__class__.serialize(error_flags_tel) + mocked_drone._telemetry_watcher._state[bp.ErrorFlagsTel] = error_flags_serialized + assert mocked_drone.error_flags["depth_read"] == True def test_battery_state_of_charge_reading(mocked_drone): - SoC = 77 - mocked_drone._state_watcher._general_state = {"battery_state_of_charge_rel": SoC} - mocked_drone._state_watcher._general_state_received.set() - assert mocked_drone.battery_state_of_charge == SoC + SoC = 0.77 + batteryTel = bp.BatteryTel(battery={"level": SoC}) + batteryTel_msg = batteryTel.__class__.serialize(batteryTel) + mocked_drone._telemetry_watcher._state[bp.BatteryTel] = batteryTel_msg + assert mocked_drone.battery.state_of_charge == pytest.approx(SoC) -@pytest.mark.parametrize("version", ["1.4.7", "1.4.8", "1.5.0", "2.0.0"]) -def test_still_picture_works_with_new_drone_version(mocked_drone, version): - mocked_drone.software_version_short = version +def test_still_picture_works(mocked_drone): mocked_drone.camera.take_picture() - mocked_drone._tcp_client.take_still_picture.assert_called_once() - mocked_drone._tcp_client.reset_mock() + mocked_drone._ctrl_client.take_still_picture.assert_called_once() @pytest.mark.parametrize( @@ -159,162 +141,95 @@ def test_update_drone_info_raises_ConnectionError_when_not_connected( mocked_drone._update_drone_info() -def test_wait_for_udp_com_raises_ConnectionError_on_timeout(mocker): - import socket - - mocked_udp = mocker.patch("blueye.sdk.drone.UdpClient", autospec=True).return_value - - mocked_udp.attach_mock(mocker.patch("blueye.sdk.drone.socket.socket", autospec=True), "_sock") - mocked_udp.get_data_dict.side_effect = socket.timeout - with pytest.raises(ConnectionError): - blueye.sdk.Drone._wait_for_udp_communication(0.001) - - -def test_connect_ignores_repeated_starts_on_watchdog_thread(mocked_drone): - mocked_drone.disconnect() - assert mocked_drone.connection_established is False - mocked_drone._tcp_client.start.side_effect = RuntimeError - mocked_drone.connect(1) - assert mocked_drone.connection_established is True - - -def test_active_video_streams_fails_on_old_versions(mocked_drone): - with pytest.raises(RuntimeError): - _ = mocked_drone.active_video_streams +def test_active_video_streams_return_correct_number(mocked_drone: Drone): + NStreamersTel = bp.NStreamersTel(n_streamers={"main": 1, "guestport": 2}) + NStreamersTel_serialized = NStreamersTel.__class__.serialize(NStreamersTel) + mocked_drone._telemetry_watcher._state[bp.NStreamersTel] = NStreamersTel_serialized - -@pytest.mark.parametrize("mocked_drone", ["1.5.33"], indirect=True) -@pytest.mark.parametrize( - "debug_flag, expected_connections", - [ - (0x0000000000000000, 0), - (0x0000000100000000, 1), - (0x000000AB00000000, 171), - (0x12345645789ABCDE, 69), - ], -) -def test_active_video_streams_return_correct_number( - mocked_drone: Drone, debug_flag, expected_connections -): - mocked_drone._state_watcher._general_state = {"debug_flags": debug_flag} - mocked_drone._state_watcher._general_state_received.set() - assert mocked_drone.active_video_streams == expected_connections + assert mocked_drone.active_video_streams["main"] == 1 + assert mocked_drone.active_video_streams["guestport"] == 2 class TestTilt: - @pytest.mark.parametrize("version", ["0.1.2", "1.2.3"]) - def test_tilt_fails_on_old_version(self, mocked_drone, version): - mocked_drone.software_version_short = version - mocked_drone.features = ["tilt"] - with pytest.raises(RuntimeError): - mocked_drone.camera.tilt.set_speed(0) - with pytest.raises(RuntimeError): - _ = mocked_drone.camera.tilt.angle - def test_tilt_fails_on_drone_without_tilt(self, mocked_drone: Drone): mocked_drone.features = [] with pytest.raises(RuntimeError): - mocked_drone.camera.tilt.set_speed(0) + mocked_drone.camera.tilt.set_velocity(0) with pytest.raises(RuntimeError): _ = mocked_drone.camera.tilt.angle with pytest.raises(RuntimeError): _ = mocked_drone.camera.tilt.stabilization_enabled with pytest.raises(RuntimeError): - mocked_drone.camera.tilt.toggle_stabilization() + mocked_drone.camera.tilt.stabilization_enabled = True @pytest.mark.parametrize( - "thruster_setpoints, tilt_speed", + "tilt_velocity", [ - ((0, 0, 0, 0), 0), - ((1, 1, 1, 1), 1), - ((-1, -1, -1, -1), -1), - ((0.1, 0.2, 0.3, 0.4), 0.5), + 0, + 1, + -1, + 0.5, ], ) - def test_tilt_calls_motion_input_with_correct_arguments( - self, mocked_drone, thruster_setpoints, tilt_speed - ): + def test_setting_tilt_velocity_works(self, mocked_drone, tilt_velocity): mocked_drone.features = ["tilt"] - mocked_drone.software_version_short = "1.5.33" - mocked_drone.motion._current_thruster_setpoints = { - "surge": thruster_setpoints[0], - "sway": thruster_setpoints[1], - "heave": thruster_setpoints[2], - "yaw": thruster_setpoints[3], - } - mocked_drone.camera.tilt.set_speed(tilt_speed) - mocked_drone._tcp_client.motion_input_tilt.assert_called_with( - *thruster_setpoints, 0, 0, tilt_speed - ) + mocked_drone.camera.tilt.set_velocity(tilt_velocity) + mocked_drone._ctrl_client.set_tilt_velocity.assert_called_with(tilt_velocity) @pytest.mark.parametrize( - "debug_flags, expected_angle", + "expected_angle", [ - (0x0000440000000000, 34.0), - (0x12344456789ABCDE, 34.0), - (0x0000000000000000, 0.0), - (0x12340056789ABCDE, 0.0), - (0x0000BE0000000000, -33.0), - (0x1234BE56789ABCDE, -33.0), + 34.0, + 0.0, + -33.0, ], ) - def test_tilt_returns_expected_angle(self, mocked_drone, debug_flags, expected_angle): + def test_tilt_returns_expected_angle(self, mocked_drone, expected_angle): mocked_drone.features = ["tilt"] - mocked_drone.software_version_short = "1.5.33" - mocked_drone._state_watcher._general_state = {"debug_flags": debug_flags} - mocked_drone._state_watcher._general_state_received.set() + TiltAngleTel = bp.TiltAngleTel(angle={"value": expected_angle}) + TiltAngleTel_serialized = bp.TiltAngleTel.serialize(TiltAngleTel) + mocked_drone._telemetry_watcher._state[bp.TiltAngleTel] = TiltAngleTel_serialized assert mocked_drone.camera.tilt.angle == expected_angle @pytest.mark.parametrize( - "debug_flags, expected_state", + "expected_state", [ - (0x0000000000000100, True), - (0x12344456789AFFDE, True), - (0x0000000000000000, False), - (0x12344456789A00DE, False), - (0x12344456789AF0DE, False), + True, + False, ], ) - def test_tilt_stabilization_state(self, mocked_drone: Drone, debug_flags, expected_state): + def test_tilt_stabilization_state(self, mocked_drone: Drone, expected_state): mocked_drone.features = ["tilt"] - mocked_drone.software_version_short = "1.6.42" - mocked_drone._state_watcher._general_state = {"debug_flags": debug_flags} - mocked_drone._state_watcher._general_state_received.set() + TiltStabilizationTel = bp.TiltStabilizationTel(state={"enabled": expected_state}) + TiltStabilizationTel_serialized = bp.TiltStabilizationTel.serialize(TiltStabilizationTel) + mocked_drone._telemetry_watcher._state[ + bp.TiltStabilizationTel + ] = TiltStabilizationTel_serialized assert mocked_drone.camera.tilt.stabilization_enabled == expected_state - def test_toggle_tilt_stabilization(self, mocked_drone: Drone): + def test_set_tilt_stabilization(self, mocked_drone: Drone): mocked_drone.features = ["tilt"] - mocked_drone.software_version_short = "1.6.42" - mocked_drone.camera.tilt.toggle_stabilization() - assert mocked_drone._tcp_client.toggle_tilt_stabilization.call_count == 1 + mocked_drone.camera.tilt.stabilization_enabled = True + assert mocked_drone._ctrl_client.set_tilt_stabilization.call_count == 1 class TestConfig: def test_water_density_property_returns_correct_value(self, mocked_drone: Drone): - mocked_drone.software_version_short = "1.5.33" - mocked_drone.config._water_density = 1000 - assert mocked_drone.config.water_density == 1000 + mocked_drone.config._water_density = 1.0 + assert mocked_drone.config.water_density == 1.0 - @pytest.mark.parametrize("version", ["0.1.2", "1.2.3", "1.4.7"]) - def test_setting_density_fails_on_old_versions(self, mocked_drone: Drone, version): - mocked_drone.software_version_short = version - with pytest.raises(RuntimeError): - mocked_drone.config.water_density = 1000 - - @pytest.mark.parametrize("version", ["1.5.0", "1.6.2", "2.1.3"]) - def test_setting_density_works_on_new_versions(self, mocked_drone: Drone, version): - mocked_drone.software_version_short = version + def test_setting_density(self, mocked_drone: Drone): old_value = mocked_drone.config.water_density - new_value = old_value + 10 + new_value = old_value + 0.010 mocked_drone.config.water_density = new_value assert mocked_drone.config.water_density == new_value - mocked_drone._tcp_client.set_water_density.assert_called_once() + mocked_drone._ctrl_client.set_water_density.assert_called_once() - def test_set_drone_time_is_called_on_connetion(self, mocked_drone: Drone): + def test_set_drone_time_is_called_on_connection(self, mocked_drone: Drone): with freeze_time("2019-01-01"): expected_time = int(time()) mocked_drone.connect() - mocked_drone._tcp_client.set_system_time.assert_called_with(expected_time) + mocked_drone._req_rep_client.sync_time.assert_called_with(expected_time) class TestMotion: @@ -325,7 +240,7 @@ def test_boost_getter_returns_expected_value(self, mocked_drone): def test_boost_setter_produces_correct_motion_input_arguments(self, mocked_drone): boost_gain = 0.5 mocked_drone.motion.boost = boost_gain - mocked_drone._tcp_client.motion_input.assert_called_with(0, 0, 0, 0, 0, boost_gain) + mocked_drone._ctrl_client.set_motion_input.assert_called_with(0, 0, 0, 0, 0, boost_gain) def test_slow_getter_returns_expected_value(self, mocked_drone): mocked_drone.motion._current_boost_setpoints["slow"] = 1 @@ -334,4 +249,16 @@ def test_slow_getter_returns_expected_value(self, mocked_drone): def test_slow_setter_produces_correct_motion_input_arguments(self, mocked_drone): slow_gain = 0.3 mocked_drone.motion.slow = slow_gain - mocked_drone._tcp_client.motion_input.assert_called_with(0, 0, 0, 0, slow_gain, 0) + mocked_drone._ctrl_client.set_motion_input.assert_called_with(0, 0, 0, 0, slow_gain, 0) + + +def test_gp_cam_recording(mocked_drone): + mocked_drone.gp_cam = Camera(mocked_drone, is_guestport_camera=True) + record_state_tel = bp.RecordStateTel( + record_state={"main_is_recording": False, "guestport_is_recording": False} + ) + mocked_drone._telemetry_watcher._state[bp.RecordStateTel] = bp.RecordStateTel.serialize( + record_state_tel + ) + mocked_drone.gp_cam.is_recording = True + mocked_drone._ctrl_client.set_recording_state.assert_called_with(False, True)