diff --git a/.bumpversion.cfg b/.bumpversion.cfg index da041c88..17518636 100644 --- a/.bumpversion.cfg +++ b/.bumpversion.cfg @@ -4,18 +4,14 @@ message = Bump version to {new_version} commit = True tag = True -[bumpversion:file:docs/conf.py] -search = version = release = '{current_version}' -replace = version = release = '{new_version}' - [bumpversion:file:docs/doc_versions.txt] search = {current_version} replace = {new_version} {current_version} -[bumpversion:file:CHANGELOG.rst] +[bumpversion:file:CHANGELOG.md] search = Unreleased -replace = {new_version} +replace = [{new_version}] {now:%Y-%m-%d} [bumpversion:file:src/compas_rrc/__version__.py] search = __version__ = '{current_version}' diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index 5e55b229..4f49572c 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -13,7 +13,7 @@ _Put an `x` in the boxes that apply. You can also fill these out after creating the PR. If you're unsure about any of them, don't hesitate to ask. We're here to help! This is simply a reminder of what we are going to look for before merging your code._ -- [ ] I added a line to the `CHANGELOG.rst` file in the `Unreleased` section under the most fitting heading (e.g. `Added`, `Changed`, `Removed`). +- [ ] I added a line to the `CHANGELOG.md` file in the `Unreleased` section under the most fitting heading (e.g. `Added`, `Changed`, `Removed`). - [ ] I ran all tests on my computer and it's all green (i.e. `invoke test`). - [ ] I ran lint on my computer and there are no errors (i.e. `invoke lint`). - [ ] I have added tests that prove my fix is effective or that my feature works. diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 43f1946b..dbabe5c9 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -9,64 +9,16 @@ on: - main jobs: - build-cpython: + build: + if: "!contains(github.event.pull_request.labels.*.name, 'docs-only')" runs-on: ${{ matrix.os }} strategy: matrix: - name: [ - "windows-py38", - "macos-py37", - "ubuntu-py36", - ] - include: - - name: "windows-py38" - os: windows-latest - python-version: 3.8 - - name: "macos-py37" - os: macos-latest - python-version: 3.7 - - name: "ubuntu-py36" - os: ubuntu-latest - python-version: 3.6 + os: [ubuntu-latest, macos-latest, windows-latest] + python: ['3.8', '3.9', '3.10'] + steps: - - uses: actions/checkout@v2 - - name: Set up Python ${{ matrix.python-version }} - uses: actions/setup-python@v2 + - uses: compas-dev/compas-actions.build@v3 with: - python-version: ${{ matrix.python-version }} - - name: Install dependencies - run: | - python -m pip install --upgrade pip - python -m pip install wheel - python -m pip install cython --install-option="--no-cython-compile" - - name: Install - run: | - python -m pip install --no-cache-dir -r requirements-dev.txt - - name: Run linter - run: | - invoke lint - - name: Run tests - run: | - pytest - build-ironpython: - name: windows-ironpython - runs-on: windows-latest - steps: - - uses: actions/checkout@v2 - - name: Install dependencies - run: | - curl -o compas.tar.gz -LJO https://pypi.debian.net/compas/latest - curl -o compas_fab.tar.gz -LJO https://pypi.debian.net/compas_fab/latest - curl -o roslibpy.tar.gz -LJO https://pypi.debian.net/roslibpy/latest - curl -o ironpython-pytest.tar.gz -LJO https://pypi.debian.net/ironpython-pytest/latest - choco install ironpython --version=2.7.8.1 - ipy -X:Frames -m ensurepip - ipy -X:Frames -m pip install --no-deps compas.tar.gz - ipy -X:Frames -m pip install --no-deps compas_fab.tar.gz - ipy -X:Frames -m pip install --no-deps roslibpy.tar.gz - ipy -X:Frames -m pip install --no-deps ironpython-pytest.tar.gz - - name: Run tests - env: - IRONPYTHONPATH: ./src - run: | - ipy tests/ipy_test_runner.py + python: ${{ matrix.python }} + invoke_lint: true diff --git a/.github/workflows/deploy-n-publish.yml b/.github/workflows/deploy-n-publish.yml deleted file mode 100644 index c97b7e80..00000000 --- a/.github/workflows/deploy-n-publish.yml +++ /dev/null @@ -1,75 +0,0 @@ -name: deploy-and-publish - -on: - push: - branches: - - main - tags: - - 'v*' - pull_request: - branches: - - main - -jobs: - build: - name: build and deploy docs - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v2 - - name: Set up Python 3.8 - uses: actions/setup-python@v2 - with: - python-version: 3.8 - - name: 🔗 Install dependencies - run: | - python -m pip install --upgrade pip - python -m pip install wheel - python -m pip install cython --install-option="--no-cython-compile" - - name: 💎 Install - run: | - python -m pip install --no-cache-dir -r requirements-dev.txt - - name: 📃 Generate docs - if: success() - run: | - invoke docs --check-links - - # Get branch/tag/latest name from git - GITHUB_REF_REGEX="tags/v([0-9a-zA-Z\.\-]+)|(pull/[0-9]+)|heads/(.+)" - - if [[ $GITHUB_REF =~ $GITHUB_REF_REGEX ]]; then - if [[ $BASH_REMATCH = pull* ]]; then - BRANCH_OR_TAG=pull_${BASH_REMATCH##*/} - elif [[ $BASH_REMATCH = tags/v* ]]; then - # 2nd element is tag, #v replaces prefix v - BRANCH_OR_TAG=${BASH_REMATCH[1]#v} - else - BRANCH_OR_TAG=${BASH_REMATCH##*/} - fi; - - if [[ $BRANCH_OR_TAG = main ]]; then - BRANCH_OR_TAG=latest - fi; - fi; - - echo "Docs will be deployed to https://compas-rrc.github.io/compas_rrc/$BRANCH_OR_TAG" - mkdir -p deploy/$BRANCH_OR_TAG && mv -T dist/docs deploy/$BRANCH_OR_TAG/ - - name: 🚢 Deploy docs - if: success() - uses: crazy-max/ghaction-github-pages@v2 - with: - target_branch: gh-pages - build_dir: deploy - keep_history: true - env: - GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} - - name: 💃 Build release - if: success() && startsWith(github.ref, 'refs/tags') - run: | - python setup.py clean --all sdist bdist_wheel - - name: 📦 Publish release to PyPI - if: success() && startsWith(github.ref, 'refs/tags') - uses: pypa/gh-action-pypi-publish@master - with: - user: __token__ - password: ${{ secrets.pypi_password }} - diff --git a/.github/workflows/docs.yml b/.github/workflows/docs.yml new file mode 100644 index 00000000..8cf4ad16 --- /dev/null +++ b/.github/workflows/docs.yml @@ -0,0 +1,20 @@ +name: docs + +on: + push: + branches: + - main + tags: + - 'v*' + pull_request_review: + types: [submitted] + +jobs: + docs: + if: github.ref == 'refs/heads/main' || startsWith(github.ref, 'refs/tags/v') || (github.event_name == 'pull_request_review' && github.event.review.state == 'approved') + runs-on: ubuntu-latest + steps: + - uses: compas-dev/compas-actions.docs@v3 + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + doc_url: https://compas-rrc.github.io/compas_rrc diff --git a/.github/workflows/ironpython.yml b/.github/workflows/ironpython.yml new file mode 100644 index 00000000..35a2ac96 --- /dev/null +++ b/.github/workflows/ironpython.yml @@ -0,0 +1,45 @@ +name: ironpython + +on: + push: + branches: + - main + pull_request: + branches: + - main + +jobs: + build: + name: windows-ironpython + runs-on: windows-latest + steps: + - uses: actions/checkout@v2 + - name: Install dependencies + run: | + choco install ironpython --version=2.7.8.1 + curl -o ironpython-pytest.tar.gz -LJO https://pypi.debian.net/ironpython-pytest/latest + curl -o roslibpy.tar.gz -LJO https://pypi.debian.net/roslibpy/latest + curl -o compas.tar.gz -LJO https://pypi.debian.net/compas/latest + curl -o compas_robots.tar.gz -LJO https://pypi.debian.net/compas_robots/latest + curl -o compas_fab.tar.gz -LJO https://pypi.debian.net/compas_fab/latest + ipy -X:Frames -m ensurepip + ipy -X:Frames -m pip install --no-deps ironpython-pytest.tar.gz + ipy -X:Frames -m pip install --no-deps roslibpy.tar.gz + ipy -X:Frames -m pip install --no-deps compas.tar.gz + ipy -X:Frames -m pip install --no-deps compas_robots.tar.gz + ipy -X:Frames -m pip install --no-deps compas_fab.tar.gz + # - uses: NuGet/setup-nuget@v1.0.5 + # - uses: compas-dev/compas-actions.ghpython_components@v5 + # with: + # source: src/compas_rrc/ghpython/components + # target: src/compas_rrc/ghpython/components/ghuser + - name: Test import + run: | + ipy -c "import compas_rrc" + env: + IRONPYTHONPATH: ./src + - name: Run tests + run: | + ipy tests/ipy_test_runner.py + env: + IRONPYTHONPATH: ./src diff --git a/.github/workflows/pr-checks.yml b/.github/workflows/pr-checks.yml index 6f10bb28..fe3c6950 100644 --- a/.github/workflows/pr-checks.yml +++ b/.github/workflows/pr-checks.yml @@ -10,10 +10,11 @@ jobs: name: Check Actions runs-on: ubuntu-latest steps: - - uses: actions/checkout@v1 + - uses: actions/checkout@v2 - name: Changelog check - uses: Zomzog/changelog-checker@v1.1.0 + uses: Zomzog/changelog-checker@v1.2.0 with: - fileName: CHANGELOG.rst + fileName: CHANGELOG.md + checkNotification: Simple env: GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml new file mode 100644 index 00000000..bfb17607 --- /dev/null +++ b/.github/workflows/release.yml @@ -0,0 +1,36 @@ +on: + push: + tags: + - 'v*' + +name: Create Release + +jobs: + build: + runs-on: ${{ matrix.os }} + strategy: + matrix: + os: [ubuntu-latest, macos-latest, windows-latest] + python: ['3.8', '3.9', '3.10'] + + steps: + - uses: compas-dev/compas-actions.build@v3 + with: + python: ${{ matrix.python }} + invoke_lint: true + check_import: true + + publish: + needs: build + runs-on: windows-latest + steps: + - uses: compas-dev/compas-actions.publish@v2 + with: + pypi_token: ${{ secrets.PYPI_PASSWORD }} + github_token: ${{ secrets.GITHUB_TOKEN }} + build_ghpython_components: false + # gh_source: src/compas_rrc/ghpython/components + # gh_target: src/compas_rrc/ghpython/components/ghuser + # gh_prefix: "COMPAS RRC: " + gh_interpreter: "ironpython" + release_name_prefix: COMPAS RRC diff --git a/.gitignore b/.gitignore index 8d64a476..cf26730a 100644 --- a/.gitignore +++ b/.gitignore @@ -109,3 +109,4 @@ ENV/ # autogenerated sphinx docs/reference/generated/ +docs/api/generated/ diff --git a/CHANGELOG.md b/CHANGELOG.md new file mode 100644 index 00000000..acd5db6a --- /dev/null +++ b/CHANGELOG.md @@ -0,0 +1,29 @@ +# Changelog + +All notable changes to this project will be documented in this file. + +The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/), +and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0.html). + +## Unreleased + +### Added + +* Added `to_configuration` and `to_configuration_primitive` to `compas_rrc.ExternalAxes` and `compas_rrc.RobotJoints` + +### Changed + +* Update minimum requirements to `compas_fab > 1.x` and `compas > 2.x` + +### Removed + +## 1.1.0 + +### Added + +* Prepared github actions for continuous integration +* Added compas plugin for automatic Rhino install + +## 1.0.0 + +* Initial version diff --git a/CHANGELOG.rst b/CHANGELOG.rst deleted file mode 100644 index 7b962161..00000000 --- a/CHANGELOG.rst +++ /dev/null @@ -1,39 +0,0 @@ - -Changelog -========= - -Unreleased ----------- - -**Added** - -* Added `to_configuration` and `to_configuration_primitive` to `compas_rrc.ExternalAxes` and `compas_rrc.RobotJoints` - -**Changed** - -**Fixed** - -**Deprecated** - -**Removed** - -1.1.0 ----------- - -**Added** - -* Prepared github actions for continuous integration -* Added compas plugin for automatic Rhino install - -**Changed** - -**Fixed** - -**Deprecated** - -**Removed** - -1.0.0 -------- - -* Initial version diff --git a/MANIFEST.in b/MANIFEST.in index ab2a8d68..ebb02e76 100644 --- a/MANIFEST.in +++ b/MANIFEST.in @@ -10,7 +10,7 @@ include .bumpversion.cfg include .editorconfig include AUTHORS.rst -include CHANGELOG.rst +include CHANGELOG.md include CONTRIBUTING.rst include LICENSE include README.rst diff --git a/docs/reference/abb-reference.rst b/docs/api/abb-reference.rst similarity index 100% rename from docs/reference/abb-reference.rst rename to docs/api/abb-reference.rst diff --git a/docs/reference/concepts.rst b/docs/api/concepts.rst similarity index 100% rename from docs/reference/concepts.rst rename to docs/api/concepts.rst diff --git a/docs/reference/custom_instructions.rst b/docs/api/custom_instructions.rst similarity index 100% rename from docs/reference/custom_instructions.rst rename to docs/api/custom_instructions.rst diff --git a/docs/reference/index.rst b/docs/api/index.rst similarity index 100% rename from docs/reference/index.rst rename to docs/api/index.rst diff --git a/docs/reference/instructions.rst b/docs/api/instructions.rst similarity index 100% rename from docs/reference/instructions.rst rename to docs/api/instructions.rst diff --git a/docs/changelog.rst b/docs/changelog.rst deleted file mode 100644 index 565b0521..00000000 --- a/docs/changelog.rst +++ /dev/null @@ -1 +0,0 @@ -.. include:: ../CHANGELOG.rst diff --git a/docs/conf.py b/docs/conf.py index 0fb0652c..6264fc0b 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -1,144 +1,170 @@ +# flake8: noqa # -*- coding: utf-8 -*- -from __future__ import unicode_literals - -import os -import sphinx_compas_theme - -from sphinx.ext.napoleon.docstring import NumpyDocstring - -extensions = [ - 'sphinx.ext.autodoc', - 'sphinx.ext.autosummary', - 'sphinx.ext.coverage', - 'sphinx.ext.doctest', - 'sphinx.ext.intersphinx', - 'sphinx.ext.extlinks', - 'sphinx.ext.ifconfig', - 'sphinx.ext.napoleon', - 'sphinx.ext.todo', - 'sphinx.ext.viewcode', -] -if os.getenv('SPELLCHECK'): - extensions += 'sphinxcontrib.spelling', - spelling_show_suggestions = True - spelling_lang = 'en_US' - -source_suffix = '.rst' -master_doc = 'index' -project = 'COMPAS RRC' -year = '2019' -author = 'ETH Zurich' -copyright = '{0}, {1}'.format(year, author) -version = release = '1.1.0' - -pygments_style = 'sphinx' -show_authors = True + +from sphinx.writers import html, html5 +import sphinx_compas2_theme + +# -- General configuration ------------------------------------------------ +project = "COMPAS RRC" +copyright = "2019-2024, ETH Zurich" +author = "ETH Zurich" +organization = "compas-rrc" +package = "compas_rrc" + +master_doc = "index" +source_suffix = {".rst": "restructuredtext", ".md": "markdown"} +templates_path = sphinx_compas2_theme.get_autosummary_templates_path() +exclude_patterns = sphinx_compas2_theme.default_exclude_patterns add_module_names = True -templates_path = ['_templates', ] -extlinks = { - 'issue': ('https://github.com/compas-rrc/compas_rrc/issues/%s', '#'), - 'pr': ('https://github.com/compas-rrc/compas_rrc/pull/%s', 'PR #'), -} +language = "en" -# intersphinx options -intersphinx_mapping = {'python': ('https://docs.python.org/', None), - 'compas': ('https://compas.dev/compas/latest/', None), - 'compas_fab': ('https://gramaziokohler.github.io/compas_fab/latest/', None), - 'roslibpy': ('https://roslibpy.readthedocs.io/en/latest/', None), - } +latest_version = sphinx_compas2_theme.get_latest_version() + +if latest_version == "Unreleased": + release = "Unreleased" + version = "latest" +else: + release = latest_version + version = ".".join(release.split(".")[0:2]) # type: ignore + +# -- Extension configuration ------------------------------------------------ + +extensions = sphinx_compas2_theme.default_extensions + +# numpydoc options + +numpydoc_show_class_members = False +numpydoc_class_members_toctree = False +numpydoc_attributes_as_param_list = True +numpydoc_show_inherited_class_members = False + +# bibtex options # autodoc options + +autodoc_type_aliases = {} +autodoc_typehints_description_target = "documented" +autodoc_mock_imports = sphinx_compas2_theme.default_mock_imports autodoc_default_options = { - 'member-order': 'bysource', - 'exclude-members': '__weakref__', - 'undoc-members': True, - 'private-members': True, - 'show-inheritance': True, + "undoc-members": True, + "show-inheritance": True, + "private-members": True, + "exclude-members": "__weakref__", } -autodoc_member_order = 'alphabetical' +autodoc_member_order = "alphabetical" +autodoc_typehints = "description" +autodoc_class_signature = "separated" -# autosummary options -autosummary_generate = True +autoclass_content = "class" -# collect doc versions -package_docs_root = 'https://compas-rrc.github.io/compas_rrc/' -with open(os.path.join(os.path.dirname(__file__), 'doc_versions.txt'), 'r') as f: - version_names = [version.strip() for version in f.readlines()] - package_docs_versions = [(version, '{}{}/'.format(package_docs_root, version)) - for version in version_names if version] +def setup(app): + app.connect("autodoc-skip-member", sphinx_compas2_theme.skip) -# on_rtd is whether we are on readthedocs.org -on_rtd = os.environ.get('READTHEDOCS', None) == 'True' -html_theme = 'compaspkg' -html_theme_path = sphinx_compas_theme.get_html_theme_path() -html_theme_options = { - "package_name": 'compas_rrc', - "package_title": project, - "package_version": release, - "package_repo": 'https://github.com/compas-rrc/compas_rrc', - "package_docs": package_docs_root, - "package_old_versions": package_docs_versions -} -html_split_index = False -html_short_title = '%s-%s' % (project, version) -html_context = {} -html_static_path = ['_static'] -html_last_updated_fmt = '%b %d, %Y' -html_copy_source = False -html_show_sourcelink = False -html_add_permalinks = '' -html_permalinks = False -html_experimental_html5_writer = True -html_compact_lists = True +# autosummary options -# napoleon options -napoleon_google_docstring = True -napoleon_numpy_docstring = True -napoleon_include_init_with_doc = False -napoleon_include_private_with_doc = True -napoleon_include_special_with_doc = True -napoleon_use_admonition_for_examples = False -napoleon_use_admonition_for_notes = False -napoleon_use_admonition_for_references = False -napoleon_use_ivar = False -napoleon_use_param = False -napoleon_use_rtype = False +autosummary_generate = True +autosummary_mock_imports = sphinx_compas2_theme.default_mock_imports -# Parse Attributes and Class Attributes on Class docs same as parameters. -# first, we define new methods for any new sections and add them to the class +# graph options +# plot options -def parse_keys_section(self, section): - return self._format_fields('Keys', self._consume_fields()) +plot_include_source = False +plot_html_show_source_link = False +plot_html_show_formats = False +plot_formats = ["png"] +# intersphinx options -NumpyDocstring._parse_keys_section = parse_keys_section +intersphinx_mapping = { + "python": ("https://docs.python.org/", None), + "compas": ("https://compas.dev/compas/latest/", None), + "compas_fab": ("https://compas.dev/compas_fab/latest/", None), + "roslibpy": ("https://roslibpy.readthedocs.io/en/latest/", None), +} +# linkcode -def parse_attributes_section(self, section): - return self._format_fields('Attributes', self._consume_fields()) +linkcode_resolve = sphinx_compas2_theme.get_linkcode_resolve(organization, package) +# extlinks -NumpyDocstring._parse_attributes_section = parse_attributes_section +extlinks = { + "rhino": ("https://developer.rhino3d.com/api/RhinoCommon/html/T_%s.htm", "%s"), + "blender": ("https://docs.blender.org/api/2.93/%s.html", "%s"), +} +# from pytorch -def parse_class_attributes_section(self, section): - return self._format_fields('Class Attributes', self._consume_fields()) +sphinx_compas2_theme.replace(html.HTMLTranslator) +sphinx_compas2_theme.replace(html5.HTML5Translator) +# -- Options for HTML output ---------------------------------------------- -NumpyDocstring._parse_class_attributes_section = parse_class_attributes_section +html_theme = "sidebaronly" +html_title = project +html_sidebars = {"index": []} +favicons = [ + { + "rel": "icon", + "href": "compas.ico", + } +] -# we now patch the parse method to guarantee that the the above methods are -# assigned to the _section dict -def patched_parse(self): - self._sections['keys'] = self._parse_keys_section - self._sections['class attributes'] = self._parse_class_attributes_section - self._unpatched_parse() +html_theme_options = { + "external_links": [ + {"name": "COMPAS RRC", "url": "https://compas-rrc.github.io/compas_rrc/"}, + ], + "icon_links": [ + { + "name": "GitHub", + "url": f"https://github.com/{organization}/{package}", + "icon": "fa-brands fa-github", + "type": "fontawesome", + }, + { + "name": "Discourse", + "url": "http://forum.compas-framework.org/", + "icon": "fa-brands fa-discourse", + "type": "fontawesome", + }, + { + "name": "PyPI", + "url": f"https://pypi.org/project/{package}/", + "icon": "fa-brands fa-python", + "type": "fontawesome", + }, + ], + "switcher": { + "json_url": f"https://raw.githubusercontent.com/{organization}/{package}/gh-pages/versions.json", + "version_match": version, + }, + "logo": { + "image_light": "_static/compas_icon_white.png", + "image_dark": "_static/compas_icon_white.png", + "text": "COMPAS RRC", + }, + "navigation_depth": 2, +} +html_context = { + "github_url": "https://github.com", + "github_user": organization, + "github_repo": package, + "github_version": "main", + "doc_path": "docs", +} -NumpyDocstring._unpatched_parse = NumpyDocstring._parse -NumpyDocstring._parse = patched_parse +html_static_path = sphinx_compas2_theme.get_html_static_path() + ["_static"] +html_css_files = [] +html_extra_path = [] +html_last_updated_fmt = "" +html_copy_source = False +html_show_sourcelink = True +html_permalinks = False +html_permalinks_icon = "" +html_compact_lists = True diff --git a/docs/index.rst b/docs/index.rst index 116212bc..5389ea0e 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -16,12 +16,11 @@ Contents readme getting_started - reference/index + api/index links contributing architecture authors - changelog citing Indices and tables diff --git a/docs/links.rst b/docs/links.rst index 43729a5a..38ae8a1b 100644 --- a/docs/links.rst +++ b/docs/links.rst @@ -4,7 +4,7 @@ Relevant links * COMPAS Links * `COMPAS `_ - * `COMPAS FAB `_ + * `COMPAS FAB `_ * `COMPAS SLICER `_ * `COMPAS Forum `_ diff --git a/requirements-dev.txt b/requirements-dev.txt index 9131e552..244206d2 100644 --- a/requirements-dev.txt +++ b/requirements-dev.txt @@ -1,12 +1,14 @@ autopep8 +black bump2version>=1.0 check-manifest>=0.36 +compas_invocations +doc8 flake8 invoke>=0.14 isort pylint pytest -sphinx_compas_theme>=0.9 -sphinx>=1.6 +sphinx_compas2_theme twine -e . diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 00000000..8b27e6c2 --- /dev/null +++ b/requirements.txt @@ -0,0 +1 @@ +compas_fab >= 1, < 2 diff --git a/setup.py b/setup.py index e6ef837e..49eb8de6 100644 --- a/setup.py +++ b/setup.py @@ -15,59 +15,58 @@ from setuptools import find_packages from setuptools import setup -requirements = ['compas_fab', 'roslibpy>=1.1'] +requirements = ["compas_fab", "roslibpy>=1.1"] keywords_list = [] here = abspath(dirname(__file__)) def read(*names, **kwargs): - return io.open( - join(here, *names), - encoding=kwargs.get('encoding', 'utf8') - ).read() + return io.open(join(here, *names), encoding=kwargs.get("encoding", "utf8")).read() about = {} -exec(read('src', 'compas_rrc', '__version__.py'), about) +exec(read("src", "compas_rrc", "__version__.py"), about) + + +requirements = read("requirements.txt").split("\n") + setup( - name=about['__title__'], - version=about['__version__'], - license=about['__license__'], - description=about['__description__'], - author=about['__author__'], - author_email=about['__author_email__'], - url=about['__url__'], - long_description='%s\n%s' % ( - re.compile('^.. start-badges.*^.. end-badges', re.M | - re.S).sub('', read('README.rst')), - re.sub(':[a-z]+:`~?(.*?)`', r'``\1``', read('CHANGELOG.rst')) + name=about["__title__"], + version=about["__version__"], + license=about["__license__"], + description=about["__description__"], + author=about["__author__"], + author_email=about["__author_email__"], + url=about["__url__"], + long_description=re.compile("^.. start-badges.*^.. end-badges", re.M | re.S).sub( + "", read("README.rst") ), - packages=find_packages('src'), - package_dir={'': 'src'}, - py_modules=[splitext(basename(path))[0] for path in glob('src/*.py')], + packages=find_packages("src"), + package_dir={"": "src"}, + py_modules=[splitext(basename(path))[0] for path in glob("src/*.py")], include_package_data=True, zip_safe=False, classifiers=[ - 'Development Status :: 4 - Beta', - 'Intended Audience :: Developers', - 'Intended Audience :: Science/Research', - 'License :: OSI Approved :: MIT License', - 'Operating System :: Unix', - 'Operating System :: POSIX', - 'Operating System :: Microsoft :: Windows', - 'Programming Language :: Python', - 'Programming Language :: Python :: 3', - 'Programming Language :: Python :: 3.3', - 'Programming Language :: Python :: 3.4', - 'Programming Language :: Python :: 3.5', - 'Programming Language :: Python :: 3.6', - 'Programming Language :: Python :: 3.7', - 'Programming Language :: Python :: 3.8', - 'Programming Language :: Python :: Implementation :: CPython', - 'Programming Language :: Python :: Implementation :: IronPython', - 'Topic :: Scientific/Engineering', + "Development Status :: 4 - Beta", + "Intended Audience :: Developers", + "Intended Audience :: Science/Research", + "License :: OSI Approved :: MIT License", + "Operating System :: Unix", + "Operating System :: POSIX", + "Operating System :: Microsoft :: Windows", + "Programming Language :: Python", + "Programming Language :: Python :: 3", + "Programming Language :: Python :: 3.3", + "Programming Language :: Python :: 3.4", + "Programming Language :: Python :: 3.5", + "Programming Language :: Python :: 3.6", + "Programming Language :: Python :: 3.7", + "Programming Language :: Python :: 3.8", + "Programming Language :: Python :: Implementation :: CPython", + "Programming Language :: Python :: Implementation :: IronPython", + "Topic :: Scientific/Engineering", ], keywords=keywords_list, install_requires=requirements, diff --git a/src/compas_rrc/__init__.py b/src/compas_rrc/__init__.py index 3f94b298..82506ea2 100644 --- a/src/compas_rrc/__init__.py +++ b/src/compas_rrc/__init__.py @@ -85,12 +85,9 @@ __copyright__, __license__, __url__, - __version__ -) -from compas_rrc.client import ( - AbbClient, - RosClient + __version__, ) +from compas_rrc.client import AbbClient, RosClient from compas_rrc.common import ( CLIENT_PROTOCOL_VERSION, ExecutionLevel, @@ -99,7 +96,7 @@ FutureResult, InstructionException, RobotJoints, - TimeoutException + TimeoutException, ) from compas_rrc.custom import CustomInstruction from compas_rrc.io import ( @@ -109,15 +106,9 @@ ReadGroup, SetAnalog, SetDigital, - SetGroup -) -from compas_rrc.motion import ( - Motion, - MoveToFrame, - MoveToJoints, - MoveToRobtarget, - Zone + SetGroup, ) +from compas_rrc.motion import Motion, MoveToFrame, MoveToJoints, MoveToRobtarget, Zone from compas_rrc.msg import PrintText from compas_rrc.utility import ( Debug, @@ -130,58 +121,54 @@ SetTool, SetWorkObject, Stop, - WaitTime -) -from compas_rrc.watch import ( - ReadWatch, - StartWatch, - StopWatch + WaitTime, ) +from compas_rrc.watch import ReadWatch, StartWatch, StopWatch -__all_plugins__ = ['compas_rrc.__install'] +__all_plugins__ = ["compas_rrc.__install"] __all__ = [ - '__url__', - '__version__', - '__author__', - '__author_email__', - '__license__', - '__copyright__', - 'CLIENT_PROTOCOL_VERSION', - 'FeedbackLevel', - 'ExecutionLevel', - 'InstructionException', - 'TimeoutException', - 'FutureResult', - 'ExternalAxes', - 'RobotJoints', - 'RosClient', - 'AbbClient', - 'SetDigital', - 'SetAnalog', - 'SetGroup', - 'PulseDigital', - 'ReadAnalog', - 'ReadDigital', - 'ReadGroup', - 'Zone', - 'Motion', - 'MoveToJoints', - 'MoveToFrame', - 'MoveToRobtarget', - 'PrintText', - 'CustomInstruction', - 'Noop', - 'GetFrame', - 'GetJoints', - 'GetRobtarget', - 'SetAcceleration', - 'SetTool', - 'SetMaxSpeed', - 'Stop', - 'WaitTime', - 'SetWorkObject', - 'Debug', - 'ReadWatch', - 'StartWatch', - 'StopWatch', + "__url__", + "__version__", + "__author__", + "__author_email__", + "__license__", + "__copyright__", + "CLIENT_PROTOCOL_VERSION", + "FeedbackLevel", + "ExecutionLevel", + "InstructionException", + "TimeoutException", + "FutureResult", + "ExternalAxes", + "RobotJoints", + "RosClient", + "AbbClient", + "SetDigital", + "SetAnalog", + "SetGroup", + "PulseDigital", + "ReadAnalog", + "ReadDigital", + "ReadGroup", + "Zone", + "Motion", + "MoveToJoints", + "MoveToFrame", + "MoveToRobtarget", + "PrintText", + "CustomInstruction", + "Noop", + "GetFrame", + "GetJoints", + "GetRobtarget", + "SetAcceleration", + "SetTool", + "SetMaxSpeed", + "Stop", + "WaitTime", + "SetWorkObject", + "Debug", + "ReadWatch", + "StartWatch", + "StopWatch", ] diff --git a/src/compas_rrc/__install.py b/src/compas_rrc/__install.py index 2c78ff5a..7f07eee5 100644 --- a/src/compas_rrc/__install.py +++ b/src/compas_rrc/__install.py @@ -1,6 +1,6 @@ import compas.plugins -@compas.plugins.plugin(category='install') +@compas.plugins.plugin(category="install") def installable_rhino_packages(): - return ['compas_rrc'] + return ["compas_rrc"] diff --git a/src/compas_rrc/__version__.py b/src/compas_rrc/__version__.py index bcc3a296..5d6f0699 100644 --- a/src/compas_rrc/__version__.py +++ b/src/compas_rrc/__version__.py @@ -1,10 +1,19 @@ -__title__ = 'compas_rrc' -__description__ = 'COMPAS RRC: Library for ABB Robots' -__url__ = 'https://github.com/compas-rrc/compas_rrc' -__version__ = '1.1.0' -__author__ = 'ETH Zurich' -__author_email__ = 'rrc@arch.ethz.ch' -__license__ = 'MIT license' -__copyright__ = 'Copyright 2019 ETH Zurich' +__title__ = "compas_rrc" +__description__ = "COMPAS RRC: Library for ABB Robots" +__url__ = "https://github.com/compas-rrc/compas_rrc" +__version__ = "1.1.0" +__author__ = "ETH Zurich" +__author_email__ = "rrc@arch.ethz.ch" +__license__ = "MIT license" +__copyright__ = "Copyright 2019 ETH Zurich" -__all__ = ['__author__', '__author_email__', '__copyright__', '__description__', '__license__', '__title__', '__url__', '__version__'] +__all__ = [ + "__author__", + "__author_email__", + "__copyright__", + "__description__", + "__license__", + "__title__", + "__url__", + "__version__", +] diff --git a/src/compas_rrc/client.py b/src/compas_rrc/client.py index 0c3e2ec5..dbd43af5 100644 --- a/src/compas_rrc/client.py +++ b/src/compas_rrc/client.py @@ -8,22 +8,23 @@ from .common import FutureResult from .common import InstructionException -__all__ = ['RosClient', 'AbbClient'] +__all__ = ["RosClient", "AbbClient"] -FEEDBACK_ERROR_PREFIX = 'Done FError ' +FEEDBACK_ERROR_PREFIX = "Done FError " def _get_key(message): - return 'msg:{}'.format(message.sequence_id) + return "msg:{}".format(message.sequence_id) def _get_response_key(message): - return 'msg:{}'.format(message['feedback_id']) + return "msg:{}".format(message["feedback_id"]) class SequenceCounter(object): """An atomic, thread-safe sequence increament counter.""" + ROLLOVER_THRESHOLD = 1000000 def __init__(self, start=0): @@ -49,7 +50,7 @@ def value(self): def default_feedback_parser(result): - feedback_value = result['feedback'] + feedback_value = result["feedback"] if feedback_value.startswith(FEEDBACK_ERROR_PREFIX): return InstructionException(feedback_value, result) @@ -103,7 +104,7 @@ class AbbClient(object): """ - def __init__(self, ros, namespace='/rob1'): + def __init__(self, ros, namespace="/rob1"): """Initialize a new robot client instance. Parameters @@ -116,53 +117,77 @@ def __init__(self, ros, namespace='/rob1'): """ self.ros = ros self.counter = SequenceCounter() - if not namespace.endswith('/'): - namespace += '/' + if not namespace.endswith("/"): + namespace += "/" self._version_checked = False - self._server_protocol_check = dict(event=threading.Event(), - param=roslibpy.Param(ros, namespace + 'protocol_version'), - version=None) + self._server_protocol_check = dict( + event=threading.Event(), + param=roslibpy.Param(ros, namespace + "protocol_version"), + version=None, + ) self.ros.on_ready(self.version_check) - self.topic = roslibpy.Topic(ros, namespace + 'robot_command', 'compas_rrc_driver/RobotMessage', queue_size=None) - self.feedback = roslibpy.Topic(ros, namespace + 'robot_response', 'compas_rrc_driver/RobotMessage', queue_size=0) + self.topic = roslibpy.Topic( + ros, + namespace + "robot_command", + "compas_rrc_driver/RobotMessage", + queue_size=None, + ) + self.feedback = roslibpy.Topic( + ros, + namespace + "robot_response", + "compas_rrc_driver/RobotMessage", + queue_size=0, + ) self.feedback.subscribe(self.feedback_callback) self.topic.advertise() self.futures = {} - self.ros.on('closing', self._disconnect_topics) + self.ros.on("closing", self._disconnect_topics) def version_check(self): """Check if the protocol version on the server matches the protocol version on the client.""" - self._server_protocol_check['version'] = self._server_protocol_check['param'].get() + self._server_protocol_check["version"] = self._server_protocol_check[ + "param" + ].get() # No version is usually caused by wrong namespace in the connection, check that and raise correct error - if self._server_protocol_check['version'] is None: + if self._server_protocol_check["version"] is None: params = self.ros.get_params() detected_namespaces = set() tentative_namespaces = set() for param in params: - if param.endswith('/robot_state_port') or param.endswith('/protocol_version'): - namespace = param[:param.rindex('/')] + if param.endswith("/robot_state_port") or param.endswith( + "/protocol_version" + ): + namespace = param[: param.rindex("/")] if namespace not in tentative_namespaces: tentative_namespaces.add(namespace) else: detected_namespaces.add(namespace) - raise Exception('Cannot find the specified namespace. Detected namespaces={}'.format(sorted(detected_namespaces))) + raise Exception( + "Cannot find the specified namespace. Detected namespaces={}".format( + sorted(detected_namespaces) + ) + ) - self._server_protocol_check['event'].set() + self._server_protocol_check["event"].set() def ensure_protocol_version(self): """Ensure protocol version on the server matches the protocol version on the client.""" if self._version_checked: return - if not self._server_protocol_check['version']: - if not self._server_protocol_check['event'].wait(10): - raise Exception('Could not yet retrieve server protocol version') + if not self._server_protocol_check["version"]: + if not self._server_protocol_check["event"].wait(10): + raise Exception("Could not yet retrieve server protocol version") - if self._server_protocol_check['version'] != CLIENT_PROTOCOL_VERSION: - raise Exception('Protocol version mismatch. Server={}, Client={}'.format(self._server_protocol_check['version'], CLIENT_PROTOCOL_VERSION)) + if self._server_protocol_check["version"] != CLIENT_PROTOCOL_VERSION: + raise Exception( + "Protocol version mismatch. Server={}, Client={}".format( + self._server_protocol_check["version"], CLIENT_PROTOCOL_VERSION + ) + ) self._version_checked = True @@ -227,7 +252,11 @@ def send(self, instruction): if instruction.feedback_level > 0: result = FutureResult() - parser = instruction.parse_feedback if hasattr(instruction, 'parse_feedback') else None + parser = ( + instruction.parse_feedback + if hasattr(instruction, "parse_feedback") + else None + ) self.futures[key] = dict(result=result, parser=parser) self.topic.publish(roslibpy.Message(instruction.msg)) @@ -292,7 +321,11 @@ def send_and_subscribe(self, instruction, callback): key = _get_key(instruction) - parser = instruction.parse_feedback if hasattr(instruction, 'parse_feedback') else None + parser = ( + instruction.parse_feedback + if hasattr(instruction, "parse_feedback") + else None + ) self.futures[key] = dict(callback=callback, parser=parser) self.topic.publish(roslibpy.Message(instruction.msg)) @@ -304,13 +337,13 @@ def feedback_callback(self, message): if future: result = message - if future['parser']: - result = future['parser'](result) + if future["parser"]: + result = future["parser"](result) else: result = default_feedback_parser(result) - if 'result' in future: - future['result']._set_result(result) + if "result" in future: + future["result"]._set_result(result) self.futures.pop(response_key) - elif 'callback' in future: - future['callback'](result) + elif "callback" in future: + future["callback"](result) # TODO: Handle unsubscribes diff --git a/src/compas_rrc/common.py b/src/compas_rrc/common.py index c0a785b0..b95435b0 100644 --- a/src/compas_rrc/common.py +++ b/src/compas_rrc/common.py @@ -2,17 +2,19 @@ import math import threading -from compas.robots import Configuration -from compas.robots import Joint - -__all__ = ['CLIENT_PROTOCOL_VERSION', - 'FeedbackLevel', - 'ExecutionLevel', - 'InstructionException', - 'TimeoutException', - 'FutureResult', - 'ExternalAxes', - 'RobotJoints'] +from compas_robots import Configuration +from compas_robots.model import Joint + +__all__ = [ + "CLIENT_PROTOCOL_VERSION", + "FeedbackLevel", + "ExecutionLevel", + "InstructionException", + "TimeoutException", + "FutureResult", + "ExternalAxes", + "RobotJoints", +] CLIENT_PROTOCOL_VERSION = 2 @@ -20,13 +22,13 @@ def _convert_unit_to_meters_radians(value, type_): if type_ in {Joint.REVOLUTE, Joint.CONTINUOUS}: return math.radians(value) - return value / 1000. + return value / 1000.0 def _convert_unit_to_mm_degrees(value, type_): if type_ in {Joint.REVOLUTE, Joint.CONTINUOUS}: return math.degrees(value) - return value * 1000. + return value * 1000.0 class FeedbackLevel(object): @@ -35,6 +37,7 @@ class FeedbackLevel(object): .. autoattribute:: NONE .. autoattribute:: DONE """ + NONE = 0 """Indicates no feedback is requested from the robot.""" @@ -50,6 +53,7 @@ class ExecutionLevel(object): .. autoattribute:: ROBOT .. autoattribute:: CONTROLLER """ + ROBOT = 0 """Execute instruction on the robot task.""" @@ -61,12 +65,15 @@ class InstructionException(Exception): """Exception caused during/after the execution of an instruction.""" def __init__(self, message, result): - super(InstructionException, self).__init__('{}, RRC Reply={}'.format(message, result)) + super(InstructionException, self).__init__( + "{}, RRC Reply={}".format(message, result) + ) self.result = result class TimeoutException(Exception): """Timeout exception caused during execution of an instruction.""" + pass @@ -91,7 +98,7 @@ def result(self, timeout=None): """ if not self.done: if not self.event.wait(timeout): - raise TimeoutException('Timeout: future result not available') + raise TimeoutException("Timeout: future result not available") if isinstance(self.value, Exception): raise self.value @@ -177,7 +184,7 @@ def eax_f(self, value): # List accessors def __repr__(self): - return 'ExternalAxes({})'.format([round(i, 2) for i in self.values]) + return "ExternalAxes({})".format([round(i, 2) for i in self.values]) def __len__(self): return len(self.values) @@ -196,7 +203,7 @@ def __iter__(self): # Conversion methods def to_configuration_primitive(self, joint_types, joint_names=None): - """Convert the ExternalAxes to a :class:`compas.robots.Configuration`, including the unit conversion + """Convert the ExternalAxes to a :class:`compas_robots.Configuration`, including the unit conversion from mm and degrees to meters and radians. Parameters @@ -208,13 +215,16 @@ def to_configuration_primitive(self, joint_types, joint_names=None): Returns ------- - :class:`compas.robots.Configuration` + :class:`compas_robots.Configuration` """ - joint_values = [_convert_unit_to_meters_radians(value, type_) for value, type_ in zip(self.values, joint_types)] + joint_values = [ + _convert_unit_to_meters_radians(value, type_) + for value, type_ in zip(self.values, joint_types) + ] return Configuration(joint_values, joint_types, joint_names) def to_configuration(self, robot, group=None): - """Convert the ExternalAxes to a :class:`compas.robots.Configuration`, including the unit conversion + """Convert the ExternalAxes to a :class:`compas_robots.Configuration`, including the unit conversion from mm and degrees to meters and radians. Parameters @@ -227,7 +237,7 @@ def to_configuration(self, robot, group=None): Returns ------- - :class:`compas.robots.Configuration` + :class:`compas_robots.Configuration` """ joint_types = robot.get_configurable_joint_types(group) joint_names = robot.get_configurable_joint_names(group) @@ -235,12 +245,12 @@ def to_configuration(self, robot, group=None): @classmethod def from_configuration_primitive(cls, configuration, joint_names=None): - """Create an instance of ``ExternalAxes`` from a :class:`compas.robots.Configuration`, including the unit + """Create an instance of ``ExternalAxes`` from a :class:`compas_robots.Configuration`, including the unit conversion from meters and radians to mm and degrees. Parameters ---------- - configuration : :class:`compas.robots.Configuration` + configuration : :class:`compas_robots.Configuration` The configuration from which to create the ``ExternalAxes`` instance. joint_names : :obj:`list` An optional list of joint names from the ``configuration`` whose corresponding @@ -251,19 +261,29 @@ def from_configuration_primitive(cls, configuration, joint_names=None): :class:`compas_rrc.ExternalAxes` """ if joint_names: - joint_values = [_convert_unit_to_mm_degrees(configuration[name], configuration.type_dict[name]) for name in joint_names] + joint_values = [ + _convert_unit_to_mm_degrees( + configuration[name], configuration.type_dict[name] + ) + for name in joint_names + ] else: - joint_values = [_convert_unit_to_mm_degrees(value, type_) for value, type_ in zip(configuration.joint_values, configuration.joint_types)] + joint_values = [ + _convert_unit_to_mm_degrees(value, type_) + for value, type_ in zip( + configuration.joint_values, configuration.joint_types + ) + ] return cls(joint_values) @classmethod def from_configuration(cls, configuration, robot=None, group=None): - """Create an instance of ``ExternalAxes`` from a :class:`compas.robots.Configuration`, including the unit + """Create an instance of ``ExternalAxes`` from a :class:`compas_robots.Configuration`, including the unit conversion from meters and radians to mm and degrees. Parameters ---------- - configuration : :class:`compas.robots.Configuration` + configuration : :class:`compas_robots.Configuration` The configuration from which to create the ``ExternalAxes`` instance. robot : :class:`compas_fab.robots.Robot` The robot to be configured. Optional. @@ -339,7 +359,7 @@ def rax_6(self, value): # List accessors def __repr__(self): - return 'RobotJoints({})'.format([round(i, 2) for i in self.values]) + return "RobotJoints({})".format([round(i, 2) for i in self.values]) def __len__(self): return len(self.values) @@ -358,7 +378,7 @@ def __iter__(self): # Conversion methods def to_configuration_primitive(self, joint_types, joint_names=None): - """Convert the RobotJoints to a :class:`compas.robots.Configuration`, including the unit conversion + """Convert the RobotJoints to a :class:`compas_robots.Configuration`, including the unit conversion from mm and degrees to meters and radians. Parameters @@ -370,13 +390,16 @@ def to_configuration_primitive(self, joint_types, joint_names=None): Returns ------- - :class:`compas.robots.Configuration` + :class:`compas_robots.Configuration` """ - joint_values = [_convert_unit_to_meters_radians(value, type_) for value, type_ in zip(self.values, joint_types)] + joint_values = [ + _convert_unit_to_meters_radians(value, type_) + for value, type_ in zip(self.values, joint_types) + ] return Configuration(joint_values, joint_types, joint_names) def to_configuration(self, robot, group=None): - """Convert the RobotJoints to a :class:`compas.robots.Configuration`, including the unit conversion + """Convert the RobotJoints to a :class:`compas_robots.Configuration`, including the unit conversion from mm and degrees to meters and radians. Parameters @@ -389,7 +412,7 @@ def to_configuration(self, robot, group=None): Returns ------- - :class:`compas.robots.Configuration` + :class:`compas_robots.Configuration` """ joint_types = robot.get_configurable_joint_types(group) joint_names = robot.get_configurable_joint_names(group) @@ -397,12 +420,12 @@ def to_configuration(self, robot, group=None): @classmethod def from_configuration_primitive(cls, configuration, joint_names=None): - """Create an instance of ``RobotJoints`` from a :class:`compas.robots.Configuration`, including the unit + """Create an instance of ``RobotJoints`` from a :class:`compas_robots.Configuration`, including the unit conversion from meters and radians to mm and degrees. Parameters ---------- - configuration : :class:`compas.robots.Configuration` + configuration : :class:`compas_robots.Configuration` The configuration from which to create the ``RobotJoints`` instance. joint_names : :obj:`list` An optional list of joint names from the ``configuration`` whose corresponding @@ -413,19 +436,29 @@ def from_configuration_primitive(cls, configuration, joint_names=None): :class:`compas_rrc.RobotJoints` """ if joint_names: - joint_values = [_convert_unit_to_mm_degrees(configuration[name], configuration.type_dict[name]) for name in joint_names] + joint_values = [ + _convert_unit_to_mm_degrees( + configuration[name], configuration.type_dict[name] + ) + for name in joint_names + ] else: - joint_values = [_convert_unit_to_mm_degrees(value, type_) for value, type_ in zip(configuration.joint_values, configuration.joint_types)] + joint_values = [ + _convert_unit_to_mm_degrees(value, type_) + for value, type_ in zip( + configuration.joint_values, configuration.joint_types + ) + ] return cls(joint_values) @classmethod def from_configuration(cls, configuration, robot=None, group=None): - """Create an instance of ``RobotJoints`` from a :class:`compas.robots.Configuration`, including the unit + """Create an instance of ``RobotJoints`` from a :class:`compas_robots.Configuration`, including the unit conversion from meters and radians to mm and degrees. Parameters ---------- - configuration : :class:`compas.robots.Configuration` + configuration : :class:`compas_robots.Configuration` The configuration from which to create the ``ExternalAxes`` instance. robot : :class:`compas_fab.robots.Robot` The robot to be configured. Optional. diff --git a/src/compas_rrc/custom.py b/src/compas_rrc/custom.py index b55889b2..687b3de8 100644 --- a/src/compas_rrc/custom.py +++ b/src/compas_rrc/custom.py @@ -3,7 +3,7 @@ from compas_rrc.common import ExecutionLevel from compas_rrc.common import FeedbackLevel -__all__ = ['CustomInstruction'] +__all__ = ["CustomInstruction"] class CustomInstruction(ROSmsg): @@ -24,7 +24,14 @@ class CustomInstruction(ROSmsg): """ - def __init__(self, name, string_values=[], float_values=[], feedback_level=FeedbackLevel.NONE, execution_level=ExecutionLevel.ROBOT): + def __init__( + self, + name, + string_values=[], + float_values=[], + feedback_level=FeedbackLevel.NONE, + execution_level=ExecutionLevel.ROBOT, + ): """Create a new instance of the instruction. Parameters diff --git a/src/compas_rrc/io.py b/src/compas_rrc/io.py index 5ca28cab..e321bfa3 100644 --- a/src/compas_rrc/io.py +++ b/src/compas_rrc/io.py @@ -3,16 +3,16 @@ from compas_rrc.common import ExecutionLevel from compas_rrc.common import FeedbackLevel -INSTRUCTION_PREFIX = 'r_RRC_' +INSTRUCTION_PREFIX = "r_RRC_" __all__ = [ - 'SetDigital', - 'SetAnalog', - 'SetGroup', - 'PulseDigital', - 'ReadAnalog', - 'ReadDigital', - 'ReadGroup', + "SetDigital", + "SetAnalog", + "SetGroup", + "PulseDigital", + "ReadAnalog", + "ReadDigital", + "ReadGroup", ] @@ -48,7 +48,7 @@ def __init__(self, io_name, value, feedback_level=FeedbackLevel.NONE): """ if value not in (0, 1): raise ValueError("Value can only be 0 or 1") - self.instruction = INSTRUCTION_PREFIX + 'SetDigital' + self.instruction = INSTRUCTION_PREFIX + "SetDigital" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [io_name] @@ -85,7 +85,7 @@ def __init__(self, io_name, value, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'SetAnalog' + self.instruction = INSTRUCTION_PREFIX + "SetAnalog" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [io_name] @@ -122,7 +122,7 @@ def __init__(self, io_name, value, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'SetGroup' + self.instruction = INSTRUCTION_PREFIX + "SetGroup" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [io_name] @@ -158,7 +158,7 @@ def __init__(self, io_name, pulse_time, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'PulseDigital' + self.instruction = INSTRUCTION_PREFIX + "PulseDigital" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [io_name] @@ -189,7 +189,7 @@ def __init__(self, io_name): io_name : :obj:`str` Name of the input signal. """ - self.instruction = INSTRUCTION_PREFIX + 'ReadAnalog' + self.instruction = INSTRUCTION_PREFIX + "ReadAnalog" self.feedback_level = FeedbackLevel.DONE self.exec_level = ExecutionLevel.ROBOT self.string_values = [io_name] @@ -203,7 +203,7 @@ def parse_feedback(self, result): Current value of the input signal. """ # read input value - result = result['float_values'][0] + result = result["float_values"][0] return result @@ -231,7 +231,7 @@ def __init__(self, io_name): io_name : :obj:`str` Name of the input signal. """ - self.instruction = INSTRUCTION_PREFIX + 'ReadDigital' + self.instruction = INSTRUCTION_PREFIX + "ReadDigital" self.feedback_level = FeedbackLevel.DONE self.exec_level = ExecutionLevel.ROBOT self.string_values = [io_name] @@ -246,7 +246,7 @@ def parse_feedback(self, result): """ # read input value - result = int(result['float_values'][0]) + result = int(result["float_values"][0]) return result @@ -274,7 +274,7 @@ def __init__(self, io_name): io_name : :obj:`str` Name of the input signal. """ - self.instruction = INSTRUCTION_PREFIX + 'ReadGroup' + self.instruction = INSTRUCTION_PREFIX + "ReadGroup" self.feedback_level = FeedbackLevel.DONE self.exec_level = ExecutionLevel.ROBOT self.string_values = [io_name] @@ -289,5 +289,5 @@ def parse_feedback(self, result): """ # read input value - result = int(result['float_values'][0]) + result = int(result["float_values"][0]) return result diff --git a/src/compas_rrc/motion.py b/src/compas_rrc/motion.py index 59fee958..95b418be 100644 --- a/src/compas_rrc/motion.py +++ b/src/compas_rrc/motion.py @@ -3,14 +3,14 @@ from compas_rrc.common import ExecutionLevel from compas_rrc.common import FeedbackLevel -INSTRUCTION_PREFIX = 'r_RRC_' +INSTRUCTION_PREFIX = "r_RRC_" __all__ = [ - 'Zone', - 'Motion', - 'MoveToJoints', - 'MoveToFrame', - 'MoveToRobtarget', + "Zone", + "Motion", + "MoveToJoints", + "MoveToFrame", + "MoveToRobtarget", ] @@ -123,10 +123,11 @@ class Motion(object): .. autoattribute:: LINEAR .. autoattribute:: JOINT """ - LINEAR = 'L' + + LINEAR = "L" """Moves the robot linearly to the specified position.""" - JOINT = 'J' + JOINT = "J" """Moves the robot not linearly to the specified position by coordinating all joints to start and end together. This type of motion can be faster than LINEAR motion.""" @@ -155,7 +156,9 @@ class MoveToJoints(ROSmsg): """ - def __init__(self, joints, ext_axes, speed, zone, feedback_level=FeedbackLevel.NONE): + def __init__( + self, joints, ext_axes, speed, zone, feedback_level=FeedbackLevel.NONE + ): """Create a new instance of the instruction. Parameters @@ -175,30 +178,36 @@ def __init__(self, joints, ext_axes, speed, zone, feedback_level=FeedbackLevel.N the motion planner has executed the instruction fully. """ if speed <= 0: - raise ValueError('Speed must be higher than zero. Current value={}'.format(speed)) + raise ValueError( + "Speed must be higher than zero. Current value={}".format(speed) + ) - self.instruction = INSTRUCTION_PREFIX + 'MoveToJoints' + self.instruction = INSTRUCTION_PREFIX + "MoveToJoints" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT joints = joints or [] if len(joints) > 6: - raise ValueError('Only up to 6 joints are supported') + raise ValueError("Only up to 6 joints are supported") joints_pad = [0.0] * (6 - len(joints)) ext_axes = ext_axes or [] if len(ext_axes) > 6: - raise ValueError('Only up to 6 external axes are supported') + raise ValueError("Only up to 6 external axes are supported") ext_axes_pad = [0.0] * (6 - len(ext_axes)) self.string_values = [] - self.float_values = list(joints) + joints_pad + list(ext_axes) + ext_axes_pad + [speed, zone] + self.float_values = ( + list(joints) + joints_pad + list(ext_axes) + ext_axes_pad + [speed, zone] + ) class MoveGeneric(ROSmsg): def __init__(self, frame, ext_axes, speed, zone, feedback_level=FeedbackLevel.NONE): if speed <= 0: - raise ValueError('Speed must be higher than zero. Current value={}'.format(speed)) + raise ValueError( + "Speed must be higher than zero. Current value={}".format(speed) + ) self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT @@ -208,7 +217,7 @@ def __init__(self, frame, ext_axes, speed, zone, feedback_level=FeedbackLevel.NO ext_axes = ext_axes or [] if len(ext_axes) > 6: - raise ValueError('Only up to 6 external axes are supported') + raise ValueError("Only up to 6 external axes are supported") ext_axes_pad = [0.0] * (6 - len(ext_axes)) self.string_values = [] @@ -240,7 +249,14 @@ class MoveToFrame(MoveGeneric): """ - def __init__(self, frame, speed, zone, motion_type=Motion.JOINT, feedback_level=FeedbackLevel.NONE): + def __init__( + self, + frame, + speed, + zone, + motion_type=Motion.JOINT, + feedback_level=FeedbackLevel.NONE, + ): """Create a new instance of the instruction. Parameters @@ -260,9 +276,9 @@ def __init__(self, frame, speed, zone, motion_type=Motion.JOINT, feedback_level= the motion planner has executed the instruction fully. """ super(MoveToFrame, self).__init__(frame, [], speed, zone, feedback_level) - instruction = 'MoveTo' + instruction = "MoveTo" self.instruction = INSTRUCTION_PREFIX + instruction - self.string_values = ['FrameJ'] if motion_type == Motion.JOINT else ['FrameL'] + self.string_values = ["FrameJ"] if motion_type == Motion.JOINT else ["FrameL"] class MoveToRobtarget(MoveGeneric): @@ -289,7 +305,15 @@ class MoveToRobtarget(MoveGeneric): """ - def __init__(self, frame, ext_axes, speed, zone, motion_type=Motion.JOINT, feedback_level=FeedbackLevel.NONE): + def __init__( + self, + frame, + ext_axes, + speed, + zone, + motion_type=Motion.JOINT, + feedback_level=FeedbackLevel.NONE, + ): """Create a new instance of the instruction. Parameters @@ -310,7 +334,9 @@ def __init__(self, frame, ext_axes, speed, zone, motion_type=Motion.JOINT, feedb Use :attr:`FeedbackLevel.DONE` and :attr:`Zone.FINE` together to make sure the motion planner has executed the instruction fully. """ - super(MoveToRobtarget, self).__init__(frame, ext_axes, speed, zone, feedback_level) - instruction = 'MoveTo' + super(MoveToRobtarget, self).__init__( + frame, ext_axes, speed, zone, feedback_level + ) + instruction = "MoveTo" self.instruction = INSTRUCTION_PREFIX + instruction - self.string_values = ['J'] if motion_type == Motion.JOINT else ['L'] + self.string_values = ["J"] if motion_type == Motion.JOINT else ["L"] diff --git a/src/compas_rrc/msg.py b/src/compas_rrc/msg.py index a76eb368..019d2b59 100644 --- a/src/compas_rrc/msg.py +++ b/src/compas_rrc/msg.py @@ -3,11 +3,9 @@ from compas_rrc.common import ExecutionLevel from compas_rrc.common import FeedbackLevel -INSTRUCTION_PREFIX = 'r_RRC_' +INSTRUCTION_PREFIX = "r_RRC_" -__all__ = [ - 'PrintText' -] +__all__ = ["PrintText"] class PrintText(ROSmsg): @@ -38,7 +36,7 @@ def __init__(self, text, feedback_level=FeedbackLevel.NONE): """ if len(text) > 80: raise ValueError("text can only be up to 80 chars") - self.instruction = INSTRUCTION_PREFIX + 'PrintText' + self.instruction = INSTRUCTION_PREFIX + "PrintText" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [text] diff --git a/src/compas_rrc/utility.py b/src/compas_rrc/utility.py index 186d3ab0..724f53cb 100644 --- a/src/compas_rrc/utility.py +++ b/src/compas_rrc/utility.py @@ -6,19 +6,21 @@ from compas_rrc.common import FeedbackLevel from compas_rrc.common import RobotJoints -INSTRUCTION_PREFIX = 'r_RRC_' - -__all__ = ['Noop', - 'GetFrame', - 'GetJoints', - 'GetRobtarget', - 'SetAcceleration', - 'SetTool', - 'SetMaxSpeed', - 'Stop', - 'WaitTime', - 'SetWorkObject', - 'Debug'] +INSTRUCTION_PREFIX = "r_RRC_" + +__all__ = [ + "Noop", + "GetFrame", + "GetJoints", + "GetRobtarget", + "SetAcceleration", + "SetTool", + "SetMaxSpeed", + "Stop", + "WaitTime", + "SetWorkObject", + "Debug", +] def is_rapid_none(val): @@ -50,7 +52,7 @@ def __init__(self, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'Noop' + self.instruction = INSTRUCTION_PREFIX + "Noop" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -152,7 +154,7 @@ class GetJoints(ROSmsg): def __init__(self): """Create a new instance of the instruction.""" - self.instruction = INSTRUCTION_PREFIX + 'GetJoints' + self.instruction = INSTRUCTION_PREFIX + "GetJoints" self.feedback_level = FeedbackLevel.DONE self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -167,10 +169,14 @@ def parse_feedback(self, result): Current joints and external axes of the robot. """ # read robot joints - robot_joints = [result['float_values'][i] for i in range(0, 6)] + robot_joints = [result["float_values"][i] for i in range(0, 6)] # read external axes - external_axes = [result['float_values'][i] for i in range(6, 12) if not is_rapid_none(result['float_values'][i])] + external_axes = [ + result["float_values"][i] + for i in range(6, 12) + if not is_rapid_none(result["float_values"][i]) + ] # write result return RobotJoints(*robot_joints), ExternalAxes(*external_axes) @@ -195,7 +201,7 @@ class GetRobtarget(ROSmsg): def __init__(self): """Create a new instance of the instruction.""" - self.instruction = INSTRUCTION_PREFIX + 'GetRobtarget' + self.instruction = INSTRUCTION_PREFIX + "GetRobtarget" self.feedback_level = FeedbackLevel.DONE self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -211,20 +217,24 @@ def parse_feedback(self, result): """ # read pos - x = result['float_values'][0] - y = result['float_values'][1] - z = result['float_values'][2] + x = result["float_values"][0] + y = result["float_values"][1] + z = result["float_values"][2] pos = [x, y, z] # read orient - orient_q1 = result['float_values'][3] - orient_q2 = result['float_values'][4] - orient_q3 = result['float_values'][5] - orient_q4 = result['float_values'][6] + orient_q1 = result["float_values"][3] + orient_q2 = result["float_values"][4] + orient_q3 = result["float_values"][5] + orient_q4 = result["float_values"][6] orientation = [orient_q1, orient_q2, orient_q3, orient_q4] # read gantry joints - external_axes = [result['float_values'][i] for i in range(7, 13) if not is_rapid_none(result['float_values'][i])] + external_axes = [ + result["float_values"][i] + for i in range(7, 13) + if not is_rapid_none(result["float_values"][i]) + ] # write result @@ -292,7 +302,7 @@ def __init__(self, acc, ramp, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'SetAcceleration' + self.instruction = INSTRUCTION_PREFIX + "SetAcceleration" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -325,7 +335,7 @@ def __init__(self, tool_name, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'SetTool' + self.instruction = INSTRUCTION_PREFIX + "SetTool" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [tool_name] @@ -365,7 +375,7 @@ def __init__(self, override, max_tcp, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'SetMaxSpeed' + self.instruction = INSTRUCTION_PREFIX + "SetMaxSpeed" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -398,7 +408,7 @@ def __init__(self, wobj_name, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'SetWorkObject' + self.instruction = INSTRUCTION_PREFIX + "SetWorkObject" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [wobj_name] @@ -429,7 +439,7 @@ def __init__(self, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'Stop' + self.instruction = INSTRUCTION_PREFIX + "Stop" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -463,7 +473,7 @@ def __init__(self, time, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'WaitTime' + self.instruction = INSTRUCTION_PREFIX + "WaitTime" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [] diff --git a/src/compas_rrc/watch.py b/src/compas_rrc/watch.py index 73ba425f..41226457 100644 --- a/src/compas_rrc/watch.py +++ b/src/compas_rrc/watch.py @@ -3,12 +3,12 @@ from compas_rrc.common import ExecutionLevel from compas_rrc.common import FeedbackLevel -INSTRUCTION_PREFIX = 'r_RRC_' +INSTRUCTION_PREFIX = "r_RRC_" __all__ = [ - 'ReadWatch', - 'StartWatch', - 'StopWatch', + "ReadWatch", + "StartWatch", + "StopWatch", ] @@ -30,7 +30,7 @@ class ReadWatch(ROSmsg): def __init__(self): """Create a new instance of the instruction.""" - self.instruction = INSTRUCTION_PREFIX + 'ReadWatch' + self.instruction = INSTRUCTION_PREFIX + "ReadWatch" self.feedback_level = FeedbackLevel.DONE self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -45,7 +45,7 @@ def parse_feedback(self, result): Current value of the watch in seconds. """ # read input value - result = round(result['float_values'][0], 3) + result = round(result["float_values"][0], 3) return result @@ -73,7 +73,7 @@ def __init__(self, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'StartWatch' + self.instruction = INSTRUCTION_PREFIX + "StartWatch" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [] @@ -104,7 +104,7 @@ def __init__(self, feedback_level=FeedbackLevel.NONE): feedback_level : :obj:`int` Defines the feedback level requested from the robot. Defaults to :attr:`FeedbackLevel.NONE`. """ - self.instruction = INSTRUCTION_PREFIX + 'StopWatch' + self.instruction = INSTRUCTION_PREFIX + "StopWatch" self.feedback_level = feedback_level self.exec_level = ExecutionLevel.ROBOT self.string_values = [] diff --git a/tasks.py b/tasks.py index 4f5fe96f..c34ba467 100644 --- a/tasks.py +++ b/tasks.py @@ -1,234 +1,35 @@ -# -*- coding: utf-8 -*- from __future__ import print_function -import contextlib -import glob import os -import sys -from shutil import copytree -from shutil import rmtree -from invoke import Exit -from invoke import task - -BASE_FOLDER = os.path.dirname(__file__) - - -class Log(object): - def __init__(self, out=sys.stdout, err=sys.stderr): - self.out = out - self.err = err - - def flush(self): - self.out.flush() - self.err.flush() - - def write(self, message): - self.flush() - self.out.write(message + '\n') - self.out.flush() - - def info(self, message): - self.write('[INFO] %s' % message) - - def warn(self, message): - self.write('[WARN] %s' % message) - - -log = Log() - - -def confirm(question): - while True: - response = input(question).lower().strip() - - if not response or response in ('n', 'no'): - return False - - if response in ('y', 'yes'): - return True - - print('Focus, kid! It is either (y)es or (n)o', file=sys.stderr) - - -@task(default=True) -def help(ctx): - """Lists available tasks and usage.""" - ctx.run('invoke --list') - log.write('Use "invoke -h " to get detailed help for a task.') - - -@task(help={ - 'docs': 'True to generate documentation, otherwise False', - 'bytecode': 'True to clean up compiled python files, otherwise False.', - 'builds': 'True to clean up build/packaging artifacts, otherwise False.'}) -def clean(ctx, docs=True, bytecode=True, builds=True): - """Cleans the local copy from compiled artifacts.""" - if builds: - ctx.run('python setup.py clean') - - if bytecode: - for root, dirs, files in os.walk(BASE_FOLDER): - for f in files: - if f.endswith('.pyc'): - os.remove(os.path.join(root, f)) - if '.git' in dirs: - dirs.remove('.git') - - folders = [] - - if docs: - folders.append('docs/_build/') - folders.append('docs/reference/generated') - folders.append('dist/') - - if bytecode: - folders.append('src/compas_rrc/__pycache__') - folders.append('.pytest_cache') - - if builds: - folders.append('build/') - folders.append('src/compas_rrc.egg-info/') - - for folder in folders: - rmtree(os.path.join(BASE_FOLDER, folder), ignore_errors=True) - - -@task(help={ - 'rebuild': 'True to clean all previously built docs before starting, otherwise False.', - 'doctest': 'True to run doctests, otherwise False.', - 'check_links': 'True to check all web links in docs for validity, otherwise False.'}) -def docs(ctx, doctest=False, rebuild=False, check_links=False): - """Builds package's HTML documentation.""" - - if rebuild: - clean(ctx) - - with chdir(BASE_FOLDER): - if doctest: - testdocs(ctx, rebuild=rebuild) - - ctx.run('sphinx-build -b html docs dist/docs') - - if check_links: - linkcheck(ctx, rebuild=rebuild) - - -@task() -def lint(ctx): - """Check the consistency of coding style.""" - log.write('Running flake8 python linter...') - - with chdir(BASE_FOLDER): - ctx.run('flake8 src') - - -@task() -def testdocs(ctx, rebuild=False): - """Test the examples in the docstrings.""" - log.write('Running doctest...') - opts = '-E' if rebuild else '' - ctx.run('sphinx-build {} -b doctest docs dist/docs'.format(opts)) - - -@task() -def linkcheck(ctx, rebuild=False): - """Check links in documentation.""" - log.write('Running link check...') - opts = '-E' if rebuild else '' - ctx.run('sphinx-build {} -b linkcheck docs dist/docs'.format(opts)) - - -@task() -def check(ctx): - """Check the consistency of documentation, coding style and a few other things.""" - - with chdir(BASE_FOLDER): - lint(ctx) - - log.write('Checking ReStructuredText formatting...') - ctx.run('python setup.py check --strict --metadata --restructuredtext') - - log.write('Checking python imports...') - ctx.run('isort --check-only --diff src tests setup.py') - - log.write('Checking MANIFEST.in...') - ctx.run('check-manifest') - - -@task(help={ - 'checks': 'True to run all checks before testing, otherwise False.', - 'doctests': 'True to run doctests, otherwise False.'}) -def test(ctx, checks=False, doctests=False): - """Run all tests.""" - if checks: - check(ctx) - - with chdir(BASE_FOLDER): - if doctests: - ctx.run('pytest --doctest-modules') - else: - ctx.run('pytest') - - -@task -def prepare_changelog(ctx): - """Prepare changelog for next release.""" - UNRELEASED_CHANGELOG_TEMPLATE = '\nUnreleased\n----------\n\n**Added**\n\n**Changed**\n\n**Fixed**\n\n**Deprecated**\n\n**Removed**\n' - - with chdir(BASE_FOLDER): - # Preparing changelog for next release - with open('CHANGELOG.rst', 'r+') as changelog: - content = changelog.read() - start_index = content.index('----------') - start_index = content.rindex('\n', 0, start_index - 1) - last_version = content[start_index:start_index + 11].strip() - - if last_version == 'Unreleased': - log.write('Already up-to-date') - return - - changelog.seek(0) - changelog.write(content[0:start_index] + UNRELEASED_CHANGELOG_TEMPLATE + content[start_index:]) - - ctx.run('git add CHANGELOG.rst && git commit -m "Prepare changelog for next release"') - - -@task(help={ - 'release_type': 'Type of release follows semver rules. Must be one of: major, minor, patch.'}) -def release(ctx, release_type): - """Releases the project in one swift command!""" - if release_type not in ('patch', 'minor', 'major'): - raise Exit('The release type parameter is invalid.\nMust be one of: major, minor, patch') - - # Run checks - ctx.run('invoke check test') - - # Bump version and git tag it - ctx.run('bump2version %s --verbose' % release_type) - - # Build project - ctx.run('python setup.py clean --all sdist bdist_wheel') - - # Prepare changelog for next release - prepare_changelog(ctx) - - # Clean up local artifacts - clean(ctx) - - # Upload to pypi - if confirm('Everything is ready. You are about to push to git which will trigger a release to pypi.org. Are you sure? [y/N]'): - ctx.run('git push --tags && git push') - else: - raise Exit('You need to manually revert the tag/commits created.') - - -@contextlib.contextmanager -def chdir(dirname=None): - current_dir = os.getcwd() - try: - if dirname is not None: - os.chdir(dirname) - yield - finally: - os.chdir(current_dir) +from compas_invocations import build +from compas_invocations import docs +from compas_invocations import style +from compas_invocations import tests +from invoke import Collection + +ns = Collection( + docs.help, + style.check, + style.lint, + style.format, + docs.docs, + docs.linkcheck, + tests.test, + tests.testdocs, + tests.testcodeblocks, + build.prepare_changelog, + build.clean, + build.release, + build.build_ghuser_components, +) +ns.configure( + { + "base_folder": os.path.dirname(__file__), + "ghuser": { + "source_dir": "src/compas_rrc/ghpython/components", + "target_dir": "src/compas_rrc/ghpython/components/ghuser", + "prefix": "COMPAS RRC: ", + }, + } +) diff --git a/tests/ipy_test_runner.py b/tests/ipy_test_runner.py index c0fe63e5..21aae1ff 100644 --- a/tests/ipy_test_runner.py +++ b/tests/ipy_test_runner.py @@ -6,9 +6,9 @@ HERE = os.path.dirname(__file__) -if __name__ == '__main__': +if __name__ == "__main__": # Fake Rhino modules - pytest.load_fake_module('Rhino') - pytest.load_fake_module('Rhino.Geometry', fake_types=['RTree', 'Sphere', 'Point3d']) + pytest.load_fake_module("Rhino") + pytest.load_fake_module("Rhino.Geometry", fake_types=["RTree", "Sphere", "Point3d"]) pytest.run(HERE) diff --git a/tests/test_client.py b/tests/test_client.py index 3c48e87a..84fbd34c 100644 --- a/tests/test_client.py +++ b/tests/test_client.py @@ -39,7 +39,7 @@ def incrementer(c): threads = [] for _ in range(nr_of_threads): - t = threading.Thread(target=incrementer, args=(counter, )) + t = threading.Thread(target=incrementer, args=(counter,)) t.start() threads.append(t) diff --git a/tests/test_common.py b/tests/test_common.py index 258d1ef9..22d5a70c 100644 --- a/tests/test_common.py +++ b/tests/test_common.py @@ -1,7 +1,7 @@ import math from compas.geometry import allclose -from compas.robots import Configuration +from compas_robots import Configuration import compas_rrc as rrc @@ -42,24 +42,30 @@ def test_robot_joints(): assert list(j) == [30, 10, 0] j = rrc.RobotJoints(30, 45, 0) - c = j.to_configuration_primitive([0, 1, 2], ['j1', 'j2', 'j3']) - assert c.joint_values == [math.pi/6, math.pi/4, 0.0] - assert c.joint_names == ['j1', 'j2', 'j3'] + c = j.to_configuration_primitive([0, 1, 2], ["j1", "j2", "j3"]) + assert c.joint_values == [math.pi / 6, math.pi / 4, 0.0] + assert c.joint_names == ["j1", "j2", "j3"] j = rrc.RobotJoints(30, -45, 100) c = j.to_configuration_primitive([0, 1, 2]) - assert c.joint_values == [math.pi/6, -math.pi/4, 0.1] + assert c.joint_values == [math.pi / 6, -math.pi / 4, 0.1] assert len(c.joint_names) == 0 - config = Configuration([2*math.pi, math.pi, math.pi/2, math.pi/3, math.pi/4, math.pi/6], [0, 0, 0, 0, 0, 0]) + config = Configuration( + [2 * math.pi, math.pi, math.pi / 2, math.pi / 3, math.pi / 4, math.pi / 6], + [0, 0, 0, 0, 0, 0], + ) rj = rrc.RobotJoints.from_configuration_primitive(config) assert allclose(rj.values, [360, 180, 90, 60, 45, 30]) config = Configuration( - [0, 2*math.pi, math.pi, math.pi/2, math.pi/3, math.pi/4, math.pi/6 ], + [0, 2 * math.pi, math.pi, math.pi / 2, math.pi / 3, math.pi / 4, math.pi / 6], [0, 0, 0, 0, 0, 0, 0], - ['a', 'b', 'c', 'd', 'e', 'f', 'g']) - rj = rrc.RobotJoints.from_configuration_primitive(config, ['b', 'c', 'd', 'e', 'f', 'g']) + ["a", "b", "c", "d", "e", "f", "g"], + ) + rj = rrc.RobotJoints.from_configuration_primitive( + config, ["b", "c", "d", "e", "f", "g"] + ) assert allclose(rj.values, [360, 180, 90, 60, 45, 30]) j = rrc.RobotJoints(30, 10, 0) @@ -85,24 +91,30 @@ def test_external_axes(): assert list(ea) == [30, 10, 0] j = rrc.ExternalAxes(30, 45, 0) - c = j.to_configuration_primitive([0, 1, 2], ['j1', 'j2', 'j3']) - assert c.joint_values == [math.pi/6, math.pi/4, 0.0] - assert c.joint_names == ['j1', 'j2', 'j3'] + c = j.to_configuration_primitive([0, 1, 2], ["j1", "j2", "j3"]) + assert c.joint_values == [math.pi / 6, math.pi / 4, 0.0] + assert c.joint_names == ["j1", "j2", "j3"] j = rrc.ExternalAxes(30, -45, 100) c = j.to_configuration_primitive([0, 1, 2]) - assert c.joint_values == [math.pi/6, -math.pi/4, 0.1] + assert c.joint_values == [math.pi / 6, -math.pi / 4, 0.1] assert len(c.joint_names) == 0 - config = Configuration([2*math.pi, math.pi, math.pi/2, math.pi/3, math.pi/4, math.pi/6], [0, 0, 0, 0, 0, 0]) + config = Configuration( + [2 * math.pi, math.pi, math.pi / 2, math.pi / 3, math.pi / 4, math.pi / 6], + [0, 0, 0, 0, 0, 0], + ) rj = rrc.ExternalAxes.from_configuration_primitive(config) assert allclose(rj.values, [360, 180, 90, 60, 45, 30]) config = Configuration( - [0, 2*math.pi, math.pi, math.pi/2, math.pi/3, math.pi/4, math.pi/6 ], + [0, 2 * math.pi, math.pi, math.pi / 2, math.pi / 3, math.pi / 4, math.pi / 6], [0, 0, 0, 0, 0, 0, 0], - ['a', 'b', 'c', 'd', 'e', 'f', 'g']) - rj = rrc.ExternalAxes.from_configuration_primitive(config, ['b', 'c', 'd', 'e', 'f', 'g']) + ["a", "b", "c", "d", "e", "f", "g"], + ) + rj = rrc.ExternalAxes.from_configuration_primitive( + config, ["b", "c", "d", "e", "f", "g"] + ) assert allclose(rj.values, [360, 180, 90, 60, 45, 30]) j = rrc.RobotJoints(30, 10, 0) diff --git a/tests/test_motion.py b/tests/test_motion.py index 36d56171..bb4f41fc 100644 --- a/tests/test_motion.py +++ b/tests/test_motion.py @@ -34,21 +34,61 @@ def test_move_to_joints_validation(): def test_move_to_frame(): inst = rrc.MoveToFrame(Frame.worldXY(), 100, rrc.Zone.FINE, rrc.Motion.JOINT) - assert inst.float_values == [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0, 0, 100, -1] - assert inst.string_values == ['FrameJ'] + assert inst.float_values == [ + 0.0, + 0.0, + 0.0, + 1.0, + 0.0, + 0.0, + 0.0, + 0, + 0, + 0, + 0, + 0, + 0, + 100, + -1, + ] + assert inst.string_values == ["FrameJ"] inst = rrc.MoveToFrame(Frame.worldXY(), 100, rrc.Zone.FINE, rrc.Motion.LINEAR) - assert inst.string_values == ['FrameL'] + assert inst.string_values == ["FrameL"] def test_move_to_robtarget(): - inst = rrc.MoveToRobtarget(Frame.worldXY(), [50, 20], 100, rrc.Zone.FINE, rrc.Motion.JOINT) - - assert inst.float_values == [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 50, 20, 0, 0, 0, 0, 100, -1] - assert inst.string_values == ['J'] + inst = rrc.MoveToRobtarget( + Frame.worldXY(), [50, 20], 100, rrc.Zone.FINE, rrc.Motion.JOINT + ) + + assert inst.float_values == [ + 0.0, + 0.0, + 0.0, + 1.0, + 0.0, + 0.0, + 0.0, + 50, + 20, + 0, + 0, + 0, + 0, + 100, + -1, + ] + assert inst.string_values == ["J"] def test_move_to_robtarget_validation(): # Only up to 6 external axes are supported with pytest.raises(ValueError): - rrc.MoveToRobtarget(Frame.worldXY(), [50, 20, 0, 0, 0, 0, 0, 0], 100, rrc.Zone.FINE, rrc.Motion.JOINT) + rrc.MoveToRobtarget( + Frame.worldXY(), + [50, 20, 0, 0, 0, 0, 0, 0], + 100, + rrc.Zone.FINE, + rrc.Motion.JOINT, + )