diff --git a/.github/workflows/documentation.yml b/.github/workflows/documentation.yml index 3e979f99..fa9c114f 100644 --- a/.github/workflows/documentation.yml +++ b/.github/workflows/documentation.yml @@ -25,14 +25,14 @@ jobs: - name: Build HTML docs run: | - cd docs/reStructuredText + cd docs make html - name: Upload docs uses: ./.github/actions/upload-release with: release_type: docs - src_dir: docs/reStructuredText/_build/html + src_dir: docs/_build/html do_access_key: ${{ secrets.DIGITALOCEAN_ACCESS_KEY }} do_secret_key: ${{ secrets.DIGITALOCEAN_SECRET_KEY }} odrive_api_key: ${{ secrets.ODRIVE_API_KEY }} diff --git a/Firmware/odrive-interface.yaml b/Firmware/odrive-interface.yaml index bf508b66..6b6163ca 100644 --- a/Firmware/odrive-interface.yaml +++ b/Firmware/odrive-interface.yaml @@ -259,23 +259,38 @@ interfaces: Here's an (incomplete) list of baudrates for ODrive v3.x: - Configured | Actual | Error [%] - -------------|---------------|----------- - 1.2 KBps | 1.2 KBps | 0 - 2.4 KBps | 2.4 KBps | 0 - 9.6 KBps | 9.6 KBps | 0 - 19.2 KBps | 19.195 KBps | 0.02 - 38.4 KBps | 38.391 KBps | 0.02 - 57.6 KBps | 57.613 KBps | 0.02 - 115.2 KBps | 115.068 KBps | 0.11 - 230.4 KBps | 230.769 KBps | 0.16 - 460.8 KBps | 461.538 KBps | 0.16 - 921.6 KBps | 913.043 KBps | 0.93 - 1.792 MBps | 1.826 MBps | 1.9 - 1.8432 MBps | 1.826 MBps | 0.93 + +-------------+---------------+-----------+ + | Configured | Actual | Error [%] | + +=============+===============+===========+ + | 1.2 KBps | 1.2 KBps | 0 | + +-------------+---------------+-----------+ + | 2.4 KBps | 2.4 KBps | 0 | + +-------------+---------------+-----------+ + | 9.6 KBps | 9.6 KBps | 0 | + +-------------+---------------+-----------+ + | 19.2 KBps | 19.195 KBps | 0.02 | + +-------------+---------------+-----------+ + | 38.4 KBps | 38.391 KBps | 0.02 | + +-------------+---------------+-----------+ + | 57.6 KBps | 57.613 KBps | 0.02 | + +-------------+---------------+-----------+ + | 115.2 KBps | 115.068 KBps | 0.11 | + +-------------+---------------+-----------+ + | 230.4 KBps | 230.769 KBps | 0.16 | + +-------------+---------------+-----------+ + | 460.8 KBps | 461.538 KBps | 0.16 | + +-------------+---------------+-----------+ + | 921.6 KBps | 913.043 KBps | 0.93 | + +-------------+---------------+-----------+ + | 1.792 MBps | 1.826 MBps | 1.9 | + +-------------+---------------+-----------+ + | 1.8432 MBps | 1.826 MBps | 0.93 | + +-------------+---------------+-----------+ + For more information refer to Section 30.3.4 and Table 142 (the column with f_PCLK = 42 MHz) in the - [STM datasheet](https://www.st.com/content/ccc/resource/technical/document/reference_manual/3d/6d/5a/66/b4/99/40/d4/DM00031020.pdf/files/DM00031020.pdf/jcr:content/translations/en.DM00031020.pdf). + `STM datasheet `__. + uart_b_baudrate: type: uint32 unit: baud/s diff --git a/docs/CNAME b/docs/CNAME deleted file mode 100644 index 52b4b501..00000000 --- a/docs/CNAME +++ /dev/null @@ -1 +0,0 @@ -docs.odriverobotics.com \ No newline at end of file diff --git a/docs/Gemfile b/docs/Gemfile deleted file mode 100644 index bcd3be7d..00000000 --- a/docs/Gemfile +++ /dev/null @@ -1,3 +0,0 @@ -source 'https://rubygems.org' -gem 'github-pages', group: :jekyll_plugins -gem 'jekyll-redirect-from' diff --git a/docs/Gemfile.lock b/docs/Gemfile.lock deleted file mode 100644 index 1eed173c..00000000 --- a/docs/Gemfile.lock +++ /dev/null @@ -1,283 +0,0 @@ -GEM - remote: https://rubygems.org/ - specs: - activesupport (6.0.3.7) - concurrent-ruby (~> 1.0, >= 1.0.2) - i18n (>= 0.7, < 2) - minitest (~> 5.1) - tzinfo (~> 1.1) - zeitwerk (~> 2.2, >= 2.2.2) - addressable (2.8.0) - public_suffix (>= 2.0.2, < 5.0) - coffee-script (2.4.1) - coffee-script-source - execjs - coffee-script-source (1.11.1) - colorator (1.1.0) - commonmarker (0.17.13) - ruby-enum (~> 0.5) - concurrent-ruby (1.1.8) - dnsruby (1.61.5) - simpleidn (~> 0.1) - em-websocket (0.5.2) - eventmachine (>= 0.12.9) - http_parser.rb (~> 0.6.0) - ethon (0.14.0) - ffi (>= 1.15.0) - eventmachine (1.2.7) - execjs (2.8.1) - faraday (1.4.2) - faraday-em_http (~> 1.0) - faraday-em_synchrony (~> 1.0) - faraday-excon (~> 1.1) - faraday-net_http (~> 1.0) - faraday-net_http_persistent (~> 1.1) - multipart-post (>= 1.2, < 3) - ruby2_keywords (>= 0.0.4) - faraday-em_http (1.0.0) - faraday-em_synchrony (1.0.0) - faraday-excon (1.1.0) - faraday-net_http (1.0.1) - faraday-net_http_persistent (1.1.0) - ffi (1.15.1) - forwardable-extended (2.6.0) - gemoji (3.0.1) - github-pages (215) - github-pages-health-check (= 1.17.2) - jekyll (= 3.9.0) - jekyll-avatar (= 0.7.0) - jekyll-coffeescript (= 1.1.1) - jekyll-commonmark-ghpages (= 0.1.6) - jekyll-default-layout (= 0.1.4) - jekyll-feed (= 0.15.1) - jekyll-gist (= 1.5.0) - jekyll-github-metadata (= 2.13.0) - jekyll-mentions (= 1.6.0) - jekyll-optional-front-matter (= 0.3.2) - jekyll-paginate (= 1.1.0) - jekyll-readme-index (= 0.3.0) - jekyll-redirect-from (= 0.16.0) - jekyll-relative-links (= 0.6.1) - jekyll-remote-theme (= 0.4.3) - jekyll-sass-converter (= 1.5.2) - jekyll-seo-tag (= 2.7.1) - jekyll-sitemap (= 1.4.0) - jekyll-swiss (= 1.0.0) - jekyll-theme-architect (= 0.1.1) - jekyll-theme-cayman (= 0.1.1) - jekyll-theme-dinky (= 0.1.1) - jekyll-theme-hacker (= 0.1.2) - jekyll-theme-leap-day (= 0.1.1) - jekyll-theme-merlot (= 0.1.1) - jekyll-theme-midnight (= 0.1.1) - jekyll-theme-minimal (= 0.1.1) - jekyll-theme-modernist (= 0.1.1) - jekyll-theme-primer (= 0.5.4) - jekyll-theme-slate (= 0.1.1) - jekyll-theme-tactile (= 0.1.1) - jekyll-theme-time-machine (= 0.1.1) - jekyll-titles-from-headings (= 0.5.3) - jemoji (= 0.12.0) - kramdown (= 2.3.1) - kramdown-parser-gfm (= 1.1.0) - liquid (= 4.0.3) - mercenary (~> 0.3) - minima (= 2.5.1) - nokogiri (>= 1.10.4, < 2.0) - rouge (= 3.26.0) - terminal-table (~> 1.4) - github-pages-health-check (1.17.2) - addressable (~> 2.3) - dnsruby (~> 1.60) - octokit (~> 4.0) - public_suffix (>= 2.0.2, < 5.0) - typhoeus (~> 1.3) - html-pipeline (2.14.0) - activesupport (>= 2) - nokogiri (>= 1.4) - http_parser.rb (0.6.0) - i18n (0.9.5) - concurrent-ruby (~> 1.0) - jekyll (3.9.0) - addressable (~> 2.4) - colorator (~> 1.0) - em-websocket (~> 0.5) - i18n (~> 0.7) - jekyll-sass-converter (~> 1.0) - jekyll-watch (~> 2.0) - kramdown (>= 1.17, < 3) - liquid (~> 4.0) - mercenary (~> 0.3.3) - pathutil (~> 0.9) - rouge (>= 1.7, < 4) - safe_yaml (~> 1.0) - jekyll-avatar (0.7.0) - jekyll (>= 3.0, < 5.0) - jekyll-coffeescript (1.1.1) - coffee-script (~> 2.2) - coffee-script-source (~> 1.11.1) - jekyll-commonmark (1.3.1) - commonmarker (~> 0.14) - jekyll (>= 3.7, < 5.0) - jekyll-commonmark-ghpages (0.1.6) - commonmarker (~> 0.17.6) - jekyll-commonmark (~> 1.2) - rouge (>= 2.0, < 4.0) - jekyll-default-layout (0.1.4) - jekyll (~> 3.0) - jekyll-feed (0.15.1) - jekyll (>= 3.7, < 5.0) - jekyll-gist (1.5.0) - octokit (~> 4.2) - jekyll-github-metadata (2.13.0) - jekyll (>= 3.4, < 5.0) - octokit (~> 4.0, != 4.4.0) - jekyll-mentions (1.6.0) - html-pipeline (~> 2.3) - jekyll (>= 3.7, < 5.0) - jekyll-optional-front-matter (0.3.2) - jekyll (>= 3.0, < 5.0) - jekyll-paginate (1.1.0) - jekyll-readme-index (0.3.0) - jekyll (>= 3.0, < 5.0) - jekyll-redirect-from (0.16.0) - jekyll (>= 3.3, < 5.0) - jekyll-relative-links (0.6.1) - jekyll (>= 3.3, < 5.0) - jekyll-remote-theme (0.4.3) - addressable (~> 2.0) - jekyll (>= 3.5, < 5.0) - jekyll-sass-converter (>= 1.0, <= 3.0.0, != 2.0.0) - rubyzip (>= 1.3.0, < 3.0) - jekyll-sass-converter (1.5.2) - sass (~> 3.4) - jekyll-seo-tag (2.7.1) - jekyll (>= 3.8, < 5.0) - jekyll-sitemap (1.4.0) - jekyll (>= 3.7, < 5.0) - jekyll-swiss (1.0.0) - jekyll-theme-architect (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-cayman (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-dinky (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-hacker (0.1.2) - jekyll (> 3.5, < 5.0) - jekyll-seo-tag (~> 2.0) - jekyll-theme-leap-day (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-merlot (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-midnight (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-minimal (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-modernist (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-primer (0.5.4) - jekyll (> 3.5, < 5.0) - jekyll-github-metadata (~> 2.9) - jekyll-seo-tag (~> 2.0) - jekyll-theme-slate (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-tactile (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-theme-time-machine (0.1.1) - jekyll (~> 3.5) - jekyll-seo-tag (~> 2.0) - jekyll-titles-from-headings (0.5.3) - jekyll (>= 3.3, < 5.0) - jekyll-watch (2.2.1) - listen (~> 3.0) - jemoji (0.12.0) - gemoji (~> 3.0) - html-pipeline (~> 2.2) - jekyll (>= 3.0, < 5.0) - kramdown (2.3.1) - rexml - kramdown-parser-gfm (1.1.0) - kramdown (~> 2.0) - liquid (4.0.3) - listen (3.5.1) - rb-fsevent (~> 0.10, >= 0.10.3) - rb-inotify (~> 0.9, >= 0.9.10) - mercenary (0.3.6) - mini_portile2 (2.5.2) - net-ftp (~> 0.1) - minima (2.5.1) - jekyll (>= 3.5, < 5.0) - jekyll-feed (~> 0.9) - jekyll-seo-tag (~> 2.1) - minitest (5.14.4) - multipart-post (2.1.1) - net-ftp (0.1.2) - net-protocol - time - net-protocol (0.1.0) - nokogiri (1.11.6) - mini_portile2 (~> 2.5.0) - racc (~> 1.4) - nokogiri (1.11.6-x86_64-linux) - racc (~> 1.4) - octokit (4.21.0) - faraday (>= 0.9) - sawyer (~> 0.8.0, >= 0.5.3) - pathutil (0.16.2) - forwardable-extended (~> 2.6) - public_suffix (4.0.6) - racc (1.5.2) - rb-fsevent (0.11.0) - rb-inotify (0.10.1) - ffi (~> 1.0) - rexml (3.2.5) - rouge (3.26.0) - ruby-enum (0.9.0) - i18n - ruby2_keywords (0.0.4) - rubyzip (2.3.0) - safe_yaml (1.0.5) - sass (3.7.4) - sass-listen (~> 4.0.0) - sass-listen (4.0.0) - rb-fsevent (~> 0.9, >= 0.9.4) - rb-inotify (~> 0.9, >= 0.9.7) - sawyer (0.8.2) - addressable (>= 2.3.5) - faraday (> 0.8, < 2.0) - simpleidn (0.2.1) - unf (~> 0.1.4) - terminal-table (1.8.0) - unicode-display_width (~> 1.1, >= 1.1.1) - thread_safe (0.3.6) - time (0.1.0) - typhoeus (1.4.0) - ethon (>= 0.9.0) - tzinfo (1.2.9) - thread_safe (~> 0.1) - unf (0.1.4) - unf_ext - unf_ext (0.0.7.7) - unicode-display_width (1.7.0) - zeitwerk (2.4.2) - -PLATFORMS - aarch64-linux - x86_64-linux - -DEPENDENCIES - github-pages - jekyll-redirect-from - -BUNDLED WITH - 2.2.18 diff --git a/docs/reStructuredText/Makefile b/docs/Makefile similarity index 100% rename from docs/reStructuredText/Makefile rename to docs/Makefile diff --git a/docs/_config.yaml b/docs/_config.yaml deleted file mode 100644 index 54752e15..00000000 --- a/docs/_config.yaml +++ /dev/null @@ -1,8 +0,0 @@ -theme: jekyll-theme-minimal -exclude: [ruby-bundle, vendor] -plugins: - - jekyll-redirect-from -google_analytics: UA-93396600-3 -collections: - api: - output: true diff --git a/docs/_data/index.yaml b/docs/_data/index.yaml deleted file mode 100644 index 7ef2d0af..00000000 --- a/docs/_data/index.yaml +++ /dev/null @@ -1,72 +0,0 @@ - -# This data could theoretically be retrieved directly from the md files: -# https://jekyllrb.com/tutorials/navigation/#scenario-8-retrieving-items-based-on-front-matter-properties - -sections: - - title: General - docs: - - title: Getting Started - url: / - - title: ODrive Tool - url: /odrivetool - - title: Control Modes - url: /control-modes - - title: Parameters & Commands - url: /commands - - title: Encoders - url: /encoders - - title: Control Structure & Tuning - url: /control - - title: Troubleshooting - url: /troubleshooting - - title: Specifications - url: /specifications - - title: Ground Loops - url: /ground-loops - - title: Tutorials - docs: - - title: Hoverboard Guide - url: /hoverboard - - title: Migration Guide - url: /migration - - title: CAN Guide - url: /can-guide - - title: Interfaces & Protocols - docs: - - title: Pinout - url: /pinout - - title: USB - url: /usb - - title: UART - url: /uart - - title: Native Protocol - url: /native-protocol - - title: ASCII Protocol - url: /ascii-protocol - - title: CAN Protocol - url: /can-protocol - - title: Step & Direction - url: /step-direction - - title: RC PWM - url: /rc-pwm - - title: Analog Input - url: /analog-input - - title: Homing & Endstops - url: /endstops - - title: Thermistors - url: /thermistors - - title: API Reference - - title: For ODrive Developers - docs: - - title: Firmware Developer Guide - url: /developer-guide - - title: Configuring Visual Studio Code - url: /configuring-vscode - - title: Configuring Eclipse - url: /configuring-eclipse - - title: Component Guides - docs: - - title: Motor Guide - url: https://docs.google.com/spreadsheets/d/12vzz7XVEK6YNIOqH0jAz51F5VUpc-lJEs3mmkWP1H4Y - - title: Encoder Guide - url: https://docs.google.com/spreadsheets/d/1OBDwYrBb5zUPZLrhL98ezZbg94tUsZcdTuwiVNgVqpU diff --git a/docs/_layouts/api_documentation_template.j2 b/docs/_layouts/api_documentation_template.j2 deleted file mode 100644 index d4a7a423..00000000 --- a/docs/_layouts/api_documentation_template.j2 +++ /dev/null @@ -1,156 +0,0 @@ ---- -title: '[% if interface %][[interface.fullname]][% else %][[enum.fullname]][% endif %]' -layout: default -edit_url: 'Firmware/odrive-interface.yaml' -download: - url: 'Firmware/odrive-interface.yaml' - text: 'download as YAML' ---- - -[% set attr_lookup_table = -{ - 'ODrive': '', - 'ODrive.Axis': '.', - 'ODrive.Motor': '..motor', -} -%] - -[%- macro interface_ref(type) -%] -**[['[']][[type.name]][[']']]([[type.fullname | lower]])** -[%- endmacro %] - -[%- macro value_type_ref(type) -%] -[%- if type.builtin -%] -[[type.name]] -[%- else -%] -[['[']][[type.name]][[']']]([[type.fullname | lower]]) -[%- endif %] -[%- endmacro %] - -[% macro attr_ref(token, scope, intf, attr) -%] -**[['[']][% if intf != scope %][[attr_lookup_table[intf.fullname] | html_escape]].[% endif %][[token]][[']']]([[attr.parent.fullname | lower]]#[[attr.name]])** -[%- endmacro %] - -[% if interface %] -[% set scope = interface %] -[% else %] -[% set scope = enum.parent %] -[% endif %] - -[%- macro doc_tokenize(text) %][[ text | tokenize(scope, interface_ref, value_type_ref, attr_ref) ]][% endmacro %] - -[%- macro status_badge(status) %] -[%- if status == 'experimental' %] -Experimental -[%- endif %] -[%- if status == 'deprecated' %] -Deprecated -[%- endif %] -[%- endmacro %] - -[%- macro breadcrumbs(title) %] -# [% for item in title.split('.') | diagonalize -%] -[[item[-1]]] -[%- if not loop.last %] 〉[% endif %] -[%- endfor %] -[%- endmacro %] - -[% if interface %] - -[[breadcrumbs(interface.fullname)]] - -[%- if interface.doc or interface.brief %] -[[doc_tokenize(interface.brief)]][% if interface.brief and interface.doc %] - -[% endif %][[doc_tokenize(interface.doc)]] -[%- endif %] - -## Attributes - -[% if interface.attributes %] -[% for attr in interface.attributes.values() %] -[%- if attr.type.purename == 'fibre.Property' %] -**[[attr.name]]**  —  [[value_type_ref(attr.type.value_type)]]    _[[attr.type.mode]]_ -[%- else %] -**[[attr.name]]**  —  [[interface_ref(attr.type)]] -[%- endif %] -[[-status_badge(attr.status)]] - -
    -[% if attr.doc or attr.brief %] -[[doc_tokenize(attr.brief)]][% if attr.brief and attr.doc %] - -[% endif %][%- if attr.unit %] - -**Unit:** [[attr.unit]] - -[% endif %][[doc_tokenize(attr.doc)]] -[%- else %] -_No description_ -[%- endif %] -
-[% endfor %] -[% else %] -This interface has no attributes. -[% endif %] - -## Functions - -[% if interface.functions %] -[% for function in interface.functions.values() %] -**[[function.name]]**([% for arg in function.in.values() | skip_first %][[arg.name]]: [[value_type_ref(arg.type)]][[', ' if not loop.last]][% endfor %])[% if function.out %]  ➔  [% for arg in function.out.values() %][[arg.name]]: [[value_type_ref(arg.type)]][[', ' if not loop.last]][% endfor %][% endif %] - -
    -[% if function.doc or function.brief %] -[[doc_tokenize(function.brief)]][% if function.brief and function.doc %] - -[% endif %][[doc_tokenize(function.doc)]] -[%- else %] -_No description_ -[%- endif %] -[% if function.in.values() | skip_first %] -**Inputs:** -[%- for arg in function.in.values() | skip_first %] - - `[[arg.name]]`: [% if arg.doc %][[doc_tokenize(arg.doc)]][% else %] _No description_[% endif %] -[%- endfor %] -[%- endif %] -[% if function.out.values() %] -**Outputs:** -[%- for arg in function.out.values() %] - - `[[arg.name]]`: [% if arg.doc %][[doc_tokenize(arg.doc)]][% else %] _No description_[% endif %] -[%- endfor %] -[%- endif %] -
-[% endfor %] -[% else %] -This interface has no functions. -[% endif %] - -[% else %] - -[[breadcrumbs(enum.fullname)]] - -[%- if enum.doc or enum.brief %] -[[doc_tokenize(enum.brief)]][% if enum.brief and enum.doc %] - -[% endif %][[doc_tokenize(enum.doc)]] -[%- endif %] - -## [% if enum.is_flags %]Flags[% else %]Values[% endif %] - -[% for k, value in enum['values'].items() %] -**[[enum.name | to_macro_case]]_[[value.name]]**  —  [% if enum.is_flags %]0x[['%08x' | format(value.value)]][% else %][[value.value]][% endif %] -[[-status_badge(value.status)]] - -
    -[% if value.doc or value.brief %] -[[doc_tokenize(value.brief)]][% if value.brief and value.doc %] - -[% endif %][[doc_tokenize(value.doc)]] -[%- else %] -_No description_ -[%- endif %] -
-[% endfor %] - -[% endif %] diff --git a/docs/_layouts/api_index_template.j2 b/docs/_layouts/api_index_template.j2 deleted file mode 100644 index 087fbced..00000000 --- a/docs/_layouts/api_index_template.j2 +++ /dev/null @@ -1,41 +0,0 @@ -[%- macro dump_interfaces(interfaces, level) %] -[%- for intf in interfaces %] -[%- if intf.interfaces or intf.value_types %] -
  • -{% assign myvar = (page.title + '.') | split: "[[intf.fullname + '.']]" %} - - -
      -[[dump_interfaces(intf.interfaces, level + 1) | indent(4)]] -[[dump_value_types(intf.enums, level + 1) | indent(4)]] -
    -
  • -[%- else %] -
  • - -
  • -[%- endif %] -[%- endfor %] -[%- endmacro %] - -[%- macro dump_value_types(value_types, level) %] -[%- for enum in value_types %] -
  • - -
  • -[%- endfor %] -[%- endmacro %] - -[[dump_interfaces(toplevel_interfaces, 0)]] diff --git a/docs/_layouts/default.html b/docs/_layouts/default.html deleted file mode 100644 index 33a6f6a2..00000000 --- a/docs/_layouts/default.html +++ /dev/null @@ -1,142 +0,0 @@ -{% assign pagename = page.url | replace_first: '/', '' | replace: '.html', '' %} -{% if pagename == '' %}{% assign pagename = 'getting-started' %}{% endif %} - - - - - - - - - -{% seo %} - - - - -
    -
    -
    -

    {{ site.title | default: site.github.repository_name }} Documentation

    - - {% if site.logo %} - Logo - {% endif %} - -

    {{ site.description | default: site.github.project_tagline }}

    -
    -
    - -
    -
    - {% if site.github.is_project_page %} -

    View the Project on GitHub {{ site.github.repository_nwo }}

    - {% endif %} - - {% if site.github.is_user_page %} -

    View My GitHub Profile

    - {% endif %} - -

    Help improve these docs: submit edits using the link in the top right.

    -

    If you need help, please search or ask the ODrive Community.

    - - {% if site.show_downloads %} - - {% endif %} -
    -
    -
    - -
    -
    - - - {% if page.edit_url %} - {% assign edit_url = "https://www.github.com/madcowswe/ODrive/edit/master/" | append: page.edit_url %} - {% else %} - {% assign edit_url = "https://www.github.com/madcowswe/ODrive/edit/master/docs/" | append: pagename | append: ".md" %} - {% endif %} - edit on GitHub -
    - - {% if page.download %} - - {% endif %} -
    - - - {{ content }} - -
    - -
    - - {% if site.google_analytics %} - - {% endif %} - - - - - diff --git a/docs/analog-input.md b/docs/analog-input.md deleted file mode 100644 index 2b0186d6..00000000 --- a/docs/analog-input.md +++ /dev/null @@ -1,5 +0,0 @@ -# Analog Input - -Analog inputs can be used to measure voltages between 0 and 3.3V. ODrive uses a 12 bit ADC (4096 steps) and so has a maximum resolution of 0.8 mV. A GPIO must be configured with `.config.gpioX_mode = GPIO_MODE_ANALOG_IN` before it can be used as an analog input. To read the voltage on GPIO1 in odrivetool the following would be entered: `odrv0.get_adc_voltage(1)`. - -Similar to RC PWM input, analog inputs can also be used to feed any of the numerical properties that are visible in `odrivetool`. This is done by configuring `odrv0.config.gpio3_analog_mapping` and `odrv0.config.gpio4_analog_mapping`. Refer to [RC PWM](rc-pwm) for instructions on how to configure the mappings. diff --git a/docs/reStructuredText/analog-input.rst b/docs/analog-input.rst similarity index 100% rename from docs/reStructuredText/analog-input.rst rename to docs/analog-input.rst diff --git a/docs/anticogging.md b/docs/anticogging.md deleted file mode 100644 index c3148266..00000000 --- a/docs/anticogging.md +++ /dev/null @@ -1,53 +0,0 @@ -# Anti-cogging - -ODrive supports an anti-cogging algorithm that attempts to compensate for the rather high cogging torques seen in hobby motors. - -`..controller.config.anticogging` is a configuration structure that contains the following items: - -Name | Type | Use --- | -- | -- -index | uint32 | The current position being used for calibration -pre_calibrated | bool | If true and using index or absolute encoder, load anticogging map from NVM at startup -calib_anticogging | bool | True when calibration is ongoing -calib_pos_threshold | float32 | (pos_estimate - index) must be < this value to calibrate. Larger values speed up calibration but hurt accuracy -calib_vel_threshold | float32 | (vel_estimate) must be < this value to calibrate. Larger values speed up calibration but hurt accuracy. -cogging_ratio | float32 | Deprecated -anticogging_enabled | bool | Enable or disable anticogging. A valid anticogging map can be ignored by setting this to `false` - -## Calibration - -To calibrate anticogging, first make sure you can adequately control the motor. It should respond to position commands. - -Start by putting the axis in `AXIS_STATE_CLOSED_LOOP_CONTROL` with `CONTROL_MODE_POSITION_CONTROL` and `INPUT_MODE_PASSTHROUGH`. Make sure you have good control of the motor in this state (it responds to position commands). Now, tune the motor to be very stiff - high `pos_gain` and relatively high `vel_integrator_gain`. This will help in calibration. - -Run `controller.start_anticogging_calibration()`. The motor will start turning slowly, calibrating each point. If you like, you can start a liveplotter session before running this command so that you can watch the position move. - -Once it's complete (it should take about 1 minute), the motor will return to 0 and the value `controller.anticogging_valid` should report True. If `controller.config.anticogging.anticogging_enabled` == True, anticogging will now be running on this axis. - -## Saving to NVM - -As of v0.5.1, the anticogging map is saved to NVM after calibrating and calling `odrv0.save_configuration()` - -The anticogging map can be reloaded automatically at startup by setting `controller.config.anticogging.pre_calibrated = True` and saving the configuration. However, this map is only valid and will only be loaded for absolute encoders, or encoders with index pins after the index search. - -## Example - -``` Py -odrv0.axis0.encoder.config.use_index = True -odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE -odrv0.axis0.encoder.config.pre_calibrated = True -odrv0.axis0.motor.config.pre_calibrated = True - -odrv0.axis0.controller.config.control_mode = CONTROL_MODE_POSITION_CONTROL -odrv0.axis0.controller.config.input_mode = INPUT_MODE_PASSTHROUGH -odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL - -odrv0.axis0.controller.start_anticogging_calibration() - -# Wait until controller.config.anticogging.calib_anticogging == False - -odrv0.axis0.controller.config.anticogging.pre_calibrated = True - -odrv0.save_configuration() -odrv0.reboot() -``` diff --git a/docs/ascii-protocol.md b/docs/ascii-protocol.md deleted file mode 100644 index 0b483f73..00000000 --- a/docs/ascii-protocol.md +++ /dev/null @@ -1,145 +0,0 @@ - -# ASCII Protocol - -## How to send commands - - * **Via USB:** - * **Windows:** Use [PuTTY](https://www.chiark.greenend.org.uk/~sgtatham/putty/) to manually send commands or open the COM port using your favorite programming language - * **Linux/macOS:** Run `/dev/tty*` to list all serial ports. The ODrive will show up as `/dev/ttyACM0` (or similar) on Linux and `/dev/tty.usbmodem[...]` on macOS. Once you know the name, you can use `screen /dev/ttyACM0` (with the correct name) to send commands manually or open the device using your favorite programming language. Serial ports on Unix can be opened, written to and read from like a normal file. - * **Via UART:** Connect the ODrive's TX (GPIO1) to your host's RX. Connect your ODrive's RX (GPIO2) to your host's TX. See [UART](uart) for more info. - * **Arduino:** You can use the [ODrive Arduino library](https://github.com/madcowswe/ODrive/tree/master/Arduino/ODriveArduino) to talk to the ODrive. - * **Windows/Linux/macOS:** You can use an FTDI USB-UART cable to connect to the ODrive. - -The ODrive does not echo commands. That means that when you type commands into a program like `screen`, the characters you type won't show up in the console. - -### Arduino -There is an Arduino library that gives some examples on how to use the ASCII protocol to communicate with the ODrive. Check it out [here](../Arduino/ODriveArduino). - -## Command format - -The ASCII protocol is human-readable and line-oriented, with each line having the following format: - -``` -command *42 ; comment [new line character] -``` - - * `*42` stands for a GCode compatible checksum and can be omitted. If and only if a checksum is provided, the device will also include a checksum in the response, if any. If the checksum is provided but is not valid, the line is ignored. The checksum is calculated as the bitwise xor of all characters before the asterisk (`*`).
    Example of a valid checksum: `r vbus_voltage *93`. - * comments are supported for GCode compatibility - * the command is interpreted once the new-line character is encountered - -## Command Reference - -#### Motor trajectory command -``` -t motor destination -``` -* `t` for trajectory -* `motor` is the motor number, `0` or `1`. -* `destination` is the goal position, in [turns]. - -Example: `t 0 -2` - -For general moving around of the axis, this is the recommended command. - -This command updates the watchdog timer for the motor. - -#### Motor Position command -For basic use where you send one setpoint at at a time, use the `q` command. -If you have a realtime controller that is streaming setpoints and tracking a trajectory, use the `p` command. - -``` -q motor position velocity_lim torque_lim -``` -* `q` for position -* `motor` is the motor number, `0` or `1`. -* `position` is the desired position, in [turns]. -* `velocity_lim` is the velocity limit, in [turns/s] (optional). -* `torque_lim` is the torque limit, in [Nm] (optional). - -Example: `q 0 -2 1 0.1` - -``` -p motor position velocity_ff torque_ff -``` -* `p` for position -* `motor` is the motor number, `0` or `1`. -* `position` is the desired position, in [turns]. -* `velocity_ff` is the velocity feed-forward term, in [turns/s] (optional). -* `torque_ff` is the torque feed-forward term, in [Nm] (optional). - -Example: `p 0 -2 0 0` - -Note that if you don't know what feed-forward is or what it's used for, simply omit it. - -This command updates the watchdog timer for the motor. - -#### Motor Velocity command -``` -v motor velocity torque_ff -``` -* `v` for velocity -* `motor` is the motor number, `0` or `1`. -* `velocity` is the desired velocity in [turns/s]. -* `torque_ff` is the torque feed-forward term, in [Nm] (optional). - -Example: `v 0 1 0` - -Note that if you don't know what feed-forward is or what it's used for, simply omit it. - -This command updates the watchdog timer for the motor. - -#### Motor Current command -``` -c motor torque -``` -* `c` for torque -* `motor` is the motor number, `0` or `1`. -* `torque` is the desired torque in [Nm]. - -This command updates the watchdog timer for the motor. - -#### Request feedback -``` -f motor - -response: -pos vel -``` -* `f` for feedback -* `pos` is the encoder position in [turns] (float) -* `vel` is the encoder velocity in [turns/s] (float) - -#### Update motor watchdog -``` -u motor -``` -* `u` for /u/pdate. -* `motor` is the motor number, `0` or `1`. - -This command updates the watchdog timer for the motor, without changing any -setpoints. - -#### Parameter reading/writing - -Not all parameters can be accessed via the ASCII protocol but at least all parameters with float and integer type are supported. - - * Reading: - ``` - r [property] - ``` - * `property` name of the property, as seen in ODrive Tool - * response: text representation of the requested value - * Example: `r vbus_voltage` => response: `24.087744` <new line> - * Writing: - ``` - w [property] [value] - ``` - * `property` name of the property, as seen in ODrive Tool - * `value` text representation of the value to be written - * Example: `w axis0.controller.input_pos -123.456` - -#### System commands: -* `ss` - Save config -* `se` - Erase config -* `sr` - Reboot -* `sc` - Clear errors diff --git a/docs/reStructuredText/ascii-protocol.rst b/docs/ascii-protocol.rst similarity index 100% rename from docs/reStructuredText/ascii-protocol.rst rename to docs/ascii-protocol.rst diff --git a/docs/can-guide.md b/docs/can-guide.md deleted file mode 100644 index e960a915..00000000 --- a/docs/can-guide.md +++ /dev/null @@ -1,138 +0,0 @@ -# CAN Bus Guide for ODrive - -ODrive v3 supports CAN 2.0b. We've built a [simple protocol](can-protocol.md) (named CANSimple) so that most ODrive functions can be controlled without a full CAN Open or similar stack. This guide is intended for beginners to set up CAN on the ODrive and on their host device. We will be focusing on Raspberry Pi and Arduino-compatible devices using the MCP2515 CAN Controller. - -## What is CAN bus? - -Borrowing from [Wikipeda](https://en.wikipedia.org/wiki/CAN_bus): - -> A Controller Area Network (CAN bus) is a robust vehicle bus standard designed to allow microcontrollers and devices to communicate with each other's applications without a host computer. It is a message-based protocol, designed originally for multiplex electrical wiring within automobiles to save on copper, but it can also be used in many other contexts. For each device, the data in a frame is transmitted sequentially but in such a way that if more than one device transmits at the same time, the highest priority device can continue while the others back off. Frames are received by all devices, including by the transmitting device. - -In simple terms, CAN is a way of communicating between many devices over a single twisted pair of wires. The signal is transmitted as the difference in voltage between the two wires (differential signalling), which makes it very robust against noise. Instead of using a unique address (like I2C) or a select pin (like SPI), CAN *messages* have a unique ID that also acts as the priority. At the beginning of a message frame, all devices talk and read at the same time. As the message ID is transmitted, the lowest value "wins" and that message will be transmitted (ID **0** has the *highest* priority). All other devices will wait for the next chance to send. If two devices send the same message ID at the same time, they will conflict and a bus failure may occur. Make sure your devices can never send the same message ID at the same time! - -See also this great article from Danfoss that quickly describes how to put together the wiring for a CAN bus https://danfosseditron.zendesk.com/hc/en-gb/articles/360042232992-CAN-bus-physical-layer - -![CAN picture](screenshots/CAN_Bus_Drawing.png) - - - -## Why use CAN? - -CAN is convenient for its simple and robust Physical Layer (PHY) that requires only a twisted pair of wires and a 120ohm termination resistor at each end. It has low jitter and low latency, because there is no host computer. It is relatively fast (CAN 2.0b supports 1 Mbps). Messages are easy to configure and load with data. Transceivers and controllers are inexpensive and widely available, thanks to its use in automotive. - -## Hardware Setup -ODrive assumes the CAN PHY is a standard differential twisted pair in a linear bus configuration with 120 ohm termination resistance at each end. ODrive versions less than V3.5 include a soldered 120 ohm termination resistor, but ODrive versions V3.5 and greater implement a dip switch to toggle the termination. ODrive uses 3.3v as the high output, but conforms to the CAN PHY requirement of achieving a differential voltage > 1.5V to represent a "0". As such, it is compatible with standard 5V bus architectures. - -## Setting up CAN on ODrive - -CANSimple breaks the CAN Message ID into two parts: An axis ID and a command ID. By default, CAN is enabled on the ODrive, where Axis 0 has ID 0, and Axis 1 has ID 1. The ID of each axis should be unique; each should be set via `odrivetool` before connecting to the bus with the command: - -`..config.can.node_id = ` - -By default, ODrive supports a value up to 63 (`0x3F`). See [can-protocol.md](can-protocol.md) for more information. - -You should also set the CAN bus speed on ODrive with the command `.can.config.baud_rate = ` - -| Speed | Value | -| --------- | ------- | -| 125 kbps | 125000 | -| 250 kbps | 250000 | -| 500 kbps | 500000 | -| 1000 kbps | 1000000 | - -That's it! You're ready to set up your host device. - -### Example -```Python -odrv0.axis0.config.can.node_id = 0 -odrv0.axis1.config.can.node_id = 1 -odrv0.can.config.baud_rate = 250000 -``` - -## Setting up a Raspberry Pi for CAN communications -First, you will need a CAN Hat for your Raspberry Pi. We are using [this CAN hat](https://www.amazon.com/Raspberry-Long-Distance-Communication-Transceiver-SN65HVD230/dp/B07DQPYFYV). - -Setting up the Raspberry Pi essentially involves the following: -1. Enable SPI communications to the MCP2515 -2. Install `can-utils` with `apt-get install can-utils` -3. Creating a connection between your application and the `can0` socket - -There are many tutorials for this process. [This one is pretty good](https://www.hackster.io/youness/how-to-connect-raspberry-pi-to-can-bus-b60235), and [this recent forum post](https://www.raspberrypi.org/forums/viewtopic.php?t=296117) also works. However, be careful. You have to set the correct parameters for the particular CAN hat you're using! - -1. Set the correct oscillator value - -We configure the MCP2515 in section 2.2 of the tutorial, but the hat we recommend uses a 12MHz crystal instead of a 16 MHz crystal. If you're not sure what value to use, the top of the [oscillator](https://en.wikipedia.org/wiki/Crystal_oscillator) will have the value printed on it in MHz. - -My Settings: -``` -dtparam=spi-on -dtoverlay=mcp2515-can0,oscillator=12000000,interrupt=25 -dtoverlay=spi0-hw-cs -``` - -2. Use the correct CAN baud rate - -By default, ODrive uses 250 kbps (250000) but the tutorial is using 500 kbps. Make sure you use the value set earlier on the ODrive. - -``` -sudo ip link set can0 up type can bitrate 250000 -``` - -### Wiring ODrive to CAN -The CANH and CANL pins on J2 are used for CAN communication. Connect CANH to CANH on all other devices, and CANL to CANL. - -If your ODrive is the "last" (furthest) device on the bus, you can use the on-board 120 Ohm termination resistor by switching the DIP switch to "CAN 120R". Otherwise, add an external resistor. - - - -### Verifying Communcation - -By default, each ODrive axis will send a heartbeat message at 10Hz. We can confirm our ODrive communication is working by starting the `can0` interface, and then reading from it: - -``` -sudo ip link set can0 up type can bitrate 250000 -candump can0 -xct z -n 10 -``` - -This will read the first 10 messages from the ODrive and stop. If you'd like to see all messages, remove the `-n 10` part (hit CTRL+C to exit). The other flags (x, c, t) are adding extra information, colouring, and a timestamp, respectively. - -``` -$ candump can0 -xct z -n 10 - (000.000000) can0 RX - - 001 [8] 00 00 00 00 01 00 00 00 - (000.001995) can0 RX - - 021 [8] 00 00 00 00 08 00 00 00 - (000.099978) can0 RX - - 001 [8] 00 00 00 00 01 00 00 00 - (000.101963) can0 RX - - 021 [8] 00 00 00 00 08 00 00 00 - (000.199988) can0 RX - - 001 [8] 00 00 00 00 01 00 00 00 - (000.201980) can0 RX - - 021 [8] 00 00 00 00 08 00 00 00 - (000.299986) can0 RX - - 001 [8] 00 00 00 00 01 00 00 00 - (000.301976) can0 RX - - 021 [8] 00 00 00 00 08 00 00 00 - (000.399986) can0 RX - - 001 [8] 00 00 00 00 01 00 00 00 - (000.401972) can0 RX - - 021 [8] 00 00 00 00 08 00 00 00 -``` - -Alternatively, if you have python can installed (`pip3 install python-can`), you can use the can.viewer script: - -`python3 -m can.viewer -c "can0" -i "socketcan"` which will give you a nice readout. See [the python-can docs](https://python-can.readthedocs.io/en/master/scripts.html#can-viewer) for an example. - -## Commanding the ODrive - -Now that we've verified the communication is working, we can try commanding the ODrive. Make sure your ODrive is configured and working properly over USB with `odrivetool` before continuing. See the [Getting Started Guide](getting-started.md) for help with first-time configuration. - -To move the ODrive, we use the command `Set Input Pos`, or cmd ID `0x00C`. First we create a message with this ID, and then "OR" in the axis ID. Then we create an 8-byte array of data with input position that we want, with a float value turned into bytes... this can be a pain though. - -## DBC Files - -A DBC file (.dbc) is a database of all the messages and signals in a CAN protocol. This file can be used with Python cantools to serialize and deserialize messages without having to handle the bitshifting etc yourself. We have generated a .dbc for CANSimple for you! - -* [CANSimple DBC File](../tools/odrive-cansimple.dbc) -* [CANSimple DBC Generator Script](../tools/create_can_dbc.py) - -Instead of manually writing values into the data, we can create a dictionary of signal:value pairs and serialize the data according to the database definition. - -1. Load the database into memory -2. Use `encode_message()` to get a byte array representation of data for sending -3. Use `decode_message()` to get a dictionary representation of data for receiving - -The [CAN DBC Example](../tools/can_dbc_example.py) script shows you how this can be used. This is the recommended method of serializing and deserializing. - -If you're using C++, then you can use the [CANHelpers](../Firmware/communication/can/can_helpers.hpp) single-header library to do this instead, although the DBC file isn't used. diff --git a/docs/reStructuredText/can-guide.rst b/docs/can-guide.rst similarity index 100% rename from docs/reStructuredText/can-guide.rst rename to docs/can-guide.rst diff --git a/docs/can-protocol.md b/docs/can-protocol.md deleted file mode 100644 index 77008f45..00000000 --- a/docs/can-protocol.md +++ /dev/null @@ -1,111 +0,0 @@ -# CAN Protocol - -This document describes the CAN Protocol. For examples of usage, check out our [CAN Guide!](can-guide.md) - - ---- -## Configuring ODrive for CAN -Configuration of the CAN parameters should be done via USB before putting the device on the bus. - -To set the desired baud rate, use `.can.config.baud_rate = `. - -Each axis looks like a separate node on the bus. Thus, they both have the two properties `can_node_id` and `can_node_id_extended`. The node ID can be from 0 to 63 (0x3F) inclusive, or, if extended CAN IDs are used, from 0 to 16777215 (0xFFFFFF). If you want to connect more than one ODrive on a CAN bus, you must set different node IDs for the second ODrive or they will conflict and crash the bus. - -### Example Configuration - -``` -odrv0.axis0.config.can_node_id = 3 -odrv0.axis1.config.can_node_id = 1 -odrv0.can.config.baud_rate = 500000 -odrv0.save_configuration() -odrv0.reboot() -``` - ---- -## Transport Protocol -We've implemented a very basic CAN protocol that we call "CAN Simple" to get users going with ODrive. This protocol is sufficiently abstracted that it is straightforward to add other protocols such as CANOpen, J1939, or Fibre over ISO-TP in the future. Unfortunately, implementing those protocols is a lot of work, and we wanted to give users a way to control ODrive's basic functions via CAN sooner rather than later. - -### CAN Frame -At its most basic, the CAN Simple frame looks like this: - -* Upper 6 bits - Node ID - max 0x3F (or 0xFFFFFF when using extended CAN IDs) -* Lower 5 bits - Command ID - max 0x1F - -To understand how the Node ID and Command ID interact, let's look at an example - -The 11-bit Arbitration ID is setup as follows: - -`can_id = axis_id << 5 | cmd_id` - -For example, an Axis ID of `0x01` with a command of `0x0C` would be result in `0x2C`: - -`0x01 << 5 | 0x0C = 0x2C` - -### Messages - -CMD ID | Name | Sender | Signals | Start byte | Signal Type | Bits | Factor | Offset ---: | :-- | :-- | :-- | :-- | :-- | :-- | :-- | :-- -0x000 | CANOpen NMT Message\*\* | Master | - | - | - | - | - | - -0x001 | ODrive Heartbeat Message | Axis | Axis Error
    Axis Current State
    Controller Status | 0
    4
    7 | Unsigned Int
    Unsigned Int
    Bitfield | 32
    8
    8 | -
    -
    - | -
    -
    - -0x002 | ODrive Estop Message | Master | - | - | - | - | - | - -0x003 | Get Motor Error\* | Axis | Motor Error | 0 | Unsigned Int | 64 | 1 | 0 -0x004 | Get Encoder Error\* | Axis | Encoder Error | 0 | Unsigned Int | 32 | 1 | 0 -0x005 | Get Sensorless Error\* | Axis | Sensorless Error | 0 | Unsigned Int | 32 | 1 | 0 -0x006 | Set Axis Node ID | Master | Axis CAN Node ID | 0 | Unsigned Int | 32 | 1 | 0 -0x007 | Set Axis Requested State | Master | Axis Requested State | 0 | Unsigned Int | 32 | 1 | 0 -0x008 | Set Axis Startup Config | Master | - Not yet implemented - | - | - | - | - | - -0x009 | Get Encoder Estimates\* | Master | Encoder Pos Estimate
    Encoder Vel Estimate | 0
    4 | IEEE 754 Float
    IEEE 754 Float | 32
    32 | 1
    1 | 0
    0 -0x00A | Get Encoder Count\* | Master | Encoder Shadow Count
    Encoder Count in CPR | 0
    4 | Signed Int
    Signed Int | 32
    32 | 1
    1 | 0
    0 -0x00B | Set Controller Modes | Master | Control Mode
    Input Mode | 0
    4 | Signed Int
    Signed Int | 32
    32 | 1
    1 | 0
    0 -0x00C | Set Input Pos | Master | Input Pos
    Vel FF
    Torque FF | 0
    4
    6 | IEEE 754 Float
    Signed Int
    Signed Int | 32
    16
    16 | 1
    0.001
    0.001 | 0
    0
    0 -0x00D | Set Input Vel | Master | Input Vel
    Torque FF | 0
    4 | IEEE 754 Float
    IEEE 754 Float | 32
    32 | 1
    1 | 0
    0 -0x00E | Set Input Torque | Master | Input Torque | 0 | IEEE 754 Float | 32 | 1 | 0 -0x00F | Set Limits | Master | Velocity Limit
    Current Limit | 0
    4 | IEEE 754 Float
    IEEE 754 Float | 32
    | 1
    1 | 0
    0 -0x010 | Start Anticogging | Master | - | - | - | - | - | - -0x011 | Set Traj Vel Limit | Master | Traj Vel Limit | 0 | IEEE 754 Float | 32 | 1 | 0 -0x012 | Set Traj Accel Limits | Master | Traj Accel Limit
    Traj Decel Limit | 0
    4 | IEEE 754 Float
    IEEE 754 Float | 32
    32 | 1
    1 | 0
    0 -0x013 | Set Traj Inertia | Master | Traj Inertia | 0 | IEEE 754 Float | 32 | 1 | 0 -0x014 | Get IQ\* | Axis | Iq Setpoint
    Iq Measured | 0
    4 | IEEE 754 Float
    IEEE 754 Float | 32
    32 | 1
    1 | 0
    0 -0x015 | Get Sensorless Estimates\* | Master | Sensorless Pos Estimate
    Sensorless Vel Estimate | 0
    4 | IEEE 754 Float
    IEEE 754 Float | 32
    32 | 1
    1 | 0
    0 -0x016 | Reboot ODrive | Master\*\*\* | - | - | - | - | - | - -0x017 | Get Vbus Voltage | Master\*\*\* | Vbus Voltage | 0 | IEEE 754 Float | 32 | 1 | 0 -0x018 | Clear Errors | Master | - | - | - | - | - | - -0x019 | Set Linear Count | Master | Position | 0 | Signed Int | 32 | 1 | 0 -0x01A | Set Position Gain | Master | Pos Gain | 0 | IEEE 754 Float | 32 | 1 | 0 -0x01B | Set Vel Gains | Master | Vel Gain
    Vel Integrator Gain | 0
    4 | IEEE 754 Float
    IEEE 754 Float | 32
    32 | 1
    1 | 0
    0 -0x700 | CANOpen Heartbeat Message\*\* | Slave | - | - | - | - | - | - --|-|-|----------------------------------|-|--------------------|-|-|- - -All multibyte values are little endian (aka Intel format, aka least significant byte first). - -\* Note: These messages are call & response. The Master node sends a message with the RTR bit set, and the axis responds with the same ID and specified payload. -\*\* Note: These CANOpen messages are reserved to avoid bus collisions with CANOpen devices. They are not used by CAN Simple. -\*\*\* Note: These messages can be sent to either address on a given ODrive board. - ---- - -### Cyclic Messages -Cyclic messages are sent by ODrive on a timer without a request. As of `fw0.5.4`, the Cyclic messsages are: - -ID | Name | Rate (ms) ---: | :-- | :-- -0x001 | ODrive Heartbeat Message | 100 -0x009 | Encoder Estimates | 10 - -These can be configured for each axis, see e.g. `axis.config.can`. - ---- - -### Interoperability with CANopen -You can deconflict with CANopen like this: - -`odrv0.axis0.config.can.node_id = 0x010` - Reserves messages 0x200 through 0x21F -`odrv0.axis1.config.can.node_id = 0x018` - Reserves messages 0x300 through 0x31F - -It may not be obvious, but this allows for some compatibility with CANOpen. Although the address space 0x200 and 0x300 correspond to receive PDO base addresses, we can guarantee they will not conflict if all CANopen node IDs are >= 32. E.g.: - -CANopen nodeID = 35 = 0x23 -Receive PDO 0x200 + nodeID = 0x223, which does not conflict with the range [0x200 : 0x21F] - -Be careful that you don't assign too many nodeIDs per PDO group. Four CAN Simple nodes (32*4) is all of the available address space of a single PDO. If the bus is strictly ODrive CAN Simple nodes, a simple sequential Node ID assignment will work fine. - diff --git a/docs/reStructuredText/can-protocol.rst b/docs/can-protocol.rst similarity index 100% rename from docs/reStructuredText/can-protocol.rst rename to docs/can-protocol.rst diff --git a/docs/commands.md b/docs/commands.md deleted file mode 100644 index 8f4ab9e2..00000000 --- a/docs/commands.md +++ /dev/null @@ -1,105 +0,0 @@ -# Parameters & Commands - -We will use the `` as a placeholder for any ODrive object. Every ODrive controller is an ODrive object. In `odrivetool` this is usually `odrv0`. Furthermore we use `` as a placeholder for any axis, which is an attribute of an ODrive object (for example `odrv0.axis0`). An axis represents where the motors are connected. (axis0 for M0 or axis1 for M1) - -### Table of contents - - -- [Per-Axis commands](#per-axis-commands) -- [System monitoring commands](#system-monitoring-commands) -- [General system commands](#general-system-commands) -- [Setting up sensorless](#setting-up-sensorless) - - - -## Per-Axis commands - -For the most part, both axes on the ODrive can be controlled independently. - -### State Machine - -The current state of an axis is indicated by [`.current_state`](api/odrive.axis#current_state). The user can request a new state by assigning a new value to [`.requested_state`](api/odrive.axis#current_state). The default state after startup is `AXIS_STATE_IDLE`. A description of all states can be found [here](api/odrive.axis.axisstate). - - -### Startup Procedure - -By default the ODrive takes no action at startup and goes to idle immediately. -In order to change what startup procedures are used, set the startup procedures you want to `True`. -The ODrive will sequence all enabled startup actions selected in the order shown below. - -* `.config.startup_motor_calibration` -* `.config.startup_encoder_index_search` -* `.config.startup_encoder_offset_calibration` -* `.config.startup_closed_loop_control` - -See [here](api/odrive.axis.axisstate) for a description of each state. - -### Control Mode -The default control mode is position control. -If you want a different mode, you can change `.controller.config.control_mode`. -Possible values are listed [here](api/odrive.controller.controlmode). - -### Input Mode - -As of version v0.5.0, ODrive now intercepts the incoming commands and can apply filters to them. The old protocol values `pos_setpoint`, `vel_setpoint`, and `current_setpoint` are still used internally by the closed-loop cascade control, but the user cannot write to them directly. This allows us to condense the number of ways the ODrive accepts motion commands. The new commands are: - -### Control Commands -* `.controller.input_pos = ` -* `.controller.input_vel = ` -* `.controller.input_torque = ` - -Modes can be selected by changing `.controller.config.input_mode`. -The default input mode is `INPUT_MODE_PASSTHROUGH`. -Possible values are listed [here](api/odrive.controller.inputmode). - -## System monitoring commands - -### Encoder position and velocity -* View encoder position with `.encoder.pos_estimate` [turns] or `.encoder.pos_est_counts` [counts] -* View rotational velocity with `.encoder.vel_estimate` [turn/s] or `.encoder.vel_est_counts` [count/s] - -### Motor current and torque estimation -* View the commanded motor current with `.motor.current_control.Iq_setpoint` [A] -* View the measured motor current with `.motor.current_control.Iq_measured` [A]. If you find that this returns noisy data then use the command motor current instead. The two values should be close so long as you are not approaching the maximum achievable rotational velocity of your motor for a given supply voltage, in which case the commanded current may become larger than the measured current. - -Using the motor current and the known KV of your motor you can estimate the motors torque using the following relationship: Torque [N.m] = 8.27 * Current [A] / KV. - -## General system commands - -### Saving the configuration - -All variables that are part of a `[...].config` object can be saved to non-volatile memory on the ODrive so they persist after you remove power. The relevant commands are: - - * `.save_configuration()`: Stores the configuration to persistent memory on the ODrive. - * `.erase_configuration()`: Resets the configuration variables to their factory defaults. This also reboots the device. - -### Diagnostics - - * `.serial_number`: A number that uniquely identifies your device. When printed in upper case hexadecimal (`hex(.serial_number).upper()`), this is identical to the serial number indicated by the USB descriptor. - * `.fw_version_major`, `.fw_version_minor`, `.fw_version_revision`: The firmware version that is currently running. - * `.hw_version_major`, `.hw_version_minor`, `.hw_version_revision`: The hardware version of your ODrive. - -## Setting up sensorless -The ODrive can run without encoder/hall feedback, but there is a minimum speed, usually around a few hundred RPM. In other words, sensorless mode does not support stopping or changing direction! - -Sensorless mode starts by ramping up the motor speed in open loop control and then switches to closed loop control automatically. The sensorless speed ramping parameters are in `axis.config.sensorless_ramp` The `vel` and `accel` (in [radians/s] and [radians/s^2]) control the speed that the ramp tries to reach and how quickly it gets there. When the ramp reaches `sensorless_ramp.vel`, `controller.input_vel` is automatically set to the same velocity, in [turns/s], and the state switches to closed loop control. - -If your motor comes to a stop after the ramp, try incrementally raising the `vel` parameter. The goal is to be above the minimum speed necessary for sensorless position and speed feedback to converge - this is not well-parameterized per motor. The parameters suggested below work for the D5065 motor, with 270KV and 7 pole pairs. If your motor grinds and skips during the ramp, lower the `accel` parameter until it is tolerable. - -Below are some suggested starting parameters that you can use for the ODrive D5065 motor. Note that you _must_ set the `pm_flux_linkage` correctly for sensorless mode to work. Motor calibration and setup must also be completed before sensorless mode will work. - - -``` -odrv0.axis0.controller.config.vel_gain = 0.01 -odrv0.axis0.controller.config.vel_integrator_gain = 0.05 -odrv0.axis0.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL -odrv0.axis0.controller.config.vel_limit = )> -odrv0.axis0.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current -odrv0.axis0.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / ( * ) -odrv0.axis0.config.enable_sensorless_mode = True -``` - -To start the motor: -``` -.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL -``` diff --git a/docs/reStructuredText/commands.rst b/docs/commands.rst similarity index 100% rename from docs/reStructuredText/commands.rst rename to docs/commands.rst diff --git a/docs/reStructuredText/conf.py b/docs/conf.py similarity index 91% rename from docs/reStructuredText/conf.py rename to docs/conf.py index ae8591d5..c55701ae 100644 --- a/docs/reStructuredText/conf.py +++ b/docs/conf.py @@ -15,8 +15,8 @@ import sys sys.path.insert(0, os.path.abspath('.')) sys.path.insert(0, os.path.abspath('./figures')) -sys.path.insert(0, os.path.abspath('../exts')) # needed for fibre_autodoc extension -sys.path.insert(0, os.path.abspath('../../tools/fibre-tools')) # needed for fibre_autodoc extension +sys.path.insert(0, os.path.abspath('./exts')) # needed for fibre_autodoc extension +sys.path.insert(0, os.path.abspath('../tools/fibre-tools')) # needed for fibre_autodoc extension # -- Project information ----------------------------------------------------- @@ -66,7 +66,7 @@ html_theme = "sphinx_rtd_theme" # so a file named "default.css" will overwrite the builtin "default.css". html_static_path = ['_static'] -fibre_interface_files = ['../../Firmware/odrive-interface.yaml'] +fibre_interface_files = ['../Firmware/odrive-interface.yaml'] autosummary_generate = False diff --git a/docs/configuring-eclipse.md b/docs/configuring-eclipse.md deleted file mode 100644 index e4576255..00000000 --- a/docs/configuring-eclipse.md +++ /dev/null @@ -1,35 +0,0 @@ -# Setting up Eclipse development environment - -## Install -* Install [Eclipse IDE for C/C++ Developers](http://www.eclipse.org/downloads/packages/eclipse-ide-cc-developers/neon3) -* Install the [OpenOCD Eclipse plugin](http://gnuarmeclipse.github.io/plugins/install/) - -## Import project -* File -> Import -> C/C++ -> Existing Code as Makefile Project -* Browse for existing code location, find the OdriveFirmware root. -* In the Toolchain options, select `Cross GCC` -* Hit Finish -* Build the project (press ctrl-B) - -![Toolchain options](screenshots/CodeAsMakefile.png "Toolchain options") - -## Load the launch configuration -* File -> Import -> Run/Debug -> Launch Configurations -> Next -* Highlight (don't tick) the OdriveFirmare folder in the left column -* Tick OdriveFirmware.launch in the right column -* Hit Finish - -![Launch Configurations](screenshots/ImportLaunch.png "Launch Configurations") - -## Launch! -* Make sure the programmer is connected to the board as per [Flashing the firmware](#flashing-the-firmware). -* Press the down-arrow of the debug symbol in the toolbar, and hit Debug Configurations - * You can also hit Run -> Debug Configurations -* Highlight the debug configuration you imported, called OdriveFirmware. If you do not see the imported launch configuration rename your project to `ODriveFirmware` or edit the launch configuration to match your project name by unfiltering unavailable projects: - -![Launch Configuration Filters](screenshots/LaunchConfigFilter.png "Launch Configuration Filters") - -* Hit Debug -* Eclipse should flash the board for you and the program should start halted on the first instruction in `Main` -* Set beakpoints, step, hit Resume, etc. -* Make some cool features! ;D \ No newline at end of file diff --git a/docs/reStructuredText/configuring-eclipse.rst b/docs/configuring-eclipse.rst similarity index 100% rename from docs/reStructuredText/configuring-eclipse.rst rename to docs/configuring-eclipse.rst diff --git a/docs/configuring-vscode.md b/docs/configuring-vscode.md deleted file mode 100644 index 0f08da1e..00000000 --- a/docs/configuring-vscode.md +++ /dev/null @@ -1,56 +0,0 @@ -# Configuring Visual Studio Code - -VSCode is the recommended IDE for working with the ODrive codebase. It is a light-weight text editor with Git integration and GDB debugging functionality. - -Before doing the VSCode setup, make sure you've installed all of your [prerequisites](developer-guide#installing-prerequisites) - -## Setup Procedure -1. Clone the ODrive repository -1. [Download VSCode](https://code.visualstudio.com/download) -1. Open VSCode -1. Install extensions. This can be done directly from VSCode (Ctrl+Shift+X) - * Required extensions: - * C/C++ `ext install ms-vscode.cpptools` - * Cortex-Debug `ext install marus25.cortex-debug` - * Cortex-Debug: Device Support Pack - STM32F4 `ext install marus25.cortex-debug-dp-stm32f4` - * Recommended Extensions: - * Include Autocomplete - * Path Autocomplete - * Auto Comment Blocks -1. Create an environment variable named `ARM_GCC_ROOT` whose value is the location of the `GNU Arm Embedded Toolchain` (.e.g `C:\Program Files (x86)\GNU Tools Arm Embedded\7 2018-q2-update`) that you installed in the prerequisites section of the developer's guide. This is not strictly needed for Linux or Mac, and you can alternatively use the `Cortex-debug: Arm Toolchain Path` setting in VSCode extension settings. -1. Relaunch VSCode -1. Open the VSCode Workspace file, which is located in the root of the ODrive repository. It is called `ODrive_Workspace.code-workspace`. The first time you open it, VSCode will install some dependencies. If it fails, you may need to [change your proxy settings](https://code.visualstudio.com/docs/getstarted/settings). - -You should now be ready to compile and test the ODrive project. - -## Building the Firmware -* Terminal -> Run Build Task (Ctrl+Shift+B) - -A terminal window will open with your native shell. VSCode is configured to run the command `make -j4` in this terminal. - -## Flashing the Firmware -* Terminal -> Run Task -> flash - -A terminal window will open with your native shell. VSCode is configured to run the command `make flash` in this terminal. - -If the flashing worked, you can connect to the board using the [odrivetool](getting-started#start-odrivetool). - -## Debugging -An extension called Cortex-Debug has recently been released which is designed specifically for debugging ARM Cortex projects. You can read more on Cortex-Debug here: https://github.com/Marus/cortex-debug - -Note: If developing on Windows, you should have `arm-none-eabi-gdb` and `openOCD` on your PATH. - - * Make sure you have the Firmware folder as your active folder - * Set `CONFIG_DEBUG=true` in the tup.config file - * Flash the board with the newest code (starting debug session doesn't do this) - * In the _Run_ tab (Ctrl+Shift+D), select "Debug ODrive (Firmware)" - * Press _Start Debugging_ (or press F5) - * The processor will reset and halt. - * Set your breakpoints. Note: you can only set breakpoints when the processor is halted, if you set them during run mode, they won't get applied. - * _Continue_ (F5) - * Stepping over/in/out, restarting, and changing breakpoints can be done by first pressing the "pause" (F6) button at the top the screen. - * When done debugging, simply stop (Shift+F5) the debugger. It will kill your openOCD process too. - -## Cleaning the Build -This sometimes needs to be done if you change branches. -* Open a terminal (View -> Integrated Terminal) and enter `make clean` diff --git a/docs/reStructuredText/configuring-vscode.rst b/docs/configuring-vscode.rst similarity index 100% rename from docs/reStructuredText/configuring-vscode.rst rename to docs/configuring-vscode.rst diff --git a/docs/control-modes.md b/docs/control-modes.md deleted file mode 100644 index d896d6e1..00000000 --- a/docs/control-modes.md +++ /dev/null @@ -1,100 +0,0 @@ - -The default control mode is unfiltered position control in the absolute encoder reference frame. You may wish to use a controlled trajectory instead. Or you may wish to control position in a circular frame to allow continuous rotation forever without growing the numeric value of the setpoint too large. - -You may also wish to control velocity (directly or with a ramping filter). -You can also directly control the current of the motor, which is proportional to torque. - -- [Filtered position control](#filtered-position-control) -- [Trajectory control](#trajectory-control) -- [Circular position control](#circular-position-control) -- [Velocity control](#velocity-control) -- [Ramped velocity control](#ramped-velocity-control) -- [Torque control](#torque-control) - - -### Filtered position control -Asking the ODrive controller to go as hard as it can to raw setpoints may result in jerky movement. Even if you are using a planned trajectory generated from an external source, if that is sent at a modest frequency, the ODrive may chase each stair in the incoming staircase in a jerky way. In this case, a good starting point for tuning the filter bandwidth is to set it to one half of your setpoint command rate. - -You can use the second order position filter in these cases. -Set the filter bandwidth: `axis.controller.config.input_filter_bandwidth = 2.0` [1/s]
    -Activate the setpoint filter: `axis.controller.config.input_mode = INPUT_MODE_POS_FILTER`.
    -You can now control the velocity with `axis.controller.input_pos = 1` [turns]. - -![secondOrderResponse](secondOrderResponse.PNG)
    -Step response of a 1000 to 0 position input with a filter bandwidth of 1.0 [/sec]. - -### Trajectory control -See the **Usage** section for usage details.
    -This mode lets you smoothly accelerate, coast, and decelerate the axis from one position to another. With raw position control, the controller simply tries to go to the setpoint as quickly as possible. Using a trajectory lets you tune the feedback gains more aggressively to reject disturbance, while keeping smooth motion. - -![Taptraj](TrapTrajPosVel.PNG)
    -In the above image blue is position and orange is velocity. - -#### Parameters -``` -..trap_traj.config.vel_limit = -..trap_traj.config.accel_limit = -..trap_traj.config.decel_limit = -..controller.config.inertia = -``` - -`vel_limit` is the maximum planned trajectory speed. This sets your coasting speed.
    -`accel_limit` is the maximum acceleration in turns / sec^2
    -`decel_limit` is the maximum deceleration in turns / sec^2
    -`controller.config.inertia` is a value which correlates acceleration (in turns / sec^2) and motor torque. It is 0 by default. It is optional, but can improve response of your system if correctly tuned. Keep in mind this will need to change with the load / mass of your system. - -All values should be strictly positive (>= 0). - -Keep in mind that you must still set your safety limits as before. It is recommended you set these a little higher ( > 10%) than the planner values, to give the controller enough control authority. -``` -..motor.config.current_lim = -..controller.config.vel_limit = -``` - -#### Usage -Make sure you are in position control mode. To activate the trajectory module, set the input mode to trajectory: -``` -axis.controller.config.input_mode = INPUT_MODE_TRAP_TRAJ -``` - -Simply send a position command to execute the move: -``` -..controller.input_pos = -``` - -Use the `move_incremental` function to move to a relative position. -To set the goal relative to the current actual position, use `from_goal_point = False` -To set the goal relative to the previous destination, use `from_goal_point = True` -``` -..controller.move_incremental(pos_increment, from_goal_point) -``` - -You can also execute a move with the [appropriate ascii command](ascii-protocol.md#motor-trajectory-command). - -### Circular position control - -To enable Circular position control, set `axis.controller.config.circular_setpoints = True` - -This mode is useful for continuous incremental position movement. For example a robot rolling indefinitely, or an extruder motor or conveyor belt moving with controlled increments indefinitely. -In the regular position mode, the `input_pos` would grow to a very large value and would lose precision due to floating point rounding. - -In this mode, the controller will try to track the position within only one turn of the motor. Specifically, `input_pos` is expected in the range `[0, 1)`. If the `input_pos` is incremented to outside this range (say via step/dir input), it is automatically wrapped around into the correct value. -Note that in this mode `encoder.pos_circular` is used for feedback instead of `encoder.pos_estimate`. - -If you try to increment the axis with a large step in one go that exceeds `1` turn, the motor will go to the same angle around the wrong way. This is also the case if there is a large disturbance. If you have an application where you would like to handle larger steps, you can use a larger circular range. Set `controller.config.circular_setpoints_range = N`. Choose N to give you an appropriate circular space for your application. - -### Velocity control -Set `axis.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL`.
    -You can now control the velocity with `axis.controller.input_vel = 1` [turn/s]. - -### Ramped velocity control -Set `axis.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL`.
    -Set the velocity ramp rate (acceleration): `axis.controller.config.vel_ramp_rate = 0.5` [turn/s^2]
    -Activate the ramped velocity mode: `axis.controller.config.input_mode = INPUT_MODE_VEL_RAMP`.
    -You can now control the velocity with `axis.controller.input_vel = 1` [turn/s]. - -### Torque control -Set `axis.controller.config.control_mode = CONTROL_MODE_TORQUE_CONTROL`.
    -You can now control the torque with `axis.controller.input_torque = 0.1` [Nm]. - -Note: If you exceed `vel_limit` in torque control mode, the current is reduced. To disable this, set `axis.controller.enable_torque_mode_vel_limit = False`. diff --git a/docs/reStructuredText/control-modes.rst b/docs/control-modes.rst similarity index 100% rename from docs/reStructuredText/control-modes.rst rename to docs/control-modes.rst diff --git a/docs/control.md b/docs/control.md deleted file mode 100644 index 10aab174..00000000 --- a/docs/control.md +++ /dev/null @@ -1,62 +0,0 @@ -# Control - -The motor controller is a cascaded style position, velocity and current control loop, as per the diagram below. When the control mode is set to position control, the whole loop runs. When running in velocity control mode, the position control part is removed and the velocity command is fed directly in to the second stage input. In torque control mode, only the current controller is used. - -![Cascaded pos vel I loops](controller_with_ff.png) - -Each stage of the control loop is a variation on a [PID controller](https://en.wikipedia.org/wiki/PID_controller). A PID controller is a mathematical model that can be adapted to control a wide variety of systems. This flexibility is essential as it allows the ODrive to be used to control all kinds of mechanical systems. - -* Note: The controller has been updated to use `torque` in Newton-meters instead of current at the "system" level. There is a `torque_constant` parameter which converts between torque and current, after which the rest of this explanation still holds. - -### Position loop: -The position controller is a P loop with a single proportional gain. -```text -pos_error = pos_setpoint - pos_feedback -vel_cmd = pos_error * pos_gain + vel_feedforward -``` - -### Velocity loop: -The velocity controller is a PI loop. -```text -vel_error = vel_cmd - vel_feedback -current_integral += vel_error * vel_integrator_gain -current_cmd = vel_error * vel_gain + current_integral + current_feedforward -``` - -### Current loop: -The current controller is a PI loop. -```text -current_error = current_cmd - current_fb -voltage_integral += current_error * current_integrator_gain -voltage_cmd = current_error * current_gain + voltage_integral (+ voltage_feedforward when we have motor model) -``` - -Note: `current_gain` and `current_integrator_gain` are automatically set according to `motor.config.current_control_bandwidth` - -For more detail refer to [controller.cpp](https://github.com/madcowswe/ODrive/blob/master/Firmware/MotorControl/controller.cpp#L86). - -### Controller Details: -The ultimate output of the controller is the voltage applied to the gate of each FET to deliver current through each coil of the motor. The current through the motor linearly relates to the torque output of the motor. This means that the inputs to the cascaded controller are theoretically the position (angle), velocity (angle/time), and acceleration (angle/time/time) of the motor. Note that when thinking about the controller from the perpective of the physics of the motor you would expect to see the time in the Velocity and Current loops, but it is absent because the time difference between iterations is always 125 microseconds (8kHz). Because the time difference between controller loops is a constant and can simply be wrapped into the controller gains. - -The output of each stage of the controller is clamped before being fed into the next stage. So after the `vel_cmd` is calculated from the position controller, the `vel_cmd` is clamped to the velocity limit. The `torque_cmd` output of the velocity controller is then clamped and fed to the current controller. Oddly enough the controller class does not contain the current controller, but instead the current controller is housed in the motor class due to the complexity of the motor driver schema. - -The feedforward terms available when using the position or velocity control mode are meant to enable better performance when the dynamics of a system are known and the host controller can predict the motion based on the load. A perfect example of this is the use of the trajectory controller that sets the position, velocity, and torque based on the desired position, velocity, and acceleration. If you take a trapezoidal velocity profile for example, you can imagine on the ramp upward the velocity will be increasing over time, while the torque is a non-zero constant. At the flat portion of the profile the velocity will be a non-zero constant, but the acceleration will be zero. This trajectory controller use case uses the cascaded controller with multiple inputs to achieve the desired motion with the best performance. - -## Tuning -Tuning the motor controller is an essential step to unlock the full potential of the ODrive. Tuning allows for the controller to quickly respond to disturbances or changes in the system (such as an external force being applied or a change in the setpoint) without becoming unstable. Correctly setting the three tuning parameters (called gains) ensures that ODrive can control your motors in the most effective way possible. The three values are: -* `.controller.config.pos_gain = 20.0` [(turn/s) / turn] -* `.controller.config.vel_gain = 0.16 ` [Nm/(turn/s)] -* `.controller.config.vel_integrator_gain = 0.32` [Nm/((turn/s) * s)] - -An upcoming feature will enable automatic tuning. Until then, here is a rough tuning procedure: -* Set vel_integrator_gain gain to 0 -* Make sure you have a stable system. If it is not, decrease all gains until you have one. -* Increase `vel_gain` by around 30% per iteration until the motor exhibits some vibration. -* Back down `vel_gain` to 50% of the vibrating value. -* Increase `pos_gain` by around 30% per iteration until you see some overshoot. -* Back down `pos_gain` until you do not have overshoot anymore. -* The integrator can be set to `0.5 * bandwidth * vel_gain`, where `bandwidth` is the overall resulting tracking bandwidth of your system. Say your tuning made it track commands with a settling time of 100ms (the time from when the setpoint changes to when the system arrives at the new setpoint); this means the bandwidth was 1/(100ms) = 1/(0.1s) = 10hz. In this case you should set the `vel_integrator_gain = 0.5 * 10 * vel_gain`. - -The liveplotter tool can be immensely helpful in dialing in these values. To display a graph that plots the position setpoint vs the measured position value run the following in the ODrive tool: - -`start_liveplotter(lambda:[odrv0.axis0.encoder.pos_estimate, odrv0.axis0.controller.pos_setpoint])` diff --git a/docs/reStructuredText/control.rst b/docs/control.rst similarity index 100% rename from docs/reStructuredText/control.rst rename to docs/control.rst diff --git a/docs/developer-guide.md b/docs/developer-guide.md deleted file mode 100644 index 34d3a3b3..00000000 --- a/docs/developer-guide.md +++ /dev/null @@ -1,335 +0,0 @@ -# ODrive Firmware Developer Guide - -This guide is intended for developers who wish to modify the firmware of the ODrive. -As such it assumes that you know things like how to use Git, what a compiler is, etc. If that sounds scary, turn around now. - -The official releases are maintained on the `master` branch. However since you are a developer, you are encouraged to use the `devel` branch, as it contains the latest features. - -The project is under active development, so make sure to check the [Changelog](../CHANGELOG.md) to keep track of updates. - -### Table of contents - - - -- [Prerequisites](#prerequisites) -- [Configuring the build](#configuring-the-build) -- [Building and flashing the Firmware](#building-and-flashing-the-firmware) -- [Debugging](#debugging) -- [Testing](#testing) -- [Setting up an IDE](#setting-up-an-ide) -- [STM32CubeMX](#stm32cubemx) -- [Troubleshooting](#troubleshooting) -- [Documentation](#documentation) -- [Releases](#releases) -- [Notes for Contributors](#notes-for-contributors) - - - -

    -## Prerequisites - -The recommended tools for ODrive development are: - - * **make**: Used to invoke tup - * **Tup**: The build system used to invoke the compile commands - * **ARM GNU Compiler**: For cross-compiling code - * **ARM GDB**: For debugging the code and stepping through on the device - * **OpenOCD**: For flashing the ODrive with the STLink/v2 programmer - * **Python 3**, along with the packages `PyYAML`, `Jinja2` and `jsonschema`: For running the Python tools (`odrivetool`). Also required for compiling firmware. - -See below for specific installation instructions for your OS. - -Depending on what you're gonna do, you may not need all of the components. - -Once you have everything, you can verify the correct installation by running: -```bash -$ arm-none-eabi-gcc --version -$ arm-none-eabi-gdb --version -$ openocd --version # should be 0.10.0 or later -$ tup --version # should be 0.7.5 or later -$ python --version # should be 3.7 or later -``` - -#### Linux (Ubuntu < 20.04) -```bash -sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa -sudo apt-get update -sudo apt-get install gcc-arm-embedded -sudo apt-get install openocd -sudo apt-get install git-lfs -sudo add-apt-repository ppa:jonathonf/tup && sudo apt-get update && sudo apt-get install tup -sudo apt-get install python3 python3-yaml python3-jinja2 python3-jsonschema -``` - -#### Linux (Ubuntu >= 20.04) -```bash -sudo apt install gcc-arm-none-eabi -sudo apt install openocd -sudo apt install git-lfs -sudo apt install tup -sudo apt install python3 python3-yaml python3-jinja2 python3-jsonschema -``` - -#### Arch Linux -```bash -sudo pacman -S arm-none-eabi-gcc arm-none-eabi-binutils -sudo pacman -S arm-none-eabi-gdb -sudo pacman -S git-lfs -sudo pacman -S tup -sudo pacman -S python python-yaml python-jinja python-jsonschema -``` -* [OpenOCD AUR package](https://aur.archlinux.org/packages/openocd/) - -#### Mac -First install [Homebrew](https://brew.sh/). Then you can run these commands in Terminal: -```bash -brew install armmbed/formulae/arm-none-eabi-gcc -brew install --cask osxfuse && brew install tup -brew install openocd -brew install git-lfs -pip3 install PyYAML Jinja2 jsonschema -``` - -#### Windows -__Note__: make sure these programs are not only installed but also added to your `PATH`. - -Some instructions in this document may assume that you're using a bash command prompt, such as the Windows 10 built-in bash or [Git](https://git-scm.com/download/win) bash. - -* [ARM compiler](https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads) - * __Note 1__: After installing, create an environment variable named `ARM_GCC_ROOT` whose value is the path you installed to. e.g. `C:\Program Files (x86)\GNU Tools Arm Embedded\7 2018-q2-update`. This variable is used to locate include files for the c/c++ Visual Studio Code extension. - * __Note 2__: 8-2018-q4-major seems to have a bug on Windows. Please use 7-2018-q2-update. -* [Tup](http://gittup.org/tup/index.html) -* [GNU MCU Eclipse's Windows Build Tools](https://github.com/gnu-mcu-eclipse/windows-build-tools/releases) -* [Python 3](https://www.python.org/downloads/) - * Install Python packages: `pip install PyYAML Jinja2 jsonschema` -* [OpenOCD](https://github.com/xpack-dev-tools/openocd-xpack/releases/). -* [ST-Link/V2 Drivers](https://www.st.com/content/st_com/en/products/development-tools/software-development-tools/stm32-software-development-tools/stm32-utilities/stsw-link009.html) - -
    - -## Configuring the build - -To customize the compile time parameters, copy or rename the file `Firmware/tup.config.default` to `Firmware/tup.config` and edit the parameters in that file: - -__CONFIG_BOARD_VERSION__: The board version you're using. Can be `v3.1`, `v3.2`, `v3.3`, `v3.4-24V`, `v3.4-48V`, `v3.5-24V`, `v3.5-48V`, etc. Check for a label on the upper side of the ODrive to find out which version you have. Some ODrive versions don't specify the voltage: in that case you can read the value of the main capacitors: 120uF are 48V ODrives, 470uF are 24V ODrives. - -__CONFIG_DEBUG__: Defines whether debugging will be enabled when compiling the firmware; specifically the `-g -gdwarf-2` flags. Note that printf debugging will only function if your tup.config specifies the `USB_PROTOCOL` or `UART_PROTOCOL` as stdout and `DEBUG_PRINT` is defined. See the IDE specific documentation for more information. - -You can also modify the compile-time defaults for all `.config` parameters. You will find them if you search for `AxisConfig`, `MotorConfig`, etc. - -

    -## Building and flashing the Firmware - -1. Run `make` in the `Firmware` directory. -2. Connect the ODrive via USB and power it up. -3. Flash the firmware using [odrivetool dfu](odrivetool#device-firmware-update). - -### Flashing using an STLink/v2 programmer - -* Connect `GND`, `SWD`, and `SWC` on connector J2 to the programmer. Note: Always plug in `GND` first! -* You need to power the board by only **ONE** of the following: VCC(3.3v), 5V, or the main power connection (the DC bus). The USB port (J1) does not power the board. -* Run `make flash` in the `Firmware` directory. -__Note__: If you receive the error `can't find target interface/stlink-v2.cfg` or similar, create and set an environment variable named `OPENOCD_SCRIPTS` to the location of the openocd scripts directory. - -If the flashing worked, you can connect to the board using the [odrivetool](getting-started#start-odrivetool). - -

    -## Testing -_Main article: [Testing](testing.md)_ - -

    -## Debugging -If you're using VSCode, make sure you have the Cortex Debug extension, OpenOCD, and the STLink. You can verify that OpenOCD and STLink are working by ensuring you can flash code. Open the ODrive_Workspace.code-workspace file, and start a debugging session (F5). VSCode will pick up the correct settings from the workspace and automatically connect. Breakpoints can be added graphically in VSCode. - -* Run `make gdb`. This will reset and halt at program start. Now you can set breakpoints and run the program. If you know how to use gdb, you are good to go. - -

    -## Setting up an IDE -For working with the ODrive code you don't need an IDE, but the open-source IDE VSCode is recommended. It is also possible to use Eclipse. If you'd like to go that route, please see the respective configuration document: - -* [Configuring VSCode](configuring-vscode.md) -* [Configuring Eclipse](configuring-eclipse.md) - -

    -## STM32CubeMX -This project uses the STM32CubeMX tool to generate startup code and to ease the configuration of the peripherals. You can download it from [here](http://www2.st.com/content/st_com/en/products/development-tools/software-development-tools/stm32-software-development-tools/stm32-configurators-and-code-generators/stm32cubemx.html?icmp=stm32cubemx_pron_pr-stm32cubef2_apr2014&sc=stm32cube-pr2). All CubeMX related files are in `Firmware/Board/v3`. - -You will likely want the pinout for this process. It is available [here](https://docs.google.com/spreadsheets/d/1QXDCs1IRtUyG__M_9WruWOheywb-GhOwFtfPcHuN2Fg/edit#gid=404444347). - -### Maintaining modified generated code -When generating the code, STM32CubeMX will nuke everything except some special sections that they provide. These sections are marked like `USER CODE BEGIN`...`USER CODE END`. -We used to try to make sure all edits we made to the generated code would only go in these sections, so some code structrure may reflect that. -However over time we realized this will not be tenable, so instead we use git to rebase all changes of the generated code whenever we need to regenerate it. -We use two special branches that will help us to do this, they are `STM32CubeMX-start` and `STM32CubeMX-end`. -How to use these is shown in the following example. - -**Note**: Due to how this rebasing is done, all development that changes the generated code should be done directly on `STM32CubeMX-end`, and not based on `devel`, then follow step 4 below to carry them over to your feature branch. If you did some changes to the generated code based from `devel`, you need to cherry pick just those changes over to `STM32CubeMX-end`. - -### 1. Ensuring a clean slate -* We do all changes to the STM32CubeMX config and regenerate the code on top of `STM32CubeMX-start`. - * `git checkout STM32CubeMX-start` -* Run stm32cubeMX and load the `Firmware/Board/v3/Odrive.ioc` project file. - * If the tool asks if you wish to migrate to a new version, choose to download the old firmware package (unless you want to use the latest libraries) -* Without changing any settings, press `Project -> Generate code`. -* You may need to let it download some drivers and such. -* STM32CubeMX may now have a newer version of some of the libraries, so there may be changes to the generated code even though we didn't change any settings. We need to check that everything is still working, and hence check in the changes: -* `git config --local core.autocrlf input` - This will tell git that all files should be checked in with LF endings (CubeMX generates CRLF endings). -* `git diff` - Ignore the pile of line ending warnings. -* If you feel qualified: you can now ispect if CubeMX introduced something stupid. If there were any changes, and they look acceptable, we should commit them: - * `git commit -am "Run STM32CubeMX v1.21"` - Replace with actual version of CubeMX - -### 2. Making changes to the STM32CubeMX config -* After completing the above steps, make sure the working directory is clean: - * `git status` should include "nothing to commit, working tree clean" -* Make your changes in STM32CubeMX, save the project and generate the code. (`Project -> Generate code`) -* `git diff` - Check that the introduced changes are as expected -* If everything looks ok, you can commit your changes. - -### 3. Rebasing the modifications to the generated code -* `git checkout STM32CubeMX-end` -* `git rebase STM32CubeMX-start` -* Make sure the rebase finishes, fixing any conflicts that may arise - -### 4. Merge new STM32CubeMX code to your feature branch -Simply merge the new state at `STM32CubeMX-end` into your feature branch. -* `git checkout your-feature` -* `git merge STM32CubeMX-end` - -### 5. Pushing back upstream -* Generate a PR like normal for your feature. -* Make sure youhave pushed to the `STM32CubeMX-start` and `STM32CubeMX-end` branches on your fork. -* Make a note in your PR to the maintainer that they need to update the STM32CubeMX branches when they merge the PR. - -

    -## Troubleshooting - -### `LIBUSB_ERROR_IO` when flashing with the STLink/v2 - -**Problem:** when I try to flash the ODrive with the STLink using `make flash` I get this error: -``` -Open On-Chip Debugger 0.10.0 -Licensed under GNU GPL v2 -For bug reports, read - http://openocd.org/doc/doxygen/bugs.html -Info : auto-selecting first available session transport "hla_swd". To override use 'transport select '. -Info : The selected transport took over low-level target control. The results might differ compared to plain JTAG/SWD -adapter speed: 2000 kHz -adapter_nsrst_delay: 100 -none separate -Info : Unable to match requested speed 2000 kHz, using 1800 kHz -Info : Unable to match requested speed 2000 kHz, using 1800 kHz -Info : clock speed 1800 kHz -Error: libusb_open() failed with LIBUSB_ERROR_IO -Error: open failed -in procedure 'init' -in procedure 'ocd_bouncer' -``` - -**Solution:** -This happens from time to time. -1. Unplug the STLink and all ODrives from your computer -2. Power off the ODrive you're trying to flash -3. Plug in the STLink into your computer -4. Power on the ODrive -5. Run `make flash` again - -### `Warn : Cannot identify target as a STM32 family.` when flashing using openocd - -**Problem:** When I try to flash ODrive v4.1 with `make flash` then I get: -``` -[...] -** Programming Started ** -auto erase enabled -Info : device id = 0x10006452 -Warn : Cannot identify target as a STM32 family. -Error: auto_probe failed -embedded:startup.tcl:487: Error: ** Programming Failed ** -in procedure 'program' -in procedure 'program_error' called at file "embedded:startup.tcl", line 543 -at file "embedded:startup.tcl", line 487 -``` - -**Solution:** -Compile and install a recent version of openocd from source. The latest official release (0.10.0 as of Nov 2020) doesn't support the STM32F722 yet. -``` -sudo apt-get install libtool libusb-1.0 -git clone https://git.code.sf.net/p/openocd/code openocd -cd openocd/ -./bootstrap -./configure --enable-stlink -make -sudo make install -``` - -## Documentation - -All *.md files in the `docs/` directory of the master branch are served up by GitHub Pages on [this domain](https://docs.odriverobotics.com). - - * Theme: [minimal](https://github.com/pages-themes/minimal) by [orderedlist](https://github.com/orderedlist) - * HTML layout: `docs/_layouts/default.html` - * CSS style: `docs/assets/css/styles.scss` - * Site index: `docs/_data/index.yaml` - -To run the docs server locally: - -```bash -cd docs -gem install bundler # The gem command typically comes with a Ruby installation -#export PATH="$PATH:~/.gem/ruby/2.7.0/bin" # or similar (depends on OS) -rm Gemfile.lock # only if below commands cause trouble -bundle config path ruby-bundle -bundle install -mkdir -p _api _includes -python ../Firmware/interface_generator_stub.py --definitions ../Firmware/odrive-interface.yaml --template _layouts/api_documentation_template.j2 --outputs _api/'#'.md && python ../Firmware/interface_generator_stub.py --definitions ../Firmware/odrive-interface.yaml --template _layouts/api_index_template.j2 --output _includes/apiindex.html -bundle exec jekyll serve --incremental --host=0.0.0.0 -``` - -On Ubuntu 18.04, prerequisites are: `ruby ruby-dev zlib1g-dev`. - -## Modifying libfibre - -If you need to modify libfibre add `CONFIG_BUILD_LIBFIBRE=true` to your tup.config and rerun `make`. After this you can start `odrivetool` (on your local PC) and it will use the updated libfibre. - -To cross-compile libfibre for the Raspberry Pi, run `make libfibre-linux-armhf` or `make libfibre-all`. This will require a docker container. See [fibre-cpp readme](../Firmware/fibre-cpp/README.md) for details. - -docker run -it -v "$(pwd)":/build -v /tmp/build:/build/build -w /build fibre-compiler configs/linux-armhf.config - -If you're satisfied with the changes don't forget to generate binaries for all -supported systems using `make libfibre-all`. - -## Releases - -We use GitHub Releases to provide firmware releases. - -1. Cut off the changelog to reflect the new release -2. Merge the release candidate into master. -3. Push a (lightweight) tag to the master branch. Follow the existing naming convention. -4. If you changed something in libfibre, regenerate the binaries using `make libfibre-all`. See [Modifying libfibre](#modifying-libfibre) for details. -5. Push the python tools to PyPI (see setup.py for details). -6. Edit the release on GitHub to add a title and description (copy&paste from changelog). - -## Other code maintenance notes -The cortex M4F processor has hardware single precision float unit. However double precision operations are not accelerated, and hence should be avoided. The following regex is helpful for cleaning out double constants: -find: `([-+]?[0-9]+\.[0-9]+(?:[eE][-+]?[0-9]+)?)([^f0-9e])` -replace: `\1f\2` - -

    - -## Notes for Contributors -In general the project uses the [Google C++ Style Guide](https://google.github.io/styleguide/cppguide.html), with a few exceptions: - - - The default indentation is 4 spaces. - - The 80 character limit is not very strictly enforced, merely encouraged. - - The file extensions *.cpp and *.hpp are used instead of *.cc and *.h. - -Your help is welcome! However before you start working on a feature/change that will take you a non-negligible amount of time and that you plan to upstream please discuss your plans with us on GitHub or Discord. This will ensure that your implementation is in line with the direction that ODrive is going. - -When filing a PR please go through this checklist: - - - Make sure you adhere to the same coding style that we use (see note above). - - Update CHANGELOG.md. - - If you removed/moved/renamed things in `odrive-interface.yaml` make sure to add corresponding bullet points tp the "API migration notes" section in the changelog. Use git to compare against the `devel` branch. - - Also, for each removed/moved/renamed API item use your IDE's search feature to search for occurrences of this name. Update the places you found (this will usually be documentation and test scripts). - - If you added things to `odrive-interface.yaml` make sure the new things have decent documentation in the YAML file. We don't expect 100% coverage but use good sense of what to document. - - Make sure your PR doesn't contain spurious changes that unnecessarily add or remove whitespace. These add noise and make the reviewer's lifes harder. - - If you changed any enums in `odrive-interface.yaml`, make sure you update [enums.py](../tools/odrive/enums.py) and [ODriveEnums.h](../Arduino/ODriveArduino/ODriveEnums.h). The file includes instructions on how to do this. Check the diff to verify that none of the existing enumerators changed their value. diff --git a/docs/reStructuredText/developer-guide.rst b/docs/developer-guide.rst similarity index 100% rename from docs/reStructuredText/developer-guide.rst rename to docs/developer-guide.rst diff --git a/docs/encoders.md b/docs/encoders.md deleted file mode 100644 index 988c6080..00000000 --- a/docs/encoders.md +++ /dev/null @@ -1,210 +0,0 @@ -# Encoders - -## Known and Supported Encoders -Be sure to read the [ODrive Encoder Guide](https://docs.google.com/spreadsheets/d/1OBDwYrBb5zUPZLrhL98ezZbg94tUsZcdTuwiVNgVqpU). - -## Encoder Calibration -All encoder types supported by ODrive require that you do some sort of encoder calibration. This requires the following: -* Selecting an encoder and mounting it to your motor -* Choosing an interface (e.g., AB, ABI or SPI) -* Connecting the pins to the odrive -* Loading the correct odrive firmware (the default will work in many cases) -* Motor calibration -* Saving the settings in the odrive for correct bootup - -### Encoder without index signal -During encoder offset calibration the rotor must be allowed to rotate without any biased load during startup. That means mass and weak friction loads are fine, but gravity or spring loads are not okay. - -In the `odrivetool`, type `.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION` Enter. - -To verify everything went well, check the following variables: - - * `.error` should be 0. - * `.encoder.config.phase_offset` - This should print a number, like -326 or 1364. - * `.encoder.config.direction` - This should print 1 or -1. - -### Encoder with index signal -If you have an encoder with an index (Z) signal, you can avoid doing the offset calibration on every startup, and instead use the index signal to re-sync the encoder to a stored calibration. - -Below are the steps to do the one-time calibration and configuration. Note that you can follow these steps with one motor at a time, or all motors together, as you wish. - -* Since you will only do this once, it is recommended that you mechanically disengage the motor from anything other than the encoder, so that it can spin freely. -* Set `.encoder.config.use_index` to `True`. -* Run `.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH`. This will make the motor turn in one direction until it finds the encoder index. -* Follow the calibration instructions for an [encoder without index signal](#encoder-without-index-signal). -* Set `.encoder.config.pre_calibrated` to `True` to confirm that the offset is valid with respect to the index pulse. -* If you would like to search for the index at startup, set `.config.startup_encoder_index_search` to `True`. - * If you'd rather do it manually, just run `.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH` on every bootup. -* If you are looking to start your machine as quickly as possible on bootup, also set `.motor.config.pre_calibrated` to `True` to save the current motor calibration and avoid doing it again on bootup. -* Save the configuration by typing `.save_configuration()` Enter. - -That's it, now on every reboot the motor will turn in one direction until it finds the encoder index. - -* If your motor has problems reaching the index location due to the mechanical load, you can increase `.motor.config.calibration_current`. - -### Reversing index search -Sometimes you would like the index search to only happen in a particular direction (the reverse of the default). Instead of swapping the motor leads, you can ensure that the following three values are negative: -* `.config.calibration_lockin.vel` -* `.config.calibration_lockin.accel` -* `.config.calibration_lockin.ramp_distance` - - -*IMPORTANT:* Your motor should find the same rotational position when the ODrive performs an index search if the index signal is working properly. This means that the motor should spin, and stop at the same position if you have set .config.startup_encoder_index_search so the search starts on reboot, or you if call the command:.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH after reboot. You can test this. Send the reboot() command, and while it's rebooting turn your motor, then make sure the motor returns back to the correct position each time when it comes out of reboot. Try this procedure a couple of times to be sure. - -### Hall Effect Encoders -Hall effect encoders can also be used with ODrive. The encoder CPR should be set to `6 * <# of motor pole pairs>`. Due to the low resolution of hall effect encoders compared to other types of encoders, low speed performance will be worse than other encoder types. - -When the encoder mode is set to hall feedback, the pinout on the encoder port is as follows: - -| Label on ODrive | Hall feedback | -|-----------------|---------------| -| A | Hall A | -| B | Hall B | -| Z | Hall C | - -To use hall effect encoders, the calibration sequence is different than incremental or absolute encoders. You must first run `AXIS_STATE_ENCODER_HALL_POLARITY_CALIBRATION` before `AXIS_STATE_ENCODER_OFFSET_CALIBRATION` The hall polarity calibration will automatically determine the order and polarity of the hall signals. When using `AXIS_STATE_FULL_CALIBRATION_SEQUENCE`, these steps are automatically used if the encoder is set to hall mode. - -### Startup sequence notes -The following are variables that MUST be set up for your encoder configuration. Your values will vary depending on your encoder: - -* `.encoder.config.cpr = 8192` -* `.encoder.config.mode = ENCODER_MODE_INCREMENTAL` - -The following are examples of values that can impact the success of calibration. These are not all of the variables you have to set for startup. Only change these when you understand why they are needed; your values will vary depending on your setup: -* `.motor.config.motor_type = MOTOR_TYPE_HIGH_CURRENT` The type of motor you have. Valid choices are high current or gimbal. -* `.encoder.config.calib_range = 0.05` Helps to relax the accuracy of encoder counts during calibration -* `.motor.config.calibration_current = 10.0` The motor current used for calibration. For large motors, this value can be increased to overcome friction and cogging. -* `.motor.config.resistance_calib_max_voltage = 12.0` Max motor voltage used for measuring motor resistance. For motor calibration, it must be possible for the motor current to reach the calibration current without the applied voltage exceeding this config setting. -* `.controller.config.vel_limit = 5` [turn/s] low values result in the spinning motor stopping abruptly during calibration - -Lots of other values can get you. It's a process. Thankfully there are a lot of good people that will help you debug calibration problems. - -If calibration works, congratulations. - -Now try: -* `.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL` -* `.controller.input_vel = 1.5` -let it loop a few times and then set: -* `.requested_state = AXIS_STATE_IDLE` - -Do you still have no errors? Awesome. Now, setup the motor and encoder to use known calibration values. This allows you to skip motor calibration and encoder offset calibration before using closed loop control. Note that this only works if you are using an absolute encoder or the encoder index input (see "Encoder with index signal" above). -* `.encoder.config.pre_calibrated = True` -* `.motor.config.pre_calibrated = True ` - -And see if ODrive agrees that the calibration worked by just running -* `.encoder.config.pre_calibrated` - -(using no "= True" ). Make sure that 'pre_calibrated' is in fact True. - -Also, if you have calibrated and encoder.pre_calibrated is equal to true, and you had no errors so far, run this: -* `odrv0.save_configuration()` -* `odrv0.reboot()` - -and now see if after a reboot you can run: -* `.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH` - -without getting errors. - -## What happens if calibration fails -There are subtle ways that encoder problems will impact your ODrive. For example, ODrive may not complete the calibrate sequence when you go to: -* `.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE` - -Or, ODrive may complete the calibrate sequence after: -* `.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE` - -but then it fails after you go to: -* `.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL` - -Or ODrive may just vibrate in an entertaining way. See: -https://www.youtube.com/watch?v=gaRUmwvSyAs - -## Encoder Testing -There are things you can test to make sure your encoder is properly connected. `shadow_count` tracks encoder motion, even before the encoder or motor are calibrated. If your encoder is working, you should see this value change when you turn the motor. -Run the command: -* `.encoder.shadow_count ` - -and look at your value. Then turn your motor by hand and see if that value changes. Also, notice that the command: -* `.encoder.config.cpr = 4000` - -must reflect the number of counts ODrive receives after one complete turn of the motor. So use shadow_count to test if that is working properly. - -You will probably never be able to properly debug if you have problems unless you use an oscilloscope. If you have one, try the following: -Connect to the AB pins, see if you get square waves as you turn the motor. -Connect to the I pin, see if you get a pulse on a complete rotation. Sometimes this is hard to see. - -If you are using SPI, use a logic analyzer and connect to the CLK, MISO, and CS pins. Set a trigger for the CS pin and ensure that the encoder position is being sent and is increasing/decreasing as you spin the motor. There is extremely cheap hardware that is supported by [Sigrok](https://sigrok.org/) for protocol analysis. - - -## Encoder Noise -Noise is found in all circuits, life is just about figuring out if it is preventing your system from working. Lots of users have no problems with noise interfering with their ODrive operation, others will tell you "_I've been using the same encoder as you with no problems_". Power to 'em, that may be true, but it doesn't mean it will work for you. If you are concerned about noise, there are several possible sources: - -* Importantly, encoder wires may be too close to motor wires, avoid overlap as much as possible -* Long wires between encoder and ODrive -* Use of ribbon cable - -The following _might_ mitigate noise problems. Use shielded cable, or use twisted pairs, where one side of each twisted pair is tied to ground and the other side is tied to your signal. If you are using SPI, use a 20-50 ohm resistor in series on CLK, which is more susceptible noise. - -If you are using an encoder with an index signal, another problem that has been encountered is noise on the Z input of ODrive. Symptoms for this problem include: -* difficulty with requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE, where your calibration sequence may not complete -* strange behavior after performing odrv0.save_configuration() and odrv0.reboot() -* when performing an index_search, the motor does not return to the same position each time. -One easy step that _might_ fix the noise on the Z input is to solder a 22nF-47nF capacitor to the Z pin and the GND pin on the underside of the ODrive board. - -## Hall feedback pinout -If position accuracy is not a concern, you can use A/B/C hall effect encoders for position feedback. - -To use this mode, configure the corresponding encoder mode: `.config.mode = ENCODER_MODE_HALL`. Configure the corresponding GPIOs as digital inputs: - -For encoder 0: - - .config.gpio9_mode = GPIO_MODE_DIGITAL - .config.gpio10_mode = GPIO_MODE_DIGITAL - .config.gpio11_mode = GPIO_MODE_DIGITAL - -For encoder 1: - - .config.gpio12_mode = GPIO_MODE_DIGITAL - .config.gpio13_mode = GPIO_MODE_DIGITAL - .config.gpio14_mode = GPIO_MODE_DIGITAL - -In this mode, the pinout on the encoder port is as follows: - -| Label on ODrive | Hall feedback | -|-----------------|---------------| -| A | Hall A | -| B | Hall B | -| Z | Hall C | - -## SPI Encoders - -Apart from (incremental) quadrature encoders, ODrive also supports absolute SPI encoders (since firmware v0.5). These usually measure an absolute angle. This means you don't need to repeat the encoder calibration after every ODrive reboot. Currently, the following modes are supported: - - * **CUI protocol**: Compatible with the AMT23xx family (AMT232A, AMT232B, AMT233A, AMT233B). - * **AMS protocol**: Compatible with AS5047P and AS5048A. - -Some of these chips come with evaluation boards that can simplify mounting the chips to your motor. For our purposes if you are using an evaluation board you should select the settings for 3.3v. - -**Note:** The AMT23x family has a hardware bug that causes them to not properly tristate the MISO line. To use them with ODrive, there are two workarounds. One is to sequence power to the encoder a second or two after the ODrive recieves power. This allows 1 encoder to be used without issue. Another solution is to add a tristate buffer, such as the 74AHC1G125SE, on the MISO line between the ODrive and each AMT23x encoder. Tie the enable pin on the buffer to the CS line for the respective encoder. This allows for more than one AMT23x encoder, or one AMT23x and another SPI encoder, to be used at the same time. - -1. Connect the encoder to the ODrive's SPI interface: - - - The encoder's SCK, MISO (aka "DATA" on CUI encoders), MOSI (if present on the encoder), GND and 3.3V should connect to the ODrive pins with the same label. If you want to save a wire with AMS encoders, you can also connect the encoder's MOSI to the encoder's VDD instead. - - The encoder's Chip Select (aka nCS/CSn) can be connected to any of the ODrive's GPIOs (caution: GPIOs 1 and 2 are usually used by UART). - -If you are having calibration problems, make sure that your magnet is centered on the axis of rotation on the motor. Some users report that this has a significant impact on calibration. Also make sure that your magnet height is within range of the spec sheet. - -2. In `odrivetool`, run: - - .encoder.config.abs_spi_cs_gpio_pin = 4 # or which ever GPIO pin you choose - .encoder.config.mode = ENCODER_MODE_SPI_ABS_CUI # or ENCODER_MODE_SPI_ABS_AMS - .encoder.config.cpr = 2**14 # or 2**12 for AMT232A and AMT233A - .save_configuration() - .reboot() - -3. Run the [offset calibration](#encoder-without-index-signal) and then save the calibration with `.save_configuration()`. - The next time you reboot, the encoder should be immediately ready. - -Sometimes the encoder takes longer than the ODrive to start, in which case you need to clear the errors after every restart. - -If you are having calibration problems - make sure your magnet is centered on the axis of rotation on the motor, some users report this has a significant impact on calibration. Also make sure your magnet height is within range of the spec sheet. - diff --git a/docs/reStructuredText/encoders.rst b/docs/encoders.rst similarity index 100% rename from docs/reStructuredText/encoders.rst rename to docs/encoders.rst diff --git a/docs/endstops.md b/docs/endstops.md deleted file mode 100644 index b43b682c..00000000 --- a/docs/endstops.md +++ /dev/null @@ -1,142 +0,0 @@ -# Endstops and Homing - -By default, the ODrive assumes that your motor encoder's zero position is the same as your machine's zero position, but in real life this is rarely the case. In these systems it is useful to allow your motor to move until a physical or electronic device orders the system to stop. That `endstop` can be used as a known reference point. Once the ODrive has hit that position it may then want to move to a final zero, or `home`, position. The process of finding your machine's zero position is known as `homing`. - -ODrive supports the use of its GPIO pins to connect to phyiscal limit switches or other sensors that can serve as endstops. Before you can home your machine, you must be able to adequately control your motor in `AXIS_STATE_CLOSED_LOOP_CONTROL`. - ---- - -## Endstop Configuration -Each axis supports two endstops: `min_endstop` and `max_endstop`. For each endstop, the following properties are accessible through `odrivetool`: - -Name | Type | Default ---- | -- | -- -gpio_num | int | 0 -offset | float | 0.0 -debounce_ms | float | 50.0 -enabled | boolean | false -is_active_high | boolean | false - -### gpio_num -The GPIO pin number, according to the silkscreen labels on ODrive. Set with these commands: -``` -..max_endstop.config.gpio_num = <1, 2, 3, 4, 5, 6, 7, 8> -..min_endstop.config.gpio_num = <1, 2, 3, 4, 5, 6, 7, 8> -``` - -### enabled -Enables/disables detection of the endstop. If disabled, homing and e-stop cannot take place. Set with: -``` -..max_endstop.config.enabled = -..min_endstop.config.enabled = -``` - -### offset -This is the position of the endstops on the relevant axis, in turns. For example, if you want a position command of `0` to represent a position 3 turns away from the endstop, the offset would be `-3.0` (because the endstop is located at axis position `-3.0`). - -``` -..min_endstop.config.offset = -``` - -This setting is only used for homing. Only the offset of the `min_endstop` is used. - -### debounce_ms -The debouncing time for this endstop. Most switches exhibit some sort of bounce, and this setting will help prevent the switch from triggering repeatedly. It works for both HIGH and LOW transitions, regardless of the setting of `is_active_high`. Debouncing is a good practice for digital inputs, read up on it [here](https://en.wikipedia.org/wiki/Switch). `debounce_ms` has units of miliseconds. - -``` -..max_endstop.config.debounce_ms = -..min_endstop.config.debounce_ms = -``` - -### is_active_high -This is how you configure the endstop to be either "NPN" or "PNP". An "NPN" configuration would be `is_active_high = False` whereas a PNP configuration is `is_active_high = True`. Refer to the following table for more information: - -Typically configuration **1** or **3** is preferred when using mechanical switches as the most common failure mode leaves the switch open. - -### GPIO configuration -The GPIOs that are used for the endstops need to be configured according to the diagram below. - -Assuming your endstop is connected to GPIO X: - - - Configuration 1, 2: `.config.gpioX_mode = GPIO_MODE_DIGITAL_PULL_DOWN` - - Configuration 3, 4: `.config.gpioX_mode = GPIO_MODE_DIGITAL_PULL_UP` - -![Endstop configuration](Endstop_configuration.png) - - -### Example - -If we want to configure a 3D printer-style (configuration 4) minimum endstop for homing on GPIO 5 and we want our motor to move away from the endstop about a quarter turn, we would set: - -``` -.config.gpio5_mode = GPIO_MODE_DIGITAL -..min_endstop.config.gpio_num = 5 -..min_endstop.config.is_active_high = False -..min_endstop.config.offset = -0.25 -..min_endstop.config.enabled = True -.config.gpio5_mode = GPIO_MODE_DIGITAL_PULL_UP -``` - -### Testing The Endstops -Once the endstops are configured you can test your endstops for correct functionality. Try activating your endstops and check the states of these variables through odrivetool: - -``` -..max_endstop.endstop_state -..min_endstop.endstop_state -``` - -A state of `True` means the switch is pressed. A state of `False` means the switch is NOT pressed. As simple as that. Give it a try. Click your switches, or put a magnet on your hall switch and see if the states change. - -After testing, don't forget to save and reboot: -``` -.save_configuration() -``` - ---- - -## Homing Configuration -There is one additional configuration parameter in `controller.config` specifically for the homing process: - -Name | Type | Default ---- | -- | -- -homing_speed | float | 0.25f - -`homing_speed` is the axis travel speed during homing, in [turns/second]. If you are using SPI based encoders and the axis is homing in the wrong direction, you can enter a negative value for the homing speed and a negative value for the minimum endstop offset. - -``` -# Set the homing speed to 0.25 turns / sec -odrv0.axis0.controller.config.homing_speed = 0.25 -``` - -### Performing the Homing Sequence -Homing is possible once the ODrive has closed-loop control over the axis. To trigger homing, we must enter `AXIS_STATE_HOMING`. This starts the homing sequence, which works as follows: - -1. The axis switches to `INPUT_MODE_VEL_RAMP` -2. The axis ramps up to `homing_speed` in the direction of `min_endstop` -3. The axis presses the `min_endstop` -4. The axis switches to `INPUT_MODE_TRAP_TRAJ` -5. The axis moves to the home position in a controlled manner - -It requires quite a few settings in addition to the endstop settings: - -``` -..controller.config.vel_ramp_rate -..trap_traj.config.vel_limit -..trap_traj.config.accel_limit -..trap_traj.config.decel_limit -``` - -We realize this is a little excessive and we will work towards minimizing the setup, but this works well for smooth and reliable behaviour for now. - -### Homing at Startup -It is possible to configure the odrive to enter homing immediately after startup. To enable homing at startup, the following must be configured: - -``` -..config.startup_homing = True -``` - -## Additional endstop devices - -In addition to phyiscal switches there are other options for wiring up your endstops - you will have to work out the details of connecting your device but here are some suggested approaches: - -![endstop figure](endstop_figure.png) diff --git a/docs/reStructuredText/endstops.rst b/docs/endstops.rst similarity index 100% rename from docs/reStructuredText/endstops.rst rename to docs/endstops.rst diff --git a/docs/exts/fibre_autodoc.py b/docs/exts/fibre_autodoc.py index 15031e4c..9c8661e8 100644 --- a/docs/exts/fibre_autodoc.py +++ b/docs/exts/fibre_autodoc.py @@ -49,8 +49,8 @@ class MethodDocumenter(Documenter): return [ '', '.. py:method:: ' + method.name + '(' + in_str + ')' + out_str, - *(['', ' ' + method.brief] if method.brief else []), - *(['', ' ' + method.doc] if method.doc else []), + *(['', *add_indent(method.brief.split('\n'))] if method.brief else []), + *(['', *add_indent(method.doc.split('\n'))] if method.doc else []), '', *((' :param ' + registry.get_py_val_type_name(decl_ns_path, arg.type) + ' ' + arg.name + ':' + (' ' + arg.doc if arg.doc else '')) for arg in method.input_args), '', @@ -65,8 +65,8 @@ class AttributeDocumenter(Documenter): '', '.. py:attribute:: ' + attr.name, ' :type: ' + registry.get_py_ref_type_name(decl_ns_path, attr.type), - *(['', ' ' + attr.brief] if attr.brief else []), - *(['', ' ' + attr.doc] if attr.doc else []), + *(['', *add_indent(attr.brief.split('\n'))] if attr.brief else []), + *(['', *add_indent(attr.doc.split('\n'))] if attr.doc else []), '' ] @@ -197,6 +197,9 @@ class FibredocDirective(SphinxDirective): documenter = documenters[objtype]() registry = self.env.app.fibre_registry + + for file in self.config.fibre_interface_files: + self.env.note_dependency(file) decl_ns, obj = documenter.load_object(registry, self.arguments[0]) lines = documenter.generate(registry, decl_ns.get_path()[:2], obj, self.options) diff --git a/docs/favicon.ico b/docs/favicon.ico deleted file mode 100644 index d34cd931..00000000 Binary files a/docs/favicon.ico and /dev/null differ diff --git a/docs/reStructuredText/fibre_types/com_odriverobotics_ODrive.rst b/docs/fibre_types/com_odriverobotics_ODrive.rst similarity index 100% rename from docs/reStructuredText/fibre_types/com_odriverobotics_ODrive.rst rename to docs/fibre_types/com_odriverobotics_ODrive.rst diff --git a/docs/figure_1-1.png b/docs/figure_1-1.png deleted file mode 100644 index 036ca262..00000000 Binary files a/docs/figure_1-1.png and /dev/null differ diff --git a/docs/figure_1.png b/docs/figure_1.png deleted file mode 100644 index 4289544d..00000000 Binary files a/docs/figure_1.png and /dev/null differ diff --git a/docs/reStructuredText/figures/CAN_Bus_Drawing.png b/docs/figures/CAN_Bus_Drawing.png similarity index 100% rename from docs/reStructuredText/figures/CAN_Bus_Drawing.png rename to docs/figures/CAN_Bus_Drawing.png diff --git a/docs/reStructuredText/figures/CodeAsMakefile.png b/docs/figures/CodeAsMakefile.png similarity index 100% rename from docs/reStructuredText/figures/CodeAsMakefile.png rename to docs/figures/CodeAsMakefile.png diff --git a/docs/Endstop_configuration.png b/docs/figures/Endstop_configuration.png similarity index 100% rename from docs/Endstop_configuration.png rename to docs/figures/Endstop_configuration.png diff --git a/docs/reStructuredText/figures/ImportLaunch.png b/docs/figures/ImportLaunch.png similarity index 100% rename from docs/reStructuredText/figures/ImportLaunch.png rename to docs/figures/ImportLaunch.png diff --git a/docs/reStructuredText/figures/LaunchConfigFilter.png b/docs/figures/LaunchConfigFilter.png similarity index 100% rename from docs/reStructuredText/figures/LaunchConfigFilter.png rename to docs/figures/LaunchConfigFilter.png diff --git a/docs/reStructuredText/figures/ODriveBasicWiring.png b/docs/figures/ODriveBasicWiring.png similarity index 100% rename from docs/reStructuredText/figures/ODriveBasicWiring.png rename to docs/figures/ODriveBasicWiring.png diff --git a/docs/TrapTrajPosVel.PNG b/docs/figures/TrapTrajPosVel.PNG similarity index 100% rename from docs/TrapTrajPosVel.PNG rename to docs/figures/TrapTrajPosVel.PNG diff --git a/docs/reStructuredText/figures/can-protocol.csv b/docs/figures/can-protocol.csv similarity index 100% rename from docs/reStructuredText/figures/can-protocol.csv rename to docs/figures/can-protocol.csv diff --git a/docs/controller_with_ff.png b/docs/figures/controller_with_ff.png similarity index 100% rename from docs/controller_with_ff.png rename to docs/figures/controller_with_ff.png diff --git a/docs/endstop_figure.png b/docs/figures/endstop_figure.png similarity index 100% rename from docs/endstop_figure.png rename to docs/figures/endstop_figure.png diff --git a/docs/ground_loop_bad.png b/docs/figures/ground_loop_bad.png similarity index 100% rename from docs/ground_loop_bad.png rename to docs/figures/ground_loop_bad.png diff --git a/docs/ground_loop_fix.png b/docs/figures/ground_loop_fix.png similarity index 100% rename from docs/ground_loop_fix.png rename to docs/figures/ground_loop_fix.png diff --git a/docs/reStructuredText/figures/liveplotter-iq-omega.png b/docs/figures/liveplotter-iq-omega.png similarity index 100% rename from docs/reStructuredText/figures/liveplotter-iq-omega.png rename to docs/figures/liveplotter-iq-omega.png diff --git a/docs/reStructuredText/figures/liveplotter-pos-estimate.png b/docs/figures/liveplotter-pos-estimate.png similarity index 100% rename from docs/reStructuredText/figures/liveplotter-pos-estimate.png rename to docs/figures/liveplotter-pos-estimate.png diff --git a/docs/reStructuredText/figures/mech_dimensions.png b/docs/figures/mech_dimensions.png similarity index 100% rename from docs/reStructuredText/figures/mech_dimensions.png rename to docs/figures/mech_dimensions.png diff --git a/docs/reStructuredText/figures/pinout.csv b/docs/figures/pinout.csv similarity index 100% rename from docs/reStructuredText/figures/pinout.csv rename to docs/figures/pinout.csv diff --git a/docs/reStructuredText/figures/secondOrderResponse.PNG b/docs/figures/secondOrderResponse.PNG similarity index 100% rename from docs/reStructuredText/figures/secondOrderResponse.PNG rename to docs/figures/secondOrderResponse.PNG diff --git a/docs/reStructuredText/figures/stlink-wiring.jpg b/docs/figures/stlink-wiring.jpg similarity index 100% rename from docs/reStructuredText/figures/stlink-wiring.jpg rename to docs/figures/stlink-wiring.jpg diff --git a/docs/reStructuredText/figures/thermistor-voltage-divider.png b/docs/figures/thermistor-voltage-divider.png similarity index 100% rename from docs/reStructuredText/figures/thermistor-voltage-divider.png rename to docs/figures/thermistor-voltage-divider.png diff --git a/docs/getting-started.md b/docs/getting-started.md deleted file mode 100644 index 5d4a48a6..00000000 --- a/docs/getting-started.md +++ /dev/null @@ -1,319 +0,0 @@ ---- -redirect_from: - - /getting-started -permalink: / ---- - -# Getting Started - -### Table of contents - - -- [Getting Started](#getting-started) - - [Hardware Requirements](#hardware-requirements) - - [Wiring up the ODrive](#wiring-up-the-odrive) - - [Downloading and Installing Tools](#downloading-and-installing-tools) - - [Firmware](#firmware) - - [Start `odrivetool`](#start-odrivetool) - - [Debugging](#debugging) - - [Configure M0](#configure-m0) - - [Position control of M0](#position-control-of-m0) - - [Other control modes](#other-control-modes) - - [Watchdog Timer](#watchdog-timer) - - [What's next?](#whats-next) - - [Upgrading from 0.4.12](#upgrading-from-0412) - - - -## Hardware Requirements - -### You will need: -* One or two [brushless motors](https://docs.google.com/spreadsheets/d/12vzz7XVEK6YNIOqH0jAz51F5VUpc-lJEs3mmkWP1H4Y). It is fine, even recommended, to start testing with just a single motor and encoder. -* One or two [encoder(s)](https://docs.google.com/spreadsheets/d/1OBDwYrBb5zUPZLrhL98ezZbg94tUsZcdTuwiVNgVqpU) -* A power resistor. A good starting point would be the 50W resistor included with your ODrive. -
    Do I really need a power resistor? What values to choose?
    - - If you don't have a brake resistor, the ODrive will pump excess power back into the power supply during deceleration to achieve the desired deceleration torque. If your power supply doesn't eat that power (which it won't if it's not a battery), the bus voltage will inevitebly rise. If you're unlucky this will break the power supply. - At some point, the ODrive's overvoltage protection will trip, after which both motors will be allowed to spin freely. Depending on your machine, this may or may not be a problem. - - The power resistor values you need depends on your motor setup, and peak/average deceleration power. - - To be on the safe side, think about what speed and current limits you want to set for the motor. - - When braking at max speed and with maximum motor current, the power that is dissipated in the power resistor can be calulated as: `P_brake = V_emf * I_motor` where `V_emf = motor_rpm / motor_kv`. - -
    - -* A power supply (12V-24V for the 24V board variant, 12V-56V for the 56V board variant). A battery is also fine. Some advice on choosing a power supply can be found [here](https://things-in-motion.blogspot.com/2018/12/how-to-select-right-power-source-for.html). -
    What voltage variant do I have?
    - On all ODrives shipped July 2018 or after have a silkscreen label clearly indicating the voltage variant. - - ODrives before this may or may not have this label. If you don't have a label, then you can look at the bus capacitors (8 gray cylinder components on the underside of the board). If they read 470uF, you have a 24V version; if they read 120uF you have a 48V version. -
    - -## Wiring up the ODrive -
    -Firmware, software, and documentation is intended for use with ODrive motor controllers purchased from odriverobotics.com. ODrive Robotics does not sell products through any channel other than odriverobotics.com. We do not provide support for ODrives purchased elsewhere. -
    -
    -Make sure you have a good mechanical connection between the encoder and the motor, slip can cause disastrous oscillations or runaway. -
    - -All non-power I/O is 3.3V output and 5V tolerant on input, on ODrive v3.3 and newer. - -### Wiring up the motors -* Connect the motor phases into the 3-phase screw terminals. It is not recommended to use a clip-on connector such as an alligator clip, as this can cause issues with the phase resistance/inductance measurements. - -### Wiring up the encoders -Connect the encoder(s) to J4. The A,B phases are required, and the Z (index pulse) is optional. The A,B and Z lines have 3.3k pull up resistors, for use with open-drain encoder outputs. For single ended push-pull signals with weak drive current (\<4mA), you may want to desolder the pull-ups. - -![Image of ODrive all hooked up](https://docs.google.com/drawings/d/e/2PACX-1vTpJziAisrkvV1kTL4vckAJkmJ-BAvTwN1GeZZNCNwpTHv47Cf8bpz-gJqK2Z3un6FCHT4E-rcuUg6c/pub?w=1716&h=1281) - -### Safety & Power UP -
    - Always think safety before powering up the ODrive if motors are attached. Consider what might happen if the motor spins as soon as power is applied. -
    - -* Unlike some devices, the ODrive does not recieve power over the USB port so the 24/56 volt power input is required even just to communicate with it using USB. It is ok to power up the ODrive before or after connecting the USB cable. - -* To power up the ODrive, connect the power source to the DC terminals. Make sure to pay attention to the polarity. Try to connect the power source first and then turn it on to avoid inrush current. If this can't be avoided then a small spark is normal. This is caused by the capacitors charging up. - -* Make sure to avoid a ground loop! See the [ground loop page](ground-loops.md) for details. - -## Downloading and Installing Tools -Most instructions in this guide refer to a utility called `odrivetool`, so you should install that first. - -### Windows -1. Install Python 3. We recommend the Anaconda distribution because it packs a lot of useful scientific tools, however you can also install the standalone python. - * __Anaconda__: Download the installer from [here](https://www.anaconda.com/download/#windows). Execute the downloaded file and follow the instructions. - * __Standalone Python__: Download the installer for 3.8.6 from [here](https://www.python.org/downloads/release/python-386/). Execute the downloaded file and follow the instructions. As of Oct 2020, Matplotlib (required by odrivetool) had not been updated to work with 3.9, so please use 3.8.6. - * If you have Python 2 installed alongside Python 3, replace `pip` by `C:\Users\YOUR_USERNAME\AppData\Local\Programs\Python\Python36-32\Scripts\pip`. If you have trouble with this step then refer to [this walkthrough](https://www.youtube.com/watch?v=jnpC_Ib_lbc). -2. Launch the command prompt. - * __Anaconda__: In the start menu, type `Anaconda Prompt` Enter - * __Standalone Python__: In the start menu, type `cmd` Enter -3. Install the ODrive tools by typing `pip install --upgrade odrive` Enter - - -### OSX -We are going to run the following commands for installation in Terminal. -1. If you don't already have it, install homebrew: -```bash -/usr/bin/ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)" -``` -2. Install python: -```bash -brew install python -``` -3. If you get the error: `Error: python 2.7.14_2 is already installed`, then upgrade to Python 3 by running: -```bash -brew upgrade python -``` -4. The odrive tools uses libusb to communicate to the ODrive: -```bash -brew install libusb -``` -5. Now that you have Python 3 and all the package managers, run: -```bash -pip3 install --upgrade odrive -``` - -__Troubleshooting__ -1. Permission Errors: Just run the previous command in sudo - ```bash - sudo pip3 install --upgrade odrive - ``` - -2. Dependency Errors: If the installer doesn't complete and you get a dependency -error (Ex. "No module..." or "module_name not found") - ```bash - sudo pip3 install module_name - ``` - Try step 5 again - -3. Other Install Errors: If the installer fails at installing dependencies, try - ```bash - sudo pip3 install odrive --no-deps - ``` - If you do this, brace yourself for runtime errors when you run `odrivetool` (the basic functionality should work though). - - -### Linux -1. [Install Python 3](https://www.python.org/downloads/). (for example, on Ubuntu, `sudo apt install python3 python3-pip`) -2. Install the ODrive tools by opening a terminal and typing `sudo pip3 install --upgrade odrive` Enter - * This should automatically add the udev rules. If this fails for some reason you can add them manually: - ```bash - echo 'SUBSYSTEM=="usb", ATTR{idVendor}=="1209", ATTR{idProduct}=="0d[0-9][0-9]", MODE="0666"' | sudo tee /etc/udev/rules.d/91-odrive.rules - sudo udevadm control --reload-rules - sudo udevadm trigger - ``` -3. **Ubuntu**, **Raspbian**: If you can't invoke `odrivetool` at this point, try adding `~/.local/bin` to your `$PATH` ([see related bug](https://unix.stackexchange.com/a/392710/176715)). This is done for example by running `nano ~/.bashrc`, scrolling to the bottom, pasting `export PATH=$PATH:~/.local/bin`, and then saving and closing, and close and reopen the terminal window. - -## Firmware -**ODrive v3.5 and later**
    -Your board should come preflashed with firmware. If you run into problems, follow the instructions [here](odrivetool.md#device-firmware-update) on the DFU procedure before you continue. - -**ODrive v3.4 and earlier**
    -Your board does **not** come preflashed with any firmware. Follow the instructions [here](odrivetool.md#device-firmware-update) on the ST Link procedure before you continue. - -## Start `odrivetool` -To launch the main interactive ODrive tool, type `odrivetool` Enter. Connect your ODrive and wait for the tool to find it. If it doesn't connect after a few seconds refer to the [troubleshooting page](troubleshooting.md#usb-connectivity-issues). Now you can, for instance type `odrv0.vbus_voltage` Enter to inpect the boards main supply voltage. -It should look something like this: - -```text -ODrive control utility v0.5.1 -Please connect your ODrive. -Type help() for help. - -Connected to ODrive 306A396A3235 as odrv0 -In [1]: odrv0.vbus_voltage -Out[1]: 11.97055721282959 -``` - -The tool you're looking at is a fully capable Python command prompt, so you can type any valid python code. - -You can read more about `odrivetool` [here](odrivetool.md). - -## Debugging -If any of the following steps fail, print the errors by running `dump_errors(odrv0)` in `odrivetool`. You can clear errors by running `odrv0.clear_errors()`. - -## Configure M0 -
    Read this section carefully, else you risk breaking something.
    -
    There is a [separate guide](hoverboard.md) specifically for hoverboard motors.
    - -### 1. Set the limits: -
    Wait, how do I set these?
    -In the previous step we started `odrivetool`. In there, you can assign variables directly by name. - -For instance, to set the current limit of M0 to 10A you would type: `odrv0.axis0.motor.config.current_lim = 10` Enter -
    - -**Current limit**
    -`odrv0.axis0.motor.config.current_lim` [A]. -The default current limit, for safety reasons, is set to 10A. This is quite weak, but good for making sure the drive is stable. Once you have tuned the oDrive, you can increase this to 60A to increase performance. Note that above 60A, you must change the current amplifier gains. You do this by requesting a different current range. i.e. for 90A on M0: `odrv0.axis0.motor.config.requested_current_range = 90` [A], then save the configuration and reboot as the gains are written out to the DRV (MOSFET driver) only during startup. - -*Note: The motor current and the current drawn from the power supply is not the same in general. You should not look at the power supply current to see what is going on with the motor current.* -
    Ok, so tell me how it actually works then...
    -The current in the motor is only connected to the current in the power supply _sometimes_ and other times it just cycles out of one phase and back in the other. This is what the modulation magnitude is (sometimes people call this duty cycle, but that's a bit confusing because we use SVM not straight PWM). When the modulation magnitude is 0, the average voltage seen across the motor phases is 0, and the motor current is never connected to the power supply. When the magnitude is 100%, it is always connected, and at 50% it's connected half the time, and cycled in just the motor half the time. - -The largest effect on modulation magnitude is speed. There are other smaller factors, but in general: if the motor is still it's not unreasonable to have 50A in the motor from 5A on the power supply. When the motor is spinning close to top speed, the power supply current and the motor current will be somewhat close to each other. -
    - -**Velocity limit**
    -`odrv0.axis0.controller.config.vel_limit` [turn/s]. -The motor will be limited to this speed. Again the default value is quite slow. - -**Calibration current**
    -You can change `odrv0.axis0.motor.config.calibration_current` [A] to the largest value you feel comfortable leaving running through the motor continuously when the motor is stationary. If you are using a small motor (i.e. 15A current rated) you may need to reduce `calibration_current` to a value smaller than the default. - -### 2. Set other hardware parameters -`odrv0.config.enable_brake_resistor` -Set this to `True` if using a brake resistor. You need to save the ODrive configuration and reboot the ODrive for this to take effect. - -`odrv0.config.brake_resistance` [Ohm] -This is the resistance of the brake resistor. You can leave this at the default setting if you are not using a brake resistor. Note that there may be some extra resistance in your wiring and in the screw terminals, so if you are getting issues while braking you may want to increase this parameter by around 0.05 ohm. - -`odrv0.config.dc_max_negative_current` [Amps] -This is the amount of current allowed to flow back into the power supply. The convention is that it is negative. By default, it is set to a conservative value of 10mA. If you are using a brake resistor and getting `DC_BUS_OVER_REGEN_CURRENT` errors, raise it slightly. If you are not using a brake resistor and you intend to send braking current back to the power supply, set this to a safe level for your power source. Note that in that case, it should be higher than your motor current limit + current limit margin. - -`odrv0.axis0.motor.config.pole_pairs` -This is the number of **magnet poles** in the rotor, **divided by two**. To find this, you can simply count the number of permanent magnets in the rotor, if you can see them. -**Note**: This is **not** the same as the number of coils in the stator. -A good way to find the number of pole pairs is with a current limited power supply. Connect any two of the three phases to a power supply outputting around 2A, spin the motor by hand, and count the number of detents. This will be the number of pole pairs. If you can't distinguish the detents from the normal cogging present when the motor is disconnected, increase the current. -Another way is sliding a loose magnet in your hand around the rotor, and counting how many times it stops. This will be the number of _pole pairs_. If you use a ferrous piece of metal instead of a magnet, you will get the number of _magnet poles_. - -`odrv0.axis0.motor.config.torque_constant` -This is the ratio of torque produced by the motor per Amp of current delivered to the motor. This should be set to **8.27 / (motor KV)**. -If you decide that you would rather command torque in units of Amps, you could simply set the torque constant to 1. - -`odrv0.axis0.motor.config.motor_type` -This is the type of motor being used. Currently two types of motors are supported: High-current motors (`MOTOR_TYPE_HIGH_CURRENT`) and gimbal motors (`MOTOR_TYPE_GIMBAL`). -
    Which motor_type to choose?
    - -If you're using a regular hobby brushless motor like [this](https://hobbyking.com/en_us/turnigy-aerodrive-sk3-5065-236kv-brushless-outrunner-motor.html) one, you should set `motor_mode` to `MOTOR_TYPE_HIGH_CURRENT`. For low-current gimbal motors like [this](https://hobbyking.com/en_us/turnigy-hd-5208-brushless-gimbal-motor-bldc.html) one, you should choose `MOTOR_TYPE_GIMBAL`. Do not use `MOTOR_TYPE_GIMBAL` on a motor that is not a gimbal motor, as it may overheat the motor or the ODrive. - -**Further detail:** -If 100's of mA of current noise is "small" for you, you can choose `MOTOR_TYPE_HIGH_CURRENT`. -If 100's of mA of current noise is "large" for you, and you do not intend to spin the motor very fast (Ω * L << R), and the motor is fairly large resistance (1 ohm or larger), you can chose `MOTOR_TYPE_GIMBAL`. -If 100's of mA current noise is "large" for you, _and_ you intend to spin the motor fast, then you need to replace the shunt resistors on the ODrive. -

    - -*Note: When using gimbal motors,* `current_lim` *and* `calibration_current` *actually mean "voltage limit" and "calibration voltage", since we don't use current feedback. This means that if you set it to 10, it means 10V, despite the name of the parameter.* - -**If using encoder**
    -`odrv0.axis0.encoder.config.cpr`: Encoder Count Per Revolution [CPR] -This is 4x the Pulse Per Revolution (PPR) value. Usually this is indicated in the datasheet of your encoder. - -**If not using encoder**
    -* If you wish to run in sensorless mode, please see [Setting up sensorless](commands.md#setting-up-sensorless). -* If you are using hall sensor feedback, please see the [hoverboard motor example](hoverboard.md). - -**If using motor thermistor**
    -Please see the [Thermistors](thermistors.md) page for setup. - -### 3. Save configuration -You can save all `.config` parameters to persistent memory so the ODrive remembers them between power cycles. This will reboot the board. -* `odrv0.save_configuration()` Enter. - - -## Position control of M0 -Let's get motor 0 up and running. The procedure for motor 1 is exactly the same, so feel free to substitute `axis1` wherever it says `axis0`. - -1. Type `odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE` Enter. After about 2 seconds should hear a beep. Then the motor will turn slowly in one direction for a few seconds, then back in the other direction. - -
    What's the point of this?
    - This procedure first measures your motor's electrical properties (namely phase resistance and phase inductance) and then the offset between the motor's electrical phase and the encoder position. -
    - - The startup procedure is demonstrated [here](https://www.youtube.com/watch?v=VCX1bA2xnuY). - - *Note: the rotor must be allowed to rotate without any biased load during startup. That means mass and weak friction loads are fine, but gravity or spring loads are not okay. Also note that in the video, the motors spin after initialization, but in the current software the default behaviour is not like that.* - -
    Help, something isn't working!
    - - Check the encoder wiring and that the encoder is firmly connected to the motor. Check the value of `dump_errors(odrv0)` and then refer to the [error code documentation](troubleshooting.md#error-codes) for details. - - Once you understand the error and have fixed its cause, you may clear the error state with (`odrv0.clear_errors()` Enter) and retry. -
    - -2. Type `odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL` Enter. From now on the ODrive will try to hold the motor's position. If you try to turn it by hand, it will fight you gently. That is unless you bump up `odrv0.axis0.motor.config.current_lim`, in which case it will fight you more fiercely. If the motor begins to vibrate either immediately or after being disturbed you will need to [lower the controller gains](control.md). -3. Send the motor a new position setpoint. `odrv0.axis0.controller.input_pos = 1` Enter. The units are in turns. -4. At this point you will probably want to [Properly tune](control.md) the motor controller in order to maximize system performance. - -## Other control modes -The default control mode is unfiltered position control in the absolute encoder reference frame. You may wish to use a controlled trajectory instead. Or you may wish to control position in a circular frame to allow continuous rotation forever without growing the numeric value of the setpoint too large. - -You may also wish to control velocity (directly or with a ramping filter). -You can also directly control the current of the motor, which is proportional to torque. - -- [Filtered position control](control-modes.md#filtered-position-control) -- [Trajectory control](control-modes.md#trajectory-control) -- [Circular position control](control-modes.md#circular-position-control) -- [Velocity control](control-modes.md#velocity-control) -- [Ramped velocity control](control-modes.md#ramped-velocity-control) -- [Torque control](control-modes.md#torque-control) - - -## Watchdog Timer -Each axis has a configurable watchdog timer that can stop the motors if the -control connection to the ODrive is interrupted. - -Each axis has a configurable watchdog timeout: `axis.config.watchdog_timeout`, -measured in seconds. Set `axis.config.enable_watchdog = True` to turn on this feature. - -The watchdog is fed using the `axis.watchdog_feed()` method of each axis. Some [ascii commands](ascii-protocol.md#command-reference), and most CANSimple commands, feed the watchdog automatically. - -## What's next? -You can now: -* [Properly tune](control.md) the motor controller to unlock the full potential of the ODrive. -* See what other [commands and parameters](commands.md) are available, in order to better control the ODrive. -* Control the ODrive from your own program or hook it up to an existing system through one of it's [interfaces](pinout.md). -* See how you can improve the behavior during the startup procedure, like [bypassing encoder calibration](encoders.md#encoder-with-index-signal). -* The CAN communication is the most reliable way of talking to ODrive in a real application. Check out the [CAN Guide](can-guide.md) and [CAN Protocol](can-protocol.md) - -If you have any issues or any questions please get in touch. The [ODrive Community](https://discourse.odriverobotics.com/) warmly welcomes you. - - -## Upgrading from 0.4.12 -A new version (0.5.1) of ODrive firmware has released, complete with a new odrivetool. Follow the installation instructions, making sure to add the `--upgrade` flag to pip commands, and check out the [Changelog](../CHANGELOG.md) for changes! - -The odrivetool will stage and restore your configuration. This probably isn't wise for the 0.4.12 -> 0.5.1 upgrade, so we suggest using `odrv0.erase_configuration()` immediately after connecting the first time. diff --git a/docs/reStructuredText/getting-started.rst b/docs/getting-started.rst similarity index 99% rename from docs/reStructuredText/getting-started.rst rename to docs/getting-started.rst index 94012ef9..094a7763 100644 --- a/docs/reStructuredText/getting-started.rst +++ b/docs/getting-started.rst @@ -98,7 +98,7 @@ Most instructions in this guide refer to a utility called `odrivetool`, so you s pip install --upgrade odrive - .. tab:: macOS + .. tab:: OSX We are going to run the following commands for installation in Terminal. diff --git a/docs/ground-loops.md b/docs/ground-loops.md deleted file mode 100644 index 4980863f..00000000 --- a/docs/ground-loops.md +++ /dev/null @@ -1,35 +0,0 @@ -# Ground Loops - -For electrical devices to communicate, most of the time they require a common ground connection. Best practice is to connect the grounds back to a single point, called a "star ground". If there are multiple paths to ground, a "ground loop" is formed. Ground loops and wire inductance can cause issues for high current electronics like ODrive. As an example of what can go wrong, look at the diagram below. - -## The Problem - -![Ground Loop with inductance](ground_loop_bad.png) - -The issue is the inductance of the power wires between the ODrive and power supply. The inductance and the high current drawn by the ODrive causes V_1 to not be the same as V_2. If the voltage caused by the wire inductance and current is high enough, the 0-5V gpio signals can swing much higher or lower than the normal 0-5V range. This causes a current to flow through the ODrive GPIO pins. - -## Solutions - -### Reduce Power Wire Inductance - -All wires have some amount of inductance. The inductance is proportional to the length of the wires and the area of the loop formed by the positive and negative power wires. It is beneficial to keep those wires as short as possible and as close together as possible. This reduces the effect of the problem but does not eliminate it! - -### Isolation - -To fix this, the ground loop must be broken. This can be achieved by isolating the power supplies (no common V-) and connecting a signal ground between the RPi and ODrive. An example of this is a single ODrive connected to a battery and a device like a RPi connected to a mains power supply or different battery. If more than one ODrive is in use and they share a power supply, you have a ground loop again. - -The best way to fix this is to isolate the data connection between the RPi and ODrive(s). The diagram below illustrates where the isolator should go. - -![Ground Loop fixed by isolator](ground_loop_fix.png) - -By isolating the data connection (whether it is GPIO, USB, or UART), the ground loop is broken. Isolation can be achieved by using a USB isolator or a signal isolator for GPIO connections. - -Here are some examples of USB isolators: [Isolator 1](https://www.aliexpress.com/item/33016336073.html?spm=a2g0s.9042311.0.0.57ec4c4dDADzZo), [Isolator 2](https://www.aliexpress.com/item/4000060726013.html?spm=a2g0s.9042311.0.0.57ec4c4dDADzZo). These are generic devices. If Aliexpress is not an option for you, you can probably find them available in your area from a different vendor. In the US, these types of isolators are available from Amazon and Ebay. - -For GPIO connections, like UART, Step/dir, PWM, etc, you can use signal isolators like the ISO7762F from Texas Instruments. Keep in mind that isolators have a speed limit. Devices like optocouplers might be too slow for UART connections or Step/direction. Check the datasheet! - -### Current Limiting - -If isolators are not an option, you can use series resistors to limit the injection current to a safe level. Place a resistor on the recieving side of all connections to or from the ODrive GPIO pins. 4.7kOhms is a good value, but anything from 3.3kOhms to 10kOhms should work. Series resistors offer some protection for the ODrive, but the ground loop problem can still cause the GPIOs to be pulled high or low for short periods of time. The ODrive and your other device will most likely be safe but communications might be interrupted. - -As an example, for UART, you would place a resistor close to the RX pin of the ODrive and another one close to the RX pin of the other device (like an Arduino). This allows the driving side, the TX pins, to adequately drive the bus capacitance. diff --git a/docs/reStructuredText/ground-loops.rst b/docs/ground-loops.rst similarity index 100% rename from docs/reStructuredText/ground-loops.rst rename to docs/ground-loops.rst diff --git a/docs/hoverboard.md b/docs/hoverboard.md deleted file mode 100644 index a8840568..00000000 --- a/docs/hoverboard.md +++ /dev/null @@ -1,214 +0,0 @@ - -# Hoverboard motor and remote control setup guide -By popular request here follows a step-by-step guide on how to setup the ODrive to drive hoverboard motors using RC PWM input. -Each step is accompanied by some explanation so hopefully you can carry over some of the steps to other setups and configurations. - - -[![IMAGE ALT TEXT HERE](https://img.youtube.com/vi/ponx_U4xhoM/0.jpg)](https://www.youtube.com/watch?v=ponx_U4xhoM)
    Click above to play video. - -### Hoverboard motor wiring -Hoverboard motors come with three motor phases (usually colored yellow, blue, green) which are thicker, and a set of 5 thinner wires for the hall sensor feedback (usually colored red, yellow, blue, green, black). - -You may wire the motor phases in any order into a motor connector on the ODrive, as we will calibrate the phase alignment later anyway. Wire the hall feedback into the ODrive J4 connector (make sure that the motor channel number matches) as follows: - -| Hall wire | J4 signal | -|-----------|-----------| -| Red | 5V | -| Yellow | A | -| Blue | B | -| Green | Z | -| Black | GND | - -Note: In order to be compatible with encoder inputs, the ODrive doesn't have any filtering capacitors on the pins where the hall sensors connect. Therefore to get a reliable hall signal, it is recommended that you add some filter capacitors to these pins. We recommend about 22nF between each signal pin and GND. You can see instructions [here](https://discourse.odriverobotics.com/t/encoder-error-error-illegal-hall-state/1047/7?u=madcowswe). - -### ODrive Configuration -There are a few items we need to configure on the ODrive before setting up the motor. - -`odrv0.config.enable_brake_resistor` -Set this to `True` if using a brake resistor. You need to save the ODrive configuration and reboot the ODrive for this to take effect. - -`odrv0.config.brake_resistance` [Ohm] -This is the resistance of the brake resistor. You can leave this at the default setting if you are not using a brake resistor. Note that there may be some extra resistance in your wiring and in the screw terminals, so if you are getting issues while braking you may want to increase this parameter by around 0.05 ohm. - -`odrv0.config.dc_max_negative_current` [Amps] -This is the amount of current allowed to flow back into the power supply. The convention is that it is negative. By default, it is set to a conservative value of 10mA. If you are using a brake resistor and getting `DC_BUS_OVER_REGEN_CURRENT` errors, raise it slightly. If you are not using a brake resistor and you intend to send braking current back to the power supply, set this to a safe level for your power source. Note that in that case, it should be higher than your motor current limit + current limit margin. - - -### Hoverboard motor configuration -Standard 6.5 inch hoverboard hub motors have 30 permanent magnet poles, and thus 15 pole pairs. If you have a different motor you need to count the magnets or have a reliable datasheet for this information. -```txt -odrv0.axis0.motor.config.pole_pairs = 15 -``` - -Hoverboard hub motors are quite high resistance compared to the hobby aircraft motors, so we want to use a bit higher voltage for the motor calibration, and set up the current sense gain to be more sensitive. -The motors are also fairly high inductance, so we need to reduce the bandwidth of the current controller from the default to keep it stable. -The KV rating of the motor also should be known. It can be measured using the "drill test", detailed [here](https://discourse.odriverobotics.com/t/project-hoverarm/441/2?u=madcowswe). If you can't perform this test, a typical value is 16. - -```txt -odrv0.axis0.motor.config.resistance_calib_max_voltage = 4 -odrv0.axis0.motor.config.requested_current_range = 25 #Requires config save and reboot -odrv0.axis0.motor.config.current_control_bandwidth = 100 -odrv0.axis0.motor.config.torque_constant = 8.27 / -``` - -If you set the encoder to hall mode (instead of incremental). See the [pinout](encoders.md#hall-effect-encoders) for instructions on how to plug in the hall feedback. -The hall feedback has 6 states for every pole pair in the motor. Since we have 15 pole pairs, we set the cpr to `15*6 = 90`. Since hall sensors are low resolution feedback, we also bump up the offset calibration displacement to get better calibration accuracy. -```txt -odrv0.axis0.encoder.config.mode = ENCODER_MODE_HALL -odrv0.axis0.encoder.config.cpr = 90 -odrv0.axis0.encoder.config.calib_scan_distance = 150 -odrv0.config.gpio9_mode = GPIO_MODE_DIGITAL -odrv0.config.gpio10_mode = GPIO_MODE_DIGITAL -odrv0.config.gpio11_mode = GPIO_MODE_DIGITAL -``` - -Since the hall feedback only has 90 counts per revolution, we want to reduce the velocity tracking bandwidth to get smoother velocity estimates. -We can also set these fairly modest gains that will be a bit sloppy but shouldn't shake your rig apart if it's built poorly. Make sure to tune the gains up when you have everything else working to a stiffness that is applicable to your application. -Lets also start in velocity control mode since that is probably what you want for a wheeled robot. Note that in velocity mode `pos_gain` isn't used but I have given you a recommended value anyway in case you wanted to run position control mode. - -* Note: The gains used here are dependent on the `torque_constant` and `cpr` config settings. The values for hoverboard motors are *very different* from the stock settings. Do not skip the above steps and go straight to these settings! -```txt -odrv0.axis0.encoder.config.bandwidth = 100 -odrv0.axis0.controller.config.pos_gain = 1 -odrv0.axis0.controller.config.vel_gain = 0.02 * odrv0.axis0.motor.config.torque_constant * odrv0.axis0.encoder.config.cpr -odrv0.axis0.controller.config.vel_integrator_gain = 0.1 * odrv0.axis0.motor.config.torque_constant * odrv0.axis0.encoder.config.cpr -odrv0.axis0.controller.config.vel_limit = 10 -odrv0.axis0.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL -``` - -In the next step we are going to start powering the motor and so we want to make sure that some of the above settings that require a reboot are applied first. -```txt -odrv0.save_configuration() -odrv0.reboot() -``` - -Make sure the motor is free to move, then activate the motor calibration. -```txt -odrv0.axis0.requested_state = AXIS_STATE_MOTOR_CALIBRATION -``` - -You can read out all the data pertaining to the motor: -```txt -odrv0.axis0.motor -``` - -Check to see that there is no error and that the phase resistance and inductance are reasonable. Here are the results I got: -```txt - error = 0x0000 (int) - phase_inductance = 0.00033594953129068017 (float) - phase_resistance = 0.1793474406003952 (float) -``` - -If all looks good then you can tell the ODrive that saving this calibration to persistent memory is OK: -```txt -odrv0.axis0.motor.config.pre_calibrated = True -``` - -Next step is to check the alignment between the motor and the hall sensor. -Because of this step you are allowed to plug the motor phases in random order and also the hall signals can be random. Just don't change it after calibration. -Make sure the motor is free to move and run: -```txt -odrv0.axis0.requested_state = AXIS_STATE_ENCODER_HALL_POLARITY_CALIBRATION -``` - -Check the status of the encoder object: -```txt -odrv0.axis0.encoder -``` - -Check that there are no errors. -```txt - error = 0x0000 (int) -``` - -If the hall encoder polarity calibration was successful, run the encoder offset calibration. - -```txt -odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION -``` - -Check the status of the encoder object: -```txt -odrv0.axis0.encoder -``` - -Check that there are no errors. If your hall sensors has a standard timing angle then `phase_offset_float` should be close to 0.5 mod 1. Meaning values close to -1.5, -0.5, 0.5, or 1.5, etc are all good. -```txt - error = 0x0000 (int) - config: - phase_offset_float = 0.5126956701278687 (float) -``` - -If all looks good then you can tell the ODrive that saving this calibration to presistent memory is OK: -```txt -odrv0.axis0.encoder.config.pre_calibrated = True -``` - -OK, we are now done with the motor configuration! Time to save, reboot, and then test it. -The ODrive starts in idle (we will look at changing this later) so we can enable closed loop control. -```txt -odrv0.save_configuration() -odrv0.reboot() -odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL -odrv0.axis0.controller.input_vel = 2 -# Your motor should spin here -odrv0.axis0.controller.input_vel = 0 -odrv0.axis0.requested_state = AXIS_STATE_IDLE -``` - -Hopefully you got your motor to spin! Feel free to repeat all of the above for the other axis if appropriate. - -### PWM input -If you want to drive your hoverboard wheels around with an RC remote control you can use the [RC PWM input](rc-pwm.md). There is more information in that link. -Lets use GPIO 3/4 for the velocity inputs so that we don't have to disable UART. -Then let's map the full stick range of these inputs to some suitable velocity setpoint range. -We also have to reboot to activate the PWM input. -```txt -odrv0.config.gpio3_pwm_mapping.min = -2 -odrv0.config.gpio3_pwm_mapping.max = 2 -odrv0.config.gpio3_pwm_mapping.endpoint = odrv0.axis0.controller._input_vel_property - -odrv0.config.gpio4_pwm_mapping.min = -2 -odrv0.config.gpio4_pwm_mapping.max = 2 -odrv0.config.gpio4_pwm_mapping.endpoint = odrv0.axis1.controller._input_vel_property - -odrv0.save_configuration() -odrv0.reboot() -``` - -Now we can check that the sticks are writing to the velocity setpoint. Move the stick, print `input_vel`, move to a different position, check again. -```txt -In [1]: odrv0.axis1.controller.input_vel -Out[1]: 0.01904754638671875 - -In [2]: odrv0.axis1.controller.input_vel -Out[2]: 0.01904754638671875 - -In [3]: odrv0.axis1.controller.input_vel -Out[3]: 1.152389526367188 - -In [4]: odrv0.axis1.controller.input_vel -Out[4]: 1.81905517578125 - -In [5]: odrv0.axis1.controller.input_vel -Out[5]: -0.990474700927734 -``` - -Ok, now we should be able to turn on the drive and control the wheels! -```txt -odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL -odrv0.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL -``` - -### Safety -Be sure to setup the Failsafe feature on your RC Receiver so that if connection is lost between the remote and the receiver, the receiver outputs 0 and 0 for the velocity setpoint of both axes (or whatever is safest for your configuration). Also note that if the receiver turns off (loss of power, etc) or if the signal from the receiver to the ODrive is lost (wire comes unplugged, etc), the ODrive will continue the last commanded velocity setpoint. There is currently no timeout function in the ODrive for PWM inputs. - -### Automatic startup -Try to reboot and then activate AXIS_STATE_CLOSED_LOOP_CONTROL on both axis. Check that everything is operational and works as expected. -If so, you can now make the ODrive turn on the motor power automatically after booting. This is useful if you are going to be running the ODrive without a PC or other logic board. -```txt -odrv0.axis0.config.startup_closed_loop_control = True -odrv0.axis1.config.startup_closed_loop_control = True -odrv0.save_configuration() -odrv0.reboot() -``` diff --git a/docs/reStructuredText/hoverboard.rst b/docs/hoverboard.rst similarity index 100% rename from docs/reStructuredText/hoverboard.rst rename to docs/hoverboard.rst diff --git a/docs/reStructuredText/index.rst b/docs/index.rst similarity index 100% rename from docs/reStructuredText/index.rst rename to docs/index.rst diff --git a/docs/interface-definition-file.md b/docs/interface-definition-file.md deleted file mode 100644 index 9e4628e1..00000000 --- a/docs/interface-definition-file.md +++ /dev/null @@ -1,133 +0,0 @@ -# Interface Definition File - -This document describes the rules on which the ODrive Interface Definition file is built. It is intended for ODrive contributors who wish to modify it or ODrive users who want to autogenerate their own code from this file to interface with the ODrive. - -## Terms and Concepts - -*Value types* are a way of saying how values of this type are serialized/deserialized to/from raw bytes. -Value types can be: - - one of the well-known types `bool`, `int8`, `uint8`, `int16`, `uint16`, `int32`, `uint32`, `int32`, `uint32`, `int64`, `uint64`, `float32`, `float64`, `fibre.Ref` - - An enumeration (that is, a mapping between serialized numbers and well known value names) - - A set of flags (in many programming languages this is the same as normal enums) - -An *interface* is a collection of features (attributes and functions) that can be implemented by an object or used by a client as a filter for object discovery. - -A *function* is something that takes zero or more inputs from the client, does something, and then returns zero or more outputs to the client. Since these input and output arguments are transmitted as raw bytes, they each have a value type. - -An *attribute* is a reference to a subobject which again implements some interface. - -Many languages don't make clear distinctions between interfaces and value types so let's be clear on this: attributes _always_ have an interface type and function input/output arguments _always_ have a value type. If you see something that looks like an attribute with a value type (let's say `uint32`), it's actually an attribute with the interface type `fibre.Property`. If you see a function argument that looks like an interface type (let's say `MyIntf`) it's actually of the value type `fibre.Ref`. - - -## File Structure - -The top level contains a dictionary of interfaces and a dictionary of value types. -Interfaces as well as value types can be subordinate to other interfaces. Nested names are specified using dots in between the subnames. - -Example: - -```yaml -interfaces: - MyFirstInterface: ... - MyFirstInterface.SubInterface: ... - -valuetypes: - MyFirstEnum: ... - MyFirstInterface.SubEnum: ... -``` - -## Interfaces - -Interfaces consist of an `attributes` dictionary and a `functions` dictionary. - -**Attributes** have a type which is either given by name as a string or directly in place. -Even though attributes conceptually and internally are always resolved to an interface type, for your convenience you can also give a value type which is then implicitly resolved to `fibre.Property`. - -If the type is given as a string, it is resolved based on the scope in which it occurs. The search precedence is as follows: The innermost scope is searched first for an interface with that name and then for a value type with that name. If both names don't exist, the next outer scope is checked. Note that the order in which types are defined does not matter. The whole file is read before any type resolution occurs. - -**Functions** have an `in` and `out` dictionary specifying one or more argument names with their corresponding value types. Like with attributes, the types can be specified in place or as a name. Type resolution also works the same except that only value types are checked for. - -Example: -```yaml -interfaces: - Car: - attributes: - velocity: float - door_front_left: Door - door_front_right: Door - steering_wheel: - attributes: - angle: float - functions: - turn: {in: {delta_angle: float32}, out: {final_angle: float32}} - Car.Door: - attributes: - is_open: bool - part_of: Car - functions: - open: - close: -``` - -Let's see how the type resolution of the attibute `Car.Door.part_of: Car` would work here: - - 1. Interface `Car.Door.Car` => not found, proceed - 2. Value type `Car.Door.Car` => not found, proceed - 3. Interface `Car.Car` => not found, proceed - 4. Value type `Car.Car` => not found, proceed - 5. Interface `Car` => found. Link to this interface type. - - -## Enums - -Enums are values which are associated with a name. They are serialized as 32-bit numbers. - -Enumerators without an explicitly stated numerical value are guaranteed to have an underlying value one larger than that of the preceding enumerator. - -Each enumerator must have a unique value. - -Example: - -```yaml -valuetypes: - ModeOfTransport: - values: - Walking: - Bicycle: - Car: {value: 5} - Train: -``` - -This would be serialized as: - - Walking <=> `0x00000000` <=> `0x00 0x00 0x00 0x00` - - Bicycle <=> `0x00000001` <=> `0x01 0x00 0x00 0x00` - - Car <=> `0x00000005` <=> `0x05 0x00 0x00 0x00` - - Train <=> `0x00000006` <=> `0x06 0x00 0x00 0x00` - -## Flagfields - -Flagfields are serialized as 32-bit low endian values where each bit has a named meaning. - -A flag without an explicit bit number is guaranteed to have the bit number of the preceding flag plus one or bit 0 it it's the first in the list. - -Each flag must have a unique bit number. - -Example: - -```yaml -valuetypes: - Anchor: - nullflag: Nowhere - flags: - Top: - Left: - Bottom: {bit: 8} - Right: -``` - -This would be serialized as: - - Nowhere <=> `0x00000000` <=> `0x00 0x00 0x00 0x00` - - Top <=> `0x00000001` <=> `0x01 0x00 0x00 0x00` - - Top and Left <=> `0x00000003` <=> `0x03 0x00 0x00 0x00` - - Bottom <=> `0x00000100` <=> `0x00 0x01 0x00 0x00` - - Top and Bottom and Right <=> `0x00000301` <=> `0x01 0x03 0x00 0x00` diff --git a/docs/reStructuredText/make.bat b/docs/make.bat similarity index 100% rename from docs/reStructuredText/make.bat rename to docs/make.bat diff --git a/docs/mechanical-brakes.md b/docs/mechanical-brakes.md deleted file mode 100644 index ab2164e1..00000000 --- a/docs/mechanical-brakes.md +++ /dev/null @@ -1,61 +0,0 @@ -# Mechanical Brake - -Some systems employ mechanical brakes on motors as a safety feature. These brakes can also be engaged as a power-saving function if the motor is not moving, but still under load. - -ODrive supports the use of its GPIO pins to connect to external brake drive electronics. - -When the ODrive engages the drive electronics, the brake will be disabled. When the drive enters a fault or idle state, the brake will be re-engaged. - ---- - -## Mechanical Brake Configuration -Each axis supports one mechanical brake. The following properties are accessible through `odrivetool`: - -Name | Type | Default ---- | -- | -- -gpio_num | int | 0 -is_active_low | boolean | true - -### gpio_num -The GPIO pin number, according to the silkscreen labels on ODrive. Set with these commands: -``` -..mechanical_brake.config.gpio_num = <1, 2, 3, 4, 5, 6, 7, 8> -``` -After GPIO pin number is changed, you'll need to run `.save_configuration()` and `.reboot()` for changes to take effect. - -### is_active_low -Most safety braking systems are active low, e.g. when the power is off, the brake is on. If the system uses brake drive electronics which use active high logic, flip this bit then reconsider the safety implications of your design... - -### Enabling -The configuration of the mechanical brake will enable the brake functionality. There's no need to specifically 'enable' this feature. - - -### Example - -Let's say we're hacking away on an old ABB robotic arm. We've wired a 24V brake drive circuit triggered by GPIO5. When GPIO5 is driven, it will release the brakes on the axis we're moving. - -We need to notify the axis of the GPIO number we've attached our brake to, and configure the ODrive pin mode to `GPIO_MODE_MECH_BRAKE`: -``` -..mechanical_brake.config.gpio_num = 5 -.config.gpio5_mode = GPIO_MODE_MECH_BRAKE -``` - -Pin configurations only take effect after a save/reboot so don't forget to run: -``` -.save_configuration() -.reboot() -``` - -### Testing The Mechanical Brakes -Depending on your system this could be a dangerous experiment. Ensure that you have taken all necessary precautions to confirm if the wrong brake were inadvertently released it would not lead to injury or damage to equipment. - -``` -..mechanical_brake.release() -``` -Note: If a brake is configured, it will be automatically engaged/disengaged during the next state machine step. - -After you're satisfied with the testing, you can re-enable the brake using the command - -``` -..mechanical_brake.engage() -``` diff --git a/docs/migration.md b/docs/migration.md deleted file mode 100644 index b95b99b5..00000000 --- a/docs/migration.md +++ /dev/null @@ -1,82 +0,0 @@ -# Migration Guide - -## v0.5.1 -> v0.5.2 - -The change from v0.5.1 to v0.5.2 had fewer breaking changes than the v0.4.12 to v0.5.1 change. - -## GPIO modes -The GPIO configuration is now more explicit. For example, to use `gpio1` for for step signals (as part of a step/dir interface), it must be set to -``` -odrv0.config.gpio1_mode = GPIO_MODE_DIGITAL -``` - -## Braking behavior -Before using the brake resistor, it must be explicitly enabled as follows: -``` -odrv0.config.enable_brake_resistor = True -``` -and then save the configuration and reboot for the setting to take effect. - -## Step/direction settings -Previously, steps were added incrementally to `input_pos`. This caused issues with accumulated floating point rounding error. Now, an absolute step count is used. This change requires that the circular setpoints mode is used `odrv0.axis0.controller.config.circular_setpoints = True` when step/dir signals are used. - -In addition, `odrv0.axis0.config.turns_per_step` has been removed and `odrv0.axis0.controller.config.steps_per_circular_range` is used. For example: -``` -# previous -odrv0.axis0.config.turns_per_step = 1.0/1024.0 - -# v0.5.2 -odrv0.axis0.controller.config.circular_setpoints = True -odrv0.axis0.controller.config.circular_setpoint_range = 1.0 -odrv0.axis0.controller.config.steps_per_circular_range = 1024 -``` - -For best results, set both the circular range and steps per circular range to powers of 2. - -## API changes - -For other API changes, see the Changelog file on github. - -## v0.4.12 -> v0.5.1 - -Certain changes occurred between firmware versions v0.4.12 and v0.5.1 that will break existing configurations. This document is a guide for how to take a working v0.4.12 ODrive config and change it to work with firmware v0.5.1. - -## Unit Changes -ODrive now uses units of [turns], [turns/s], and [turns/s^2] instead of [counts], [counts/s], and [counts/s^2]. In addition, the motor controller class now has an input command of torque in [Nm] instead of current in [Amps]. In general, every user-facing parameter that has to do with position or velocity is affected by the unit change. - -**Note:** For the torque to be in correct in [Nm] you need to configure the `motor.config.torque_constant`. See the updated [getting started](getting-started.md/#configure-m0) for more details. - -## Control Parameter Names -ODrive now uses `input_pos`, `input_vel`, and `input_torque` as commands instead of `pos_setpoint`, `vel_setpoint`, and `current_setpoint` - -## Guide -For a working v0.4.12 ODrive configuration, use the following equations to convert parameters as required. - -- `pos_gain` is unaffected ( [counts/s / count] -> [turns/s / turns] ) -- `vel_gain` is `vel_gain_old` * `torque_constant` * `encoder cpr` -- `vel_integrator_gain` is `vel_integrator_gain_old` * `torque_constant` * `encoder cpr` - -For other values, [turns] = [counts] / [encoder cpr]. Converting [counts/s] and [counts/s^2] is similar. - -### Affected Variables -- `axis.controller.input_pos` -- `axis.controller.input_vel` -- `axis.controller.input_torque` -- `axis.controller.config.vel_limit` -- `axis.controller.config.vel_ramp_rate` -- `axis.controller.config.current_ramp_rate` is now `axis.controller.config.torque_ramp_rate` -- `axis.controller.config.circular_setpoint_range` -- `axis.controller.config.inertia` -- `axis.controller.config.homing_speed` -- `axis.controller.pos_setpoint` -- `axis.controller.vel_setpoint` -- `axis.controller.torque_setpoint` instead of `axis.controller.current_setpoint` -- `axis.trap_traj.config.vel_limit` -- `axis.trap_traj.config.accel_limit` -- `axis.trap_traj.config.decel_limit` -- `axis.encoder.pos_estimate` -- `axis.encoder.pos_estimate_circular` -- `axis.encoder.vel_estimate` -- `axis.config.counts_per_step` is now `turns_per_step` for the step/direction interface -- `axis.sensorless_estimator.vel_estimate` is in mechanical [turns/s] instead of electrical [radians/s] - diff --git a/docs/reStructuredText/migration.rst b/docs/migration.rst similarity index 100% rename from docs/reStructuredText/migration.rst rename to docs/migration.rst diff --git a/docs/native-protocol.md b/docs/native-protocol.md deleted file mode 100644 index 47f53dae..00000000 --- a/docs/native-protocol.md +++ /dev/null @@ -1,21 +0,0 @@ -# Native Protocol - -This protocol is what the ODrive Tool uses to talk to the ODrive. If you have a choice, this is the recommended protocol for all applications. The native protocol runs on [USB](usb) and on [UART](uart). - -## Python - -The ODrive Tool you installed as part of the [Getting Started guide](getting-started.md#downloading-and-installing-tools) comes with a library that you can use to easily control the ODrive from Python. - -Assuming you already installed the odrive library (`pip install odrive`), the simplest program to control the ODrive is this: - -```python -import odrive -odrv0 = odrive.find_any() -print(str(odrv0.vbus_voltage)) -``` - -For a more comprehensive example, see [tools/odrive_demo.py](../tools/odrive_demo.py). - -## Other languages - -We don't have an official library for you just yet. Check the community, there might be someone working on it. If you want to write a library yourself, refer to the [native protocol specification](protocol). You are of course welcome to contribute it back. \ No newline at end of file diff --git a/docs/reStructuredText/native-protocol.rst b/docs/native-protocol.rst similarity index 100% rename from docs/reStructuredText/native-protocol.rst rename to docs/native-protocol.rst diff --git a/docs/odrivetool.md b/docs/odrivetool.md deleted file mode 100644 index 5c1d902e..00000000 --- a/docs/odrivetool.md +++ /dev/null @@ -1,262 +0,0 @@ -# ODrive Tool - -The ODrive Tool is the accompanying PC program for the ODrive. It's main purpose is to provide an interactive shell to control the device manually, as well as some supporting functions like firmware update. - -### Table of contents - - -- [Installation](#installation) -- [Multiple ODrives](#multiple-odrives) -- [Configuration Backup](#configuration-backup) -- [Device Firmware Update](#device-firmware-update) -- [Flashing with an STLink](#flashing-with-an-stlink) -- [Liveplotter](#liveplotter) - - - -## Installation - -Refer to the [Getting Started guide](getting-started#downloading-and-installing-tools). - -Type `odrivetool --help` to see what features are available. - -## Multiple ODrives - -By default, `odrivetool` will connect to any ODrive it finds. If this is not what you want, you can select a specific ODrive. - -To find the serial number of your ODrive, run `odrivetool`, connect exactly one ODrive and power it up. You should see this: -``` -Connected to ODrive 306A396A3235 as odrv0 -In [1]: -``` -`306A396A3235` is the serial number of this particular ODrive. If you want ODrive Tool to ignore all other devices you would close it and then run `odrivetool --serial-number 306A396A3235`. - -
    My ODrive is stuck in DFU mode, can I still find the serial number?
    -Yes, the serial number is part of the USB descriptors. - -In Linux you can find it by running: -``` -$ (sudo lsusb -d 1209:0d32 -v; sudo lsusb -d 0483:df11 -v) 2>/dev/null | grep iSerial - iSerial 3 385F324D3037 - iSerial 3 306A396A3235 -``` -Here, two ODrives are connected. -
    - -## Configuration Backup - -You can use ODrive Tool to back up and restore device configurations or transfer the configuration of one ODrive to another one. - - * To save the configuration to a file on the PC, run `odrivetool backup-config my_config.json`. - * To restore the configuration form such a file, run `odrivetool restore-config my_config.json`. - -Note that encoder offset calibration is not restored because this would be dangerous if you transfer the calibration values of one axis to another axis. - -## Device Firmware Update - -
    __ODrive v3.4 or earlier__: DFU is not supported on these devices. You need to [flash with the external programmer](#flashing-with-an-stlink) instead.
    - -To update the ODrive to the newest firmware release, simply open up a terminal and run the following command: - -``` -~ $ odrivetool dfu -ODrive control utility v0.3.7.dev -Waiting for ODrive... -Found ODrive 308039673235 (v3.5-24V) with firmware v0.3.7-dev -Checking online for newest firmware... found v0.3.7 -Downloading firmware... -Putting device 308039673235 into DFU mode... -Erasing... done -Flashing... done -Verifying... done -``` - -Note that this command will connect to GitHub servers to retrieve the latest firmware. - -If you have a non-default configuration saved on the device, ODrive Tool will try to carry over the configuration across the firmware update. If any of the settings are removed or renamed, you will get warning messages. - -
    How to flash a custom firmware
    -If you want to flash a specific firmware file instead of automatically downloading one, you can run `odrivetool dfu path/to/firmware/file.hex` - -You can download one of the officially released firmware files from [here](https://github.com/madcowswe/ODrive/releases). You will need one of the __.hex__ files (not the __.elf__ file). Make sure you select the file that matches your board version. - -To compile firmware from source, refer to the [developer guide](developer-guide). -
    - - -### Troubleshooting - -* __Windows__: During the update, a new device called "STM32 BOOTLOADER" will appear. Open the [Zadig utility](http://zadig.akeo.ie/) and set the driver for "STM32 BOOTLOADER" to libusb-win32. After that the firmware update will continue. -* __Linux__: Try running `sudo odrivetool dfu` instead of `odrivetool dfu`. -* On some machines you will need to unplug and plug back in the USB cable to make the PC understand that we switched from regular mode to bootloader mode. -* If the DFU script can't find the device, try forcing it into DFU mode. - -
    How to force DFU mode (ODrive v3.5 and newer)
    - Flick the DIP switch that says "DFU, RUN" to "DFU" and power cycle the board. If that alone doesn't work, also connect the pin "GPIO6" to "GND". After you're done upgrading firmware, don't forget to put the switch back into the "RUN" position and power cycle the board again. -
    - -
    How to force DFU mode (ODrive v3.1, v3.2)
    - Connect the pin "BOOT0" to "3.3V" and power cycle the board. If that alone doesn't work, also connect the pin "GPIO1" to "GND". After you're done, remove the wires and power cycle the board again. -
    - -### Upgrading firmware with a different DFU tool -Some people have had issues using the python dfu tool, so below is a guide on how to manually use different tools. - -Before starting the below steps, you need to get firmware binary. You can download one of the officially released firmware files from [here](https://github.com/madcowswe/ODrive/releases/latest). Make sure you select the file that matches your board version. On Windows you will need one of the __.hex__ files, and for Linux and Mac you will want the __.elf__ file. - -To compile firmware from source, refer to the [developer guide](developer-guide). - -#### Multi-platform -ST has a tool called STM32CubeProgrammer. - -1. Download the tool [here](https://www.st.com/en/development-tools/stm32cubeprog.html). You will need to make an account with ST to download the tool. -1. Install the tool. On Windows, make sure to let it make a desktop shortcut. -1. Force the ODrive into DFU mode, as per the instructions above titled "How to force DFU mode". -1. Launch the tool. -1. Under "Memory & File edition", there are two tabs called "Device memory" and "Open file". Click "Open file" and choose the ODrive firmware hex file that you downloaded or compiled. -1. In the top right, there is a dropdown menu containing the different methods to connect to an STM32 device. Choose "USB". -1. Under "USB configuration", a USB port should be automatically selected and the ODrive serial number should be present next to "Serial number." -1. Click "Connect" above "USB configuration". -1. Click the tab with the name of your firmware file (example: ODriveFirmware_v3.6-56V.hex) if it is not already selected. -1. Click "Download" to flash your ODrive with the firmware. Your ODrive is now flashed! -1. Close STM32CubeProgrammer. -1. Turn off the power to the ODrive and set the DIP swtich back to RUN mode. - -#### Windows -You can use the DfuSe app from ST. - -1. Download the tool [here](https://www.st.com/en/development-tools/stsw-stm32080.html). Unfortunately they make you create a login to download. Sorry about that. -1. After installing the tool, launch `DfuFileMgr.exe` which probably got added to the start menu as "Dfu file manager". -1. Select "I want to GENERATE a DFU file from S19, HEX or BIN files", press OK. -1. Click the button that says "S19 or Hex...", find the `ODriveFirmware.hex` file you built or downloaded. -1. Leave all the other settings as default and click the "Generate..." button. -1. Save the output file as `ODriveFirmware.dfu`. Note that the success message has a warning sign for some reason... -1. Launch `DfuSeDemo.exe` which probably got added to the start menu as "DfuSeDemo". -1. Force the ODrive into DFU mode, as per the instructions above "How to force DFU mode". -1. In the top left it should now be connected to "STM Device in DFU Mode". - 1. If it doesn't appear, it may be because the driver is set to libusb by Zadig. We need to set it back to the original driver. Follow [these instructions](https://github.com/pbatard/libwdi/wiki/FAQ#Help_Zadig_replaced_the_driver_for_the_wrong_device_How_do_I_restore_it). - 2. If, after doing the above step, the ODrive still installs itself as a libusb device in Device Manager, you can try to delete the libusb driver (this is OK, since we can use Zadig to install it again). You can simply delete the file `C:\Windows\System32\drivers\libusb0.sys`. -1. In the bottom right section called "Upgrade or Verify Action" click the button "Choose...". -1. Locate the `ODriveFirmware.dfu` we made before. -1. Click button "Upgrade". -1. If you get a warning that it's not possible to check that it's the correct device type: click yes to continue. -1. Congratulations your ODrive should now be flashed; you can now quit DfuSeDemo. -1. Turn off the power to the ODrive and set the DIP switch back to RUN mode. - -#### Linux -Install `dfu-util`: -```text -sudo apt install dfu-util -``` - -Force DFU mode, as per the instructions above. -In the Firmware directory, after finishing building the firmware: -```text -sudo dfu-util -a 0 -s 0x08000000 -D build/ODriveFirmware.bin -``` - -#### macOS - -First, you need to install the arm development tools to copy the binary into the appropriate format. - -```text -$ brew install --cask gcc-arm-embedded -``` - -Then convert the binary to .bin format - -```text -$ arm-none-eabi-objcopy -O binary ODriveFirmware_v3.5-48V.elf ODriveFirmware_v3.5-48V.bin -``` - -Install `dfu-util`: - -```text -$ sudo port install dfu-util # via MacPorts; for HomeBrew use "brew install dfu-util" -``` - -Put the ODrive into DFU mode using the DIP switch, then turn it on and plug in the USB. -Find the correct device serial number to use: - -```text -$ dfu-util --list # list the DFU capable devices -[...] -Found DFU: [0483:df11] ver=2200, devnum=5, cfg=1, intf=0, path="20-2", alt=0, - name="@Internal Flash /0x08000000/04*016Kg,01*064Kg,07*128Kg", serial="388237123123" -``` - -Finally, flash the firmware using the found serial number: - -```text -$ sudo dfu-util -S 388237123123 -a 0 -s 0x08000000 -D ODriveFirmware_v3.5-48V.bin -``` - -## Flashing with an STLink - -This procedure is only necessary for ODrive v3.4 or earlier. You will need an STLink/v2 or compatible programmer. You should have received one with your ODrive. - -1. Install OpenOCD - * **Windows:** [instructions](http://gnuarmeclipse.github.io/openocd/install/) (also follow the instructions on the ST-LINK/V2 drivers) - * **Linux:** `sudo apt-get install openocd` - * **macOS:** `brew install openocd` -2. Download the latest firmware release form [here](https://github.com/madcowswe/ODrive/releases). You will need the __.elf__ file. Make sure you select the file that matches your board version. -3. Wire up the ODrive and STLink/v2 programmer as shown in this picture:
    - ![stlink-wiring](stlink-wiring-cropped.jpg) - Power up the ODrive. -4. Open up a terminal and navigate to the directory where the firmware is. -5. Run the following command (replace `ODriveFirmware_v3.4-24V.elf` with the name of your firmware file): -``` -openocd -f interface/stlink-v2.cfg -f target/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase ODriveFirmware_v3.4-24V.elf" -c "reset run" -c exit -``` - -If everything worked correctly, you should see something similar to this towards the end of the printout: -``` -wrote 262144 bytes from file ODriveFirmware_v3.4-24V.elf in 10.194110s (25.113 KiB/s) -``` - -If something doesn't work, make sure `openocd` is in your `PATH` variable, check that the wires are connected properly and try with elevated privileges. - -## Liveplotter - -Liveplotter is used for the graphical plotting of odrive parameters (i.e. position) in real time. To start liveplotter, close any other instances of liveplotter and run `odrivetool liveplotter` from a new anaconda prompt window. By default two parameters are plotted on startup; the encoder position of axis 1 and axis 2. In the below example the motors are running in `closed_loop_control` while they are being forced off position by hand. - -![Liveplotter position plot](figure_1.png) - -To change what parameters are plotted open odrivetool (located in Anaconda3\Scripts or ODrive-master\tools) with a text editor and modify the liveplotter function: -``` - # If you want to plot different values, change them here. - # You can plot any number of values concurrently. - cancellation_token = start_liveplotter(lambda: [ - my_odrive.axis0.encoder.pos_estimate, - my_odrive.axis1.encoder.pos_estimate, - ]) -``` -For example, to plot the approximate motor torque [Nm] and the velocity [RPM] of axis0, you would modify the function to read: -``` - # If you want to plot different values, change them here. - # You can plot any number of values concurrently. - cancellation_token = start_liveplotter(lambda: [ - ((my_odrive.axis0.encoder.vel_estimate*60), # turns/s to rpm - ((my_odrive.axis0.motor.current_control.Iq_setpoint * my_odrive.axis0.motor.config.torque_constant), # Torque [Nm] - ]) -``` -In the example below the motor is forced off axis by hand and held there. In response the motor controller increases the torque (orange line) to counteract this disturbance up to a peak of 500 N.cm at which point the motor current limit is reached. When the motor is released it returns back to its commanded position very quickly as can be seen by the spike in the motor velocity (blue line). - -![Liveplotter torque vel plot](figure_1-1.png) - -To change the scale and sample rate of the plot modify the following parameters located at the beginning of utils.py (located in Anaconda3\Lib\site-packages\odrive): - -``` -data_rate = 100 -plot_rate = 10 -num_samples = 1000 -``` - -For more examples on how to interact with the plotting functionality refer to the [Matplotlib examples.](https://matplotlib.org/examples) - -### Liveplotter from interactive odrivetool instance -You can also run `start_liveplotter(...)` directly from the interactive odrivetool prompt. This is useful if you want to issue commands or otherwise keep interacting with the odrive while plotting. - -For example you can type the following directly into the interactive prompt: `start_liveplotter(lambda: [odrv0.axis0.encoder.pos_estimate])`. Just like the examples above, you can list several parameters to plot separated by comma in the square brackets. -In general, you can plot any variable that you are able to read like normal in odrivetool. - diff --git a/docs/reStructuredText/odrivetool.rst b/docs/odrivetool.rst similarity index 100% rename from docs/reStructuredText/odrivetool.rst rename to docs/odrivetool.rst diff --git a/docs/pinout.md b/docs/pinout.md deleted file mode 100644 index 047874b2..00000000 --- a/docs/pinout.md +++ /dev/null @@ -1,42 +0,0 @@ -# Pinout - -## ODrive v4.1 - -**TODO** - -## ODrive v3.x - -| # | Label | `GPIO_MODE_DIGITAL` | `GPIO_MODE_ANALOG_IN` | `GPIO_MODE_UART_A` | `GPIO_MODE_UART_B` | `GPIO_MODE_PWM` | `GPIO_MODE_CAN_A` | `GPIO_MODE_I2C_A` | `GPIO_MODE_ENC0` | `GPIO_MODE_ENC1` | `GPIO_MODE_MECH_BRAKE` | -|----|---------------|------------------------|-----------------------|--------------------|--------------------|-----------------|------------------|-------------------|------------------|------------------|------------------------| -| 0 | _not a pin_ | | | | | | | | | | | -| 1 | GPIO1 (+) | general purpose | analog input | **UART_A.TX** | | PWM0.0 | | | | | mechanical brake | -| 2 | GPIO2 (+) | general purpose | analog input | **UART_A.RX** | | PWM0.1 | | | | | mechanical brake | -| 3 | GPIO3 | general purpose | **analog input** | | **UART_B.TX** | PWM0.2 | | | | | mechanical brake | -| 4 | GPIO4 | general purpose | **analog input** | | **UART_B.RX** | PWM0.3 | | | | | mechanical brake | -| 5 | GPIO5 | general purpose | **analog input** (*) | | | | | | | | mechanical brake | -| 6 | GPIO6 (*) (+) | **general purpose** | | | | | | | | | mechanical brake | -| 7 | GPIO7 (*) (+) | **general purpose** | | | | | | | | | mechanical brake | -| 8 | GPIO8 (*) (+) | **general purpose** | | | | | | | | | mechanical brake | -| 9 | M0.A | general purpose | | | | | | | **ENC0.A** | | | -| 10 | M0.B | general purpose | | | | | | | **ENC0.B** | | | -| 11 | M0.Z | **general purpose** | | | | | | | | | | -| 12 | M1.A | general purpose | | | | | | I2C.SCL | | **ENC1.A** | | -| 13 | M1.B | general purpose | | | | | | I2C.SDA | | **ENC1.B** | | -| 14 | M1.Z | **general purpose** | | | | | | | | | | -| 15 | _not exposed_ | general purpose | | | | | **CAN_A.RX** | I2C.SCL | | | | -| 16 | _not exposed_ | general purpose | | | | | **CAN_A.TX** | I2C.SDA | | | | - - -(*) ODrive v3.5 and later
    -(+) On ODrive v3.5 and later these pins have noise suppression filters. This is useful for step/dir input.
    - -## Notes - -* Changes to the pin configuration only take effect after `odrv0.save_configuration()` and `odrv0.reboot()` -* Bold font marks the default configuration. -* If a GPIO is set to an unsupported mode it will be left uninitialized. -* When setting a GPIO to a special purpose mode (e.g. `GPIO_MODE_UART_A`) you must also enable the corresponding feature (e.g. `.config.enable_uart_a`). -* Digital mode is a general purpose mode that can be used for these functions: step, dir, enable, encoder index, hall effect encoder, SPI encoder nCS. -* You must also connect GND between ODrive and your other board. -* ODrive v3.3 and onward have 5V tolerant GPIO pins. -* Simultaneous operation of UART_A and UART_B is currently not supported. diff --git a/docs/reStructuredText/pinout.rst b/docs/pinout.rst similarity index 100% rename from docs/reStructuredText/pinout.rst rename to docs/pinout.rst diff --git a/docs/protocol.md b/docs/protocol.md deleted file mode 100644 index fd244e65..00000000 --- a/docs/protocol.md +++ /dev/null @@ -1,86 +0,0 @@ - -# ODrive Communication Protocol # - -Communicating with an ODrive consists of a series of endpoint operations. -An endpoint can theoretically be any kind data serialized in any way. -There is a default serialization implementation for POD types; for custom types -you must (de)serialize yourself. In the future we may provide a default serializer -for structs. -The available endpoints can be enumerated by reading the JSON from endpoint 0 -and can theoretically be different for each communication interface (they are not in practice). - -Each endpoint operation can send bytes to one endpoint (referenced by its ID) -and at the same time receive bytes from the same endpoint. The semantics of -these payloads are specific to each endpoint's type, the name of which is -indicated in the JSON. - -For instance an int32 endpoint's input and output is a 4 byte little endian -representation. In general the convention for combined read/write requests is -_exchange_, i.e. the returned value is the old value. Custom endpoint handlers -may be non-compliant. - -There is a packet based version and a stream based variant of the protocol. Each -variant is employed as appropriate. For instance USB runs the packet based variant -by default while UART runs the stream based variant. - - -## Packet format ## -We will call the ODrive "server" and the PC "client". A request is a message -from the PC to the ODrive and a response is a message from the ODrive to the -PC. - -Each request-response transaction corresponds to a single endpoint operation. - -__Request__ - - - __Bytes 0, 1__ Sequence number, MSB = 0 - - Currently the server does not care about ordering and does not filter resent messages. - - __Bytes 2, 3__ Endpoint ID - - The IDs of all endpoints can be obtained from the JSON definition. The JSON definition can be obtained by reading from endpoint 0. - If (and only if) the MSB is set to 1 the client expects a response for this request. - - __Bytes 4, 5__ Expected response size - - The number of bytes that should be returned to the client. If the client doesn't need any response data, it can set this value to 0. The operation will still be acknowledged if the - MSB in EndpointID is set. - - __Bytes 6 to N-3__ Payload - - The length of the payload is determined by the total packet size. The format of the payload depends on the endpoint type. The endpoint type can be obtained from the JSON definition. - - __Bytes N-2, N-1__ - - For endpoint 0: Protocol version (currently 1). A server shall ignore packets with other values. - - For all other endpoints: The CRC16 calculated over the JSON definition using the algorithm described below, except that the initial value is set to the protocol version (currently 1). A server shall ignore packets that set this field incorrectly. - -__Response__ - - - __Bytes 0, 1__ Sequence number, MSB = 1 - - The sequence number of the request to which this is the response. - - __Bytes 2, 3__ Payload - - The length of the payload tends to be equal to the number of expected bytes as indicated - in the request. The server must not expect the client to accept more bytes than it requested. - -## Stream format ## -The stream based format is just a wrapper for the packet format. - - - __Byte 0__ Sync byte `0xAA` - - __Byte 1__ Packet length - - Currently both parties shall only emit and accept values of 0 through 127. - - __Byte 2__ CRC8 of bytes 0 and 1 (see below for details) - - __Bytes 3 to N-3__ Packet - - __Bytes N-2, N-1__ CRC16 (see below for details) - -## CRC algorithms ## - -__CRC8__ - - Polynomial: `0x37` - - Initial value: `0x42` - - No input reflection, no result reflection, no final XOR operation - - Examples: - - `0x01, 0x02, 0x03, 0x04` => `0x61` - - `0x05, 0x04, 0x03, 0x02, 0x01` => `0x64` - -__CRC16__ - - Polynomial: `0x3d65` - - Initial value: `0x1337` (or `0x0001` for the JSON CRC) - - No input reflection, no result reflection, no final XOR operation - - Examples: - - `0x01, 0x02, 0x03, 0x04` => `0x672E` - - `0x05, 0x04, 0x03, 0x02, 0x01` => `0xE251` - -You can use the online calculator at http://www.sunshine2k.de/coding/javascript/crc/crc_js.html to verify your implementation. diff --git a/docs/reStructuredText/protocol.rst b/docs/protocol.rst similarity index 100% rename from docs/reStructuredText/protocol.rst rename to docs/protocol.rst diff --git a/docs/rc-pwm.md b/docs/rc-pwm.md deleted file mode 100644 index f916fd19..00000000 --- a/docs/rc-pwm.md +++ /dev/null @@ -1,23 +0,0 @@ -# RC PWM input -You can control the ODrive directly from a hobby RC receiver. - -Any of the numerical parameters that are writable from the ODrive Tool can be hooked up to a PWM input. The [Pinout](#pinout) tells you which pins are PWM input capable. As an example, we'll configure GPIO4 to control the angle of axis 0. We want the axis to move within a range of -2 to 2 turns. - -1. Make sure you're able control the axis 0 angle by writing to `odrv0.axis0.controller.input_pos`. If you need help with this follow the [getting started guide](getting-started.md). -2. If you want to control your ODrive with the PWM input without using anything else to activate the ODrive, you can configure the ODrive such that axis 0 automatically goes operational at startup. See [here](commands.md#startup-procedure) for more information. -3. In ODrive Tool, configure the PWM input mapping - ``` - odrv0.config.gpio4_mode = GPIO_MODE_PWM - odrv0.config.gpio4_pwm_mapping.min = -2 - odrv0.config.gpio4_pwm_mapping.max = 2 - odrv0.config.gpio4_pwm_mapping.endpoint = odrv0.axis0.controller._input_pos_property - ``` - Note: you can disable the input by setting `odrv0.config.gpio4_pwm_mapping.endpoint = None` -4. Save the configuration and reboot - ``` - odrv0.save_configuration() - odrv0.reboot() - ``` -5. With the ODrive powered off, connect the RC receiver ground to the ODrive's GND and one of the RC receiver signals to GPIO4. You may try to power the receiver from the ODrive's 5V supply if it doesn't draw too much power. Power up the the RC transmitter. You should now be able to control axis 0 from one of the RC sticks. - -Be sure to setup the Failsafe feature on your RC Receiver so that if connection is lost between the remote and the receiver, the receiver outputs 0 for the velocity setpoint of both axes (or whatever is safest for your configuration). Also note that if the receiver turns off (loss of power, etc) or if the signal from the receiver to the ODrive is lost (wire comes unplugged, etc), the ODrive will continue the last commanded velocity setpoint. There is currently no timeout function in the ODrive for PWM inputs. \ No newline at end of file diff --git a/docs/reStructuredText/rc-pwm.rst b/docs/rc-pwm.rst similarity index 100% rename from docs/reStructuredText/rc-pwm.rst rename to docs/rc-pwm.rst diff --git a/docs/reStructuredText/figures/Endstop_configuration.png b/docs/reStructuredText/figures/Endstop_configuration.png deleted file mode 100644 index 56a618ff..00000000 Binary files a/docs/reStructuredText/figures/Endstop_configuration.png and /dev/null differ diff --git a/docs/reStructuredText/figures/TrapTrajPosVel.PNG b/docs/reStructuredText/figures/TrapTrajPosVel.PNG deleted file mode 100644 index 59c5bbe9..00000000 Binary files a/docs/reStructuredText/figures/TrapTrajPosVel.PNG and /dev/null differ diff --git a/docs/reStructuredText/figures/controller_with_ff.png b/docs/reStructuredText/figures/controller_with_ff.png deleted file mode 100644 index 212b1f26..00000000 Binary files a/docs/reStructuredText/figures/controller_with_ff.png and /dev/null differ diff --git a/docs/reStructuredText/figures/endstop_figure.png b/docs/reStructuredText/figures/endstop_figure.png deleted file mode 100644 index aaec20dd..00000000 Binary files a/docs/reStructuredText/figures/endstop_figure.png and /dev/null differ diff --git a/docs/reStructuredText/figures/ground_loop_bad.png b/docs/reStructuredText/figures/ground_loop_bad.png deleted file mode 100644 index a88bba3d..00000000 Binary files a/docs/reStructuredText/figures/ground_loop_bad.png and /dev/null differ diff --git a/docs/reStructuredText/figures/ground_loop_fix.png b/docs/reStructuredText/figures/ground_loop_fix.png deleted file mode 100644 index 26619383..00000000 Binary files a/docs/reStructuredText/figures/ground_loop_fix.png and /dev/null differ diff --git a/docs/resources.md b/docs/resources.md deleted file mode 100644 index 5212dfb3..00000000 --- a/docs/resources.md +++ /dev/null @@ -1,132 +0,0 @@ - -Most information in this file can be reproduced by running `dump_interrupts(odrv0)`, `dump_dma(odrv0)` and `dump_threads(odrv0)` in `odrivetool` (minor manual postprocessing was applied to the output of those functions). - -Take this info with a grain of salt as we might forget to update it from time to time. When in doubt check the file history. - -# ODrive v3.6 - -## Interrupt Vectors - - - lowest priority: 15 - - highest priority: 0 - -| # | Name | Prio | -|-----|-------------------------|------| -| -12 | MemoryManagement_IRQn | 0 | -| -11 | BusFault_IRQn | 0 | -| -10 | UsageFault_IRQn | 0 | -| -5 | SVCall_IRQn | 3 | -| -4 | DebugMonitor_IRQn | 0 | -| -2 | PendSV_IRQn | 15 | -| -1 | SysTick_IRQn | 15 | -| 6 | EXTI0_IRQn | 1 | -| 7 | EXTI1_IRQn | 1 | -| 8 | EXTI2_IRQn | 1 | -| 9 | EXTI3_IRQn | 1 | -| 10 | EXTI4_IRQn | 1 | -| 11 | DMA1_Stream0_IRQn | 4 | -| 13 | DMA1_Stream2_IRQn | 10 | -| 15 | DMA1_Stream4_IRQn | 10 | -| 16 | DMA1_Stream5_IRQn | 10 | -| 17 | DMA1_Stream6_IRQn | 10 | -| 19 | CAN1_TX_IRQn | 9 | -| 20 | CAN1_RX0_IRQn | 9 | -| 21 | CAN1_RX1_IRQn | 9 | -| 22 | CAN1_SCE_IRQn | 9 | -| 23 | EXTI9_5_IRQn | 1 | -| 40 | EXTI15_10_IRQn | 1 | -| 44 | TIM8_UP_TIM13_IRQn | 0 | -| 45 | TIM8_TRG_COM_TIM14_IRQn | 6 | -| 47 | DMA1_Stream7_IRQn | 3 | -| 50 | TIM5_IRQn | 1 | -| 52 | UART4_IRQn | 10 | -| 67 | OTG_FS_IRQn | 6 | -| 77 | OTG_HS_IRQn (aka ControlLoop_IRQn) | 5 | - - -## DMA Streams - - - lowest priority: 0 - - highest priority: 3 - -| Name | Prio | Channel | High Level Func | -|--------------|------|----------------------------------|-----------------| -| DMA1_Stream0 | 1 | 0 (SPI3_RX) | SPI_A | -| DMA1_Stream2 | 0 | 4 (UART4_RX) | UART_A | -| DMA1_Stream4 | 0 | 4 (UART4_TX) | UART_A | -| DMA1_Stream5 | 0 | 4 (USART2_RX) | UART_B | -| DMA1_Stream6 | 0 | 4 (USART2_TX) | UART_B | -| DMA1_Stream7 | 2 | 0 (SPI3_TX) | SPI_A | -| DMA2_Stream0 | 0 | 0 (ADC1) | freerunning ADC | - - -## Threads - - - lowest priority: -3 - - highest priority: 3 - -| Name | Stack Size [B] | Prio | -|---------|----------------|------| -| axis0 | 2048 | 3 | -| axis1 | 2048 | 2 | -| can | 1024 | 0 | -| startup | 2048 | 0 | -| uart | 4096 | 0 | -| usb | 4096 | 0 | - - -# ODrive v4.0 - -## Interrupt Vectors - - - lowest priority: 15 - - highest priority: 0 - -| # | Name | Prio | -|-----|-------------------------|------| -| -12 | MemoryManagement_IRQn | 0 | -| -11 | BusFault_IRQn | 0 | -| -10 | UsageFault_IRQn | 0 | -| -5 | SVCall_IRQn | 0 | -| -4 | DebugMonitor_IRQn | 0 | -| -2 | PendSV_IRQn | 15 | -| -1 | SysTick_IRQn | 15 | -| 11 | DMA1_Stream0_IRQn | 5 | -| 14 | DMA1_Stream3_IRQn | 5 | -| 15 | DMA1_Stream4_IRQn | 5 | -| 16 | DMA1_Stream5_IRQn | 5 | -| 17 | DMA1_Stream6_IRQn | 5 | -| 18 | ADC_IRQn | 1 | -| 19 | CAN1_TX_IRQn | 6 | -| 20 | CAN1_RX0_IRQn | 6 | -| 21 | CAN1_RX1_IRQn | 6 | -| 22 | CAN1_SCE_IRQn | 6 | -| 26 | TIM1_TRG_COM_TIM11_IRQn | 2 | -| 35 | SPI1_IRQn | 5 | -| 36 | SPI2_IRQn | 5 | -| 38 | USART2_IRQn | 5 | -| 45 | TIM8_TRG_COM_TIM14_IRQn | 0 | -| 47 | DMA1_Stream7_IRQn | 0 | -| 51 | SPI3_IRQn | 5 | -| 59 | DMA2_Stream3_IRQn | 5 | -| 77 | OTG_HS_IRQn | 5 | - -## DMA Streams - - - lowest priority: 0 - - highest priority: 3 - -| Name | Prio | Channel | High Level Func | -|--------------|------|----------------------------------|-----------------| -| DMA1_Stream0 | 1 | 0 (SPI3_RX) | Onboard SPI | -| DMA1_Stream3 | 0 | 0 (SPI2_RX) | Offboard SPI | -| DMA1_Stream4 | 0 | 0 (SPI2_TX) | Offboard SPI | -| DMA1_Stream5 | 0 | 4 (USART2_RX) | UART1 | -| DMA1_Stream6 | 0 | 4 (USART2_TX) | UART1 | -| DMA1_Stream7 | 1 | 0 (SPI3_TX) | Onboard SPI | -| DMA2_Stream0 | 0 | 0 (ADC1) | freerunning ADC | -| DMA2_Stream3 | 0 | 3 (SPI1_TX) | Status LED | - -## Threads - -**TODO** diff --git a/docs/screenshots/CAN_Bus_Drawing.png b/docs/screenshots/CAN_Bus_Drawing.png deleted file mode 100644 index 8be3fc6e..00000000 Binary files a/docs/screenshots/CAN_Bus_Drawing.png and /dev/null differ diff --git a/docs/screenshots/CodeAsMakefile.png b/docs/screenshots/CodeAsMakefile.png deleted file mode 100644 index 5d846bda..00000000 Binary files a/docs/screenshots/CodeAsMakefile.png and /dev/null differ diff --git a/docs/screenshots/ImportLaunch.png b/docs/screenshots/ImportLaunch.png deleted file mode 100644 index 3270ee15..00000000 Binary files a/docs/screenshots/ImportLaunch.png and /dev/null differ diff --git a/docs/screenshots/LaunchConfigFilter.png b/docs/screenshots/LaunchConfigFilter.png deleted file mode 100644 index 4a43bcfc..00000000 Binary files a/docs/screenshots/LaunchConfigFilter.png and /dev/null differ diff --git a/docs/screenshots/thermistor-voltage-divider.png b/docs/screenshots/thermistor-voltage-divider.png deleted file mode 100644 index e01c7cf9..00000000 Binary files a/docs/screenshots/thermistor-voltage-divider.png and /dev/null differ diff --git a/docs/secondOrderResponse.PNG b/docs/secondOrderResponse.PNG deleted file mode 100644 index 7199b37f..00000000 Binary files a/docs/secondOrderResponse.PNG and /dev/null differ diff --git a/docs/specifications.md b/docs/specifications.md deleted file mode 100644 index 45f3b642..00000000 --- a/docs/specifications.md +++ /dev/null @@ -1,29 +0,0 @@ - -# Specifications - -## Electrical Specifications -Besides the input voltage range, (12V to 24V for ODrive v3.6 24V, 12V to 56V for ODrive v3.6 56V), the electrical specifications of both version of ODrive v3.6 are the same. - -Note: ODrive versions after v3.5 are closed-source with respect to board files and schematics. -### ODrive v3.6 24V and 56V -- Peak current per motor: 120 Amps -- Max continuous current depends on cooling. See [this](https://discourse.odriverobotics.com/t/odrive-mosfet-temperature-rise-measurements-using-the-onboard-thermistor/972) for more details. - - Heatsink in still air: 40A per channel - - Heatsink with basic fan cooling: 75A per channel - - Heatsink with overkill fan cooling: 90A per channel -- Max motor RPM: This depends on your power supply voltage, motor, and encoder. It is the lesser of: - - motor RPM limit - - encoder RPM limit - - motor KV * 0.7 * Supply voltage - - 35000 eRPM / # of motor pole pairs - - (840M counts/minute) / encoder counts per revolution (for incremental encoders - 4 x pulses per revolution). - -### Schematic -The electrical schematic for ODrive v3.5 is available [here](https://github.com/madcowswe/ODriveHardware/blob/master/v3/v3.5docs/schematic_v3.5.pdf) in PDF format. - -## Mechanical Specifications -### STEP file -A step file for ODrive v3.5 is available [here](https://github.com/madcowswe/ODriveHardware/blob/master/v3/v3.5docs/PCB_v3.5.step) - -### Board outline and mounting hole dimensions -![board dimensions](https://raw.githubusercontent.com/madcowswe/ODriveHardware/master/v3/v3.5docs/mech_dimensions.PNG) diff --git a/docs/reStructuredText/specifications.rst b/docs/specifications.rst similarity index 100% rename from docs/reStructuredText/specifications.rst rename to docs/specifications.rst diff --git a/docs/step-direction.md b/docs/step-direction.md deleted file mode 100644 index 70af9fe3..00000000 --- a/docs/step-direction.md +++ /dev/null @@ -1,39 +0,0 @@ -# Step/direction -This is the simplest possible way of controlling the ODrive. It is also the most primitive and fragile one. So don't use it unless you must interoperate with other hardware that you don't control. - -### Pinout -* Step/dir signals: Any GPIOs can be used. Also see [Pinout](pinout.md) for more info. -* GND: you must connect the grounds of the devices together. Use any GND pin on J3 of the ODrive. - -### How to configure - - 1. Choose any two of the unused GPIOs for step/dir input. Let's say you chose GPIO7 for the step signal and GPIO8 for the dir signal. - 2. Configure the GPIO modes: - - .config.gpio7_mode = GPIO_MODE_DIGITAL_PULL_DOWN - .config.gpio8_mode = GPIO_MODE_DIGITAL - - 3. Configure the axis: - - .config.step_gpio_pin = 7 - .config.dir_gpio_pin = 8 - .config.enable_step_dir = True - - 4. Enable circular setpoints - - .controller.config.circular_setpoints = True - -After this, step and direction will be enabled when you put the axis into closed loop control. Note that to change out of step/dir, you need to set `.config.enable_step_dir = False`, go to `AXIS_STATE_IDLE`, and then back into closed loop control. - -Circular setpoints are used to keep floating point error at a manageable error for systems where the motor can rotate large amounts. If the motor is commanded out of the circular range, the position setpoint automatically wraps around to stay in the range. Two parameters are used to control this behavior: `..controller.config.circular_setpoint_range` and `..controller.config.steps_per_circular_range`. The circular setpoint range sets the operating range of input_pos, starting at 0.0. The `steps per circular range` setting controls how many steps are needed to traverse the entire range. For example, to use 1024 steps per 1 full motor turn, set - -``` -..controller.config.circular_setpoint_range = 1.0 [turns] -..controller.config.steps_per_circular_range = 1024 [steps] -``` - -The circular range is a floating point value and the steps per circular range parameter is an integer. For best results, set both parameters to powers of 2. - -The maximum step rate is pending tests, but 250kHz step rates with both axes in closed loop has been achieved. - -Please be aware that there is no enable line right now, and the step/direction interface is enabled by default, and remains active as long as the ODrive is in position control mode. To get the ODrive to go into position control mode at bootup, see how to configure the [startup procedure](commands.md#startup-procedure). diff --git a/docs/reStructuredText/step-direction.rst b/docs/step-direction.rst similarity index 100% rename from docs/reStructuredText/step-direction.rst rename to docs/step-direction.rst diff --git a/docs/stlink-wiring-cropped.jpg b/docs/stlink-wiring-cropped.jpg deleted file mode 100644 index 368524e9..00000000 Binary files a/docs/stlink-wiring-cropped.jpg and /dev/null differ diff --git a/docs/testing.md b/docs/testing.md deleted file mode 100644 index 2f1a5d86..00000000 --- a/docs/testing.md +++ /dev/null @@ -1,131 +0,0 @@ -# Automated Testing - -This section describes how to use the automated testing facilities. -You don't have to do this as an end user. - -The testing facility consists of the following components: - * **Test rig:** In the simplest case this can be a single ODrive optionally with a single motor and encoder pair. Can also be multiple ODrives with multiple axes, some of which may be mechanically coupled. - * **Test host:** The PC on which the test script runs. All ODrives must be connected to the test host via USB. - * **test-rig.yaml:** Describes your test rig. Make sure all values are correct. Incorrect values may physically break or fry your test setup. - * **test_runner.py:** This is the main script that runs all the tests. - * **..._test.py** The actual tests - -## The Tests - - - `analog_input_test.py`: Analog Input - - `calibration_test.py`: Motor calibration, encoder offset calibration, encoder direction find, encoder index search - - `can_test.py`: Partial coverage of the commands described in [CAN Protocol](can-protocol) - - `closed_loop_test.py`: Velocity control, position control (TODO: sensorless control), brake regen current hard limit, current control with velocity limiting - - `encoder_test.py`: Incremental encoder, hall effect encoder, sin/cos encoder, SPI encoders (AMS, CUI) - - `fibre_test.py`: General USB protocol tests - - `nvm_test.py`: Configuration storage - - `pwm_input_test.py`: PWM input - - `step_dir_test.py`: Step/dir input - - `uart_ascii_test.py`: Partial coverage of the commands described in [ASCII Protocol](ascii-protocol) - -All tests in a file can be run with e.g.: - - python3 uart_ascii_test.py --test-rig-yaml ../../test-rig-rpi.yaml - -See the following sections for a more detailed test flow description. - -## Our test rig - -Our test rig essentially consists of the following components: - - - an ODrive as the test subject - - a Teensy 4.0 to emulate external hardware such as encoders - - a Motor + Encoder pair for closed loop control tests - - a Raspberry Pi 4.0 as test host - - a CAN hat for the Raspberry Pi for CAN tests - -This document is therefore centered around this test rig layout. -If your test rig differs, you may be able to run some but not all of the tests. - -## How to set up a Raspberry Pi as testing host - - 1. Install Raspbian Lite on a Raspberry Pi 4.0. This is easiest if you have a keyboard, mouse and screen (micro-HDMI!). I used the [NOOBS Lite installer](https://www.raspberrypi.org/downloads/noobs/) for this. Paste the ZIP-file's contents onto a FAT32 formatted SD card (fs type `0b` in `fdisk`) and boot it. Then follow the on-screen instructions. - 2. Prepare the installation: - - sudo systemctl enable ssh - sudo systemctl start ssh - # Transfer your public key for passwordless SSH. All subsequent steps can be done via SSH. - sudo apt-get update - sudo apt-get upgrade - # Change /etc/hostname to something meaningful - - 3. Add the following lines to `/boot/config.txt`: - - `enable_uart=1` - - `dtparam=spi=on` - - `dtoverlay=spi-bcm2835-overlay` - - `dtoverlay=mcp2515-can0,oscillator=12000000,interrupt=25` - Note: These oscillator and interrupt GPIO settings here are for the "RS485 CAN HAT" I have. There appear to be multiple versions, so they may be different from yours. Check the marking on the oscillator and the schematics. - - 4. Remove the following arguments from `/boot/cmdline.txt`: - - `console=serial0,115200` - - 5. Append `ODRIVE_TEST_RIG_NAME=[test-rig-name]` to `/etc/environment`. The HWIL tests use this to look up the the file `[test-rig-name].yaml` which is supposed to describe your test rig. - - 6. Reboot. - - 7. Install the prerequisites: - - sudo apt-get install ipython3 python3-appdirs python3-yaml python3-jinja2 python3-usb python3-serial python3-can python3-scipy python3-matplotlib python3-ipdb git openocd - # Optionally, to be able to compile the firmware: - sudo apt-get install gcc-arm-none-eabi - - 8. Install Teensyduino and teensy-loader-cli: - - sudo apt-get install libfontconfig libxft2 libusb-dev - - wget https://downloads.arduino.cc/arduino-1.8.13-linuxarm.tar.xz - tar -xf arduino-1.8.13-linuxarm.tar.xz - wget https://www.pjrc.com/teensy/td_153/TeensyduinoInstall.linuxarm - chmod +x TeensyduinoInstall.linuxarm - ./TeensyduinoInstall.linuxarm --dir=arduino-1.8.13 - sudo cp -R arduino-1.8.13 /usr/share/arduino - sudo ln -s /usr/share/arduino/arduino /usr/bin/arduino - - git clone https://github.com/PaulStoffregen/teensy_loader_cli - pushd teensy_loader_cli - make - sudo cp teensy_loader_cli /usr/bin/ - sudo ln -s /usr/bin/teensy_loader_cli /usr/bin/teensy-loader-cli - popd - curl https://www.pjrc.com/teensy/49-teensy.rules | sudo tee /etc/udev/rules.d/49-teensy.rules - - 9. Add the following lines to `/etc/udev/rules.d/49-stlinkv2.rules`: - - SUBSYSTEMS=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", MODE:="0666" - SUBSYSTEMS=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="3748", MODE:="0666" - - 10. `sudo mkdir /opt/odrivetest && sudo chown $USER /opt/odrivetest` - - 11. At this point you need the ODrive repository. See next section to sync it from your main PC. We assume now that you navigated to `tools/odrive/tests/`. - - 12. `sudo ../../odrivetool udev-setup` - - 13. `sudo udevadm trigger` - - 14. Run once after every reboot: `sudo -E ipython3 --pdb test_runner.py -- --setup-host` - -## SSH testing flow - -Here's one possible workflow for developing on the local host and testing on a remote SSH host. - -We assume that the ODrive repo is at `/path/to/ODriveFirmware` and your testing host is configured under the SSH name `odrv`. - -To flash and start remote debugging: - - 1. Start OpenOCD remotely, along with a tunnel to localhost: `ssh -t odrv -L3333:localhost:3333 bash -c "\"openocd '-f' 'interface/stlink-v2.cfg' '-f' 'target/stm32f4x_stlink.cfg'\""` - You can keep this open for multiple debug sessions. Press Ctrl+C to quit. - 2. Compile the firmware. - 3. In VSCode, select the run configuration "Debug ODrive v3.x/v4.x - Remote" and press Run. This will flash the new firmware before dropping you into the debugger. - -To run a test: - - rsync -avh -e ssh /path/to/ODriveFirmware/ odrv:/opt/odrivetest --exclude="Firmware/build" --exclude="Firmware/.tup" --exclude=".git" --exclude="GUI" --delete - - ssh odrv - > cd /opt/odrivetest/tools/odrive/tests/ - > ipython3 --pdb uart_ascii_test.py - diff --git a/docs/reStructuredText/testing.rst b/docs/testing.rst similarity index 100% rename from docs/reStructuredText/testing.rst rename to docs/testing.rst diff --git a/docs/thermistors.md b/docs/thermistors.md deleted file mode 100644 index 144734fe..00000000 --- a/docs/thermistors.md +++ /dev/null @@ -1,34 +0,0 @@ -# Thermistors - -## Introduction -Thermistors are elements that change their resistance based on the temperature. They can be used to electrically measure temperature. The ODrive itself has thermistors on board near the FETs to ensure that they don't burn themselves out. In addition to this it's possible to connect your own thermistor to measure the temperature of the connected motors. There are two types of thermistors, Negative Temperature Coefficient (NTC) and Positive Temperature Coefficient (PTC). This indicates whether the resistance goes up or down when the temperature goes up or down. The ODrive only supports the NTC type thermistor. - -## FET thermistor -The temperature of the onboard FET thermistors can be read out by using the `odrivetool` under `.motor.fet_thermistor.temperature`. The odrive will automatically start current limiting the motor when the `.motor.fet_thermistor.config.temp_limit_lower` threshold is exceeded and once `.motor.fet_thermistor.config.temp_limit_upper` is exceeded the ODrive will stop controlling the motor and set an error. The lower and upper threshold can be changed, but this is not recommended. - -## Connecting motor thermistors - -To use your own thermistors with the ODrive a few things have to be clarified first. The use of your own thermistor requires one analog input pin. Under `.motor.motor_thermistor.config` the configuration of your own thermistor is available with the following fields: - -* `gpio_pin`: The GPIO input in used for this thermistor. -* `poly_coefficient_0` to `poly_coefficient_3`: Coefficient that needs to be set for your specific setup more on that in [Thermistor coefficients](#thermistor-coefficients). -* `temp_limit_lower` and `temp_limit_upper`: Same principle as the FET temperature limits. -* `enabled`: Whether this thermistor is enabled or not. - -## Voltage divider circuit -To measure a temperature with a thermistor a voltage divider circuit is used in addition with an ADC. The screenshot below is taken directly from the ODrive schematic. - -![Launch Configurations](screenshots/thermistor-voltage-divider.png "Thermistor voltage divider") - -The way this works is that the thermistor is connected in series with a known resistance value. By connecting an ADC directly after the thermistor the resistance value can be determined. For further information see [Voltage divider](https://en.wikipedia.org/wiki/Voltage_divider). While not strictly necessary, it is a good idea to add a capacitor as shown as well. This will help reduce the effect of electrical noise. A value between 470nF and 4.7uF is recommended, and any voltage rating 4V or higher. Put the capacitor physically close to the ODrive. - -To use a thermistor with the ODrive a voltage divider circuit has to be made that uses `VCCA` as the power source with `GNDA` as the ground. The voltage divider output can be connected to a GPIO pin that supports analog input. - -## Thermistor coefficients -Every thermistor and voltage divider circuit is different and thus it's necessary to let the ODrive know how to relate a voltage it measures at the GPIO pin to a temperature. The `poly_coefficient_0` to `poly_coefficient_3` under `.motor.motor_thermistor.config` are used for this. The `odrivetool` has a convenience function `set_motor_thermistor_coeffs(axis, Rload, R_25, Beta, Tmin, Tmax)` which can be used to calculate and set these coefficients. - -* `axis`: Which axis do set the motor thermistor coefficients for (`odrv0.axis0` or `odrv0.axis1`). -* `Rload`: The Ohm value of the resistor used in the voltage divider circuit. -* `R_25`: The resistance of the thermistor when the temperature is 25 degrees celsius. Can usually be found in the datasheet of your thermistor. Can also be measured manually with a multimeter. -* `Beta`: A constant specific to your thermistor. Can be found in the datasheet of your thermistor. -* `Tmin` and `Tmax`: The temperature range that is used to create the coefficients. Make sure to set this range to be wider than what is expected during operation. A good example may be -10 to 150. diff --git a/docs/reStructuredText/thermistors.rst b/docs/thermistors.rst similarity index 100% rename from docs/reStructuredText/thermistors.rst rename to docs/thermistors.rst diff --git a/docs/troubleshooting.md b/docs/troubleshooting.md deleted file mode 100644 index 72dcaa4a..00000000 --- a/docs/troubleshooting.md +++ /dev/null @@ -1,111 +0,0 @@ -# Troubleshooting - -Table of Contents: - - -- [Error codes](#error-codes) -- [USB Connectivity Issues](#usb-connectivity-issues) -- [Firmware Issues](#firmware-issues) -- [Other issues that may not produce an error code](#other-issues-that-may-not-produce-an-error-code) - - - -## Error codes -If your ODrive is not working as expected, run `odrivetool` and type `dump_errors(odrv0)` Enter. This will dump a list of all the errors that are present. To clear all the errors, you can run `odrv0.clear_errors()`. - -With this information you can look up the API documentation for your error(s): -* System error flags documented [here](api/odrive.error). -* Axis error flags documented [here](api/odrive.axis.error). -* Motor error flags documented [here](api/odrive.motor.error). -* Encoder error flags documented [here](api/odrive.encoder.error). -* Controller error flags documented [here](api/odrive.controller.error). -* Sensorless estimator error flags documented [here](odrive.sensorlessestimator.error). - -### What if `dump_errors()` gives me python errors? -If you get output like this: -
    Show code:
    - -```py -In [1]: dump_errors(odrv0) -axis0 ---------------------------------------------------------------------------- -AttributeError Traceback (most recent call last) -~/.local/lib/python3.6/site-packages/fibre/shell.py in -----> 1 dump_errors(odrv0) - -~/.local/lib/python3.6/site-packages/odrive/utils.py in dump_errors(odrv, clear) - 78 ('axis', axis, {k: v for k, v in odrive.enums.__dict__ .items() if k.startswith("AXIS_ERROR_")}), - 79 ('motor', axis.motor, {k: v for k, v in odrive.enums.__dict__ .items() if k.startswith("MOTOR_ERROR_")}), ----> 80 ('fet_thermistor', axis.fet_thermistor, {k: v for k, v in odrive.enums.__dict__ .items() if k.startswith("THERMISTOR_CURRENT_LIMITER_ERROR")}), - 81 ('motor_thermistor', axis.motor_thermistor, {k: v for k, v in odrive.enums.__dict__ .items() if k.startswith("THERMISTOR_CURRENT_LIMITER_ERROR")}), - 82 ('encoder', axis.encoder, {k: v for k, v in odrive.enums.__dict__ .items() if k.startswith("ENCODER_ERROR_")}), - -~/.local/lib/python3.6/site-packages/fibre/remote_object.py in __getattribute__(self, name) - 243 return attr - 244 else: ---> 245 return object.__getattribute__(self, name) - 246 #raise AttributeError("Attribute {} not found".format(name)) - 247 - -AttributeError: 'RemoteObject' object has no attribute 'fet_thermistor' -``` - -
    -when you call `dump_errors()`, you have a version mismatch between odrivetool and the firmware on your ODrive. To get the newest version of odrivetool, you can run `pip install odrive --upgrade`. To get the newest ODrive firmware, run `odrivetool dfu`. See the [odrivetool](odrivetool.md#device-firmware-update) page for more details. - -## USB Connectivity Issues - - * Try turning it off and on again (the ODrive, the script, the PC) - * Make sure you're using the latest firmware and python tools release - * **Linux**: Type `lsusb` to list all USB devices. Verify that your ODrive is listed. - * **Linux**: Make sure you [set up your udev rules](getting-started#downloading-and-installing-tools) correctly. - * **Windows**: Right-click on the start menu and open "Device Manager". Verify that your ODrive is listed. - * **Windows**: Use the [Zadig utility](http://zadig.akeo.ie/) to verify the driver is set to `WinUSB` or `libusb-win32`. Note that there are two options listed in Zadig for ODrive: `ODrive 3.x Native Interface (Interface 2)` and `ODrive 3.x CDC Interface (Interface 0)`. Only the driver setting of the native interface is important to `odrivetool`. - * Ensure that no other ODrive program is running - * Run `odrivetools` with the `--verbose` option. - * Run `PYUSB_DEBUG=debug odrivetools` to get even more log output. - * If you're a developer you can use Wireshark to capture USB traffic. - * Try a different USB cable - * Try routing your USB cable so that it is far away from the motor and PSU cables to reduce EMI - -## Firmware Issues - -### Failure to build the firmware when running `make` -- Clear out temporary files from previous compiles by first running `make clean` to prevent conflicts. -- **Windows users**: Confirm that tup has been correctly added to path by running `env|grep PATH` in Git Bash. If you see no mention of tup then you must [add its location to your PATH environment variable.](https://docs.alfresco.com/4.2/tasks/fot-addpath.html). Note that you may need to restart for the added path to take effect. - -### Failure to flash the firmware when running `make flash` -- If using an ST-link, confirm that the ST-link is connected the correct pins and that you have power supplied to the board. This can be by the 5V pin on the ST link or the main DC power jack. No power is supplied over the USB connection. - -## Other issues that may not produce an error code - -### Motor cuts off or spins uncontrollably at high rotational speeds (ie: > 5000 RPM) -- You may be approaching the limit of your encoder. The 2400 count/rotation encoders that were initially included with odrive are realistically limited to around 5000 RPM. Exceeding this speed causes the odrive to lose track of position. This can only be fixed by using an alternative encoder or gearing down the output of your motor onto your encoder so that it still sees < 5000RPM at full speed. If using the gearing options be sure to change your counts/rotation accordingly. - -### Motor vibrates when stationary or makes constant noise - -- Likely due to incorrect gains, specifically `vel_gain` may be set too high. Try following the [tuning procedure](control.md#Tuning). -- Check encoder shaft connection. Grub screws may vibrate lose with time. If using a CUI shaft encoder try remounting the plastic retaining ring and confirm that it is not coming into contact with the encoder housing. Also confirm that the encoder is securely mounted. -- If you are using a high resolution encoder (>4000 counts/rotation) then increasing encoder_pll_bandwidth may help reduce vibration. -- If you connect your motor to an object with a large moment of inertia (such as a flywheel) this will help reduce vibrations at high gians. However, make sure that all connections are ridged. Cheap shaft couplers or belts under low tension can introduce enough flex into a system that the motor may still vibrate independently. - -### Motor overshoots target position or oscillates back and forth -- Likely due to incorrect gains for a given motor current limit. Specifically `pos_gain` is set too high. Try following the [tuning procedure](control.md#Tuning). -- Increase the current limit of your motor for more torque. - -### Motor slowly starts to increase in speed -- Encoder has likely slipped. This may occur when your motor makes a hard stop or violently vibrates causing something to come lose. Power the board off and on again so that it undertakes a new calibration. If you are using an index search on startup then you will need to repeat the index calibration process. - -### Motor feels like it has less torque than it should and/or gets hot sitting still while under no load. -- Encoder has likely slipped causing the motor controller to commutate the wrong windings slightly which reduces output torque and produces excess heat as the motor 'fights itself'. -- This can also be caused if the rotor bell slips on the motor shaft. On some motors the rotor bell is secured against the shaft with a grub screw. Confirm that this screw is tight enough. For further details on how to resolve this issue see [this forum post](https://discourse.odriverobotics.com/t/motor-gets-hot-has-less-torque-in-one-direction-than-the-other/2394). - -### False steps or direction changes when using step/dir -- Prior to Odrive board V3.5 no filtering is present on the GPIO pins used for step/dir interface and so inductively coupled noise may causes false steps to be detected. Odrive V3.5 and has onboard filtering to resolve this issue. -- If you experience this issue use a twisted pair cable between your microcontroller that’s generating the step/dir signals and your odrive board. A section cut from cat-5 cable works well as does just twisting some normal insulated wire together. -- Ensure that the step/dir signal cables are not draped over the odrive board, are not running in parallel to the motor or power supply cables. -- If the above does not resolve your issue on V3.4 boards and lower try adding a ~22 Ohm resistor in series with the step and direction pins along with a ~ 4.7 nF capacitor between the ground pin and the step and dir pins such as shown [here](https://cdn.discordapp.com/attachments/369667319280173069/420811057431445504/IMG_20180306_211224.jpg). - -### Index search never completes - -- There are some GPIO pin interrupt collisions on ODrive 3.6 that could cause index search to fail in certain conditions. If you are using both step/dir and index pins, we recommend disabling `step_dir_always_on`. For more information, see this thread: https://github.com/odriverobotics/ODrive/issues/605#issuecomment-971576393 diff --git a/docs/reStructuredText/troubleshooting.rst b/docs/troubleshooting.rst similarity index 100% rename from docs/reStructuredText/troubleshooting.rst rename to docs/troubleshooting.rst diff --git a/docs/uart.md b/docs/uart.md deleted file mode 100644 index 0dd4cf85..00000000 --- a/docs/uart.md +++ /dev/null @@ -1,25 +0,0 @@ -# UART Interface - -The ODrive's UART_A interface is enabled by default with a baudrate of 115200 on the pins as shown in [Pinout](pinout). - -To use UART connect it like this: - -* Tx of the ODrive <=> Rx of other device -* Rx of the ODrive <=> Tx of other device -* GND of the ODrive (use any GND pin on J3 of the ODrive) <=> GND of the other device - -The logic level of the ODrive is 3.3V. The GPIOs are 5V tolerant. - -You can use `odrv0.config.uart_a_baudrate` to change the baudrate and `odrv0.config.enable_uart_a` to disable/reenable UART_A. The UART_A port can run the [Native Protocol](native-protocol) or the [ASCII Protocol](ascii-protocol), but not both at the same time. You can configure this by setting `odrv0.config.uart0_protocol` to either `STREAM_PROTOCOL_TYPE_ASCII_AND_STDOUT` for the ASCII protocol or `STREAM_PROTOCOL_TYPE_FIBRE` for the native protocol. - -### How to use UART on GPIO3/4 - -If you need GPIO1/2 for some function other than UART you can disable UART_A and instead use UART_B on GPIO3/4. Here's how you do it: - - odrv0.config.enable_uart_a = False - odrv0.config.gpio1_mode = GPIO_MODE_DIGITAL - odrv0.config.gpio2_mode = GPIO_MODE_DIGITAL - odrv0.config.enable_uart_b = True - odrv0.config.gpio3_mode = GPIO_MODE_UART_B - odrv0.config.gpio4_mode = GPIO_MODE_UART_B - odrv0.reboot() diff --git a/docs/reStructuredText/uart.rst b/docs/uart.rst similarity index 100% rename from docs/reStructuredText/uart.rst rename to docs/uart.rst diff --git a/docs/usb.md b/docs/usb.md deleted file mode 100644 index 10dc0fa6..00000000 --- a/docs/usb.md +++ /dev/null @@ -1,28 +0,0 @@ -# USB - -This page documents the low level USB configuration. If you're looking for a higher level protocol documentation see [Native Protocol](native-protocol) and [ASCII Protocol](ascii-protocol). - -This page assumes that you are familiar with the general USB architecture, in particular with terms like "configuration", "interface" and "endpoint". - -On USB the ODrive provides a single configuration which is a composite device consisting of a CDC device (virtual COM port) and a vendor specific device. - -
    What is a composite device?
    -A composite device is a device where interfaces are grouped by interface association descriptors. For such devices, the host OS loads an intermediate driver, so that each of the interface groups can be treated like a separate device and have its own host-side driver attached. -
    - -The following interface groups are present: - - * Interface Association: Communication Device Class (CDC) - * Interface 0: - * Endpoint `0x82`: CDC commands - * Interface 1: - * Endpoint `0x01`: CDC data OUT - * Endpoint `0x81`: CDC data IN - * Interface Association: Vendor Specific Device Class - * Interface 2: - * Endpoint `0x03`: data OUT - * Endpoint `0x83`: data IN - -The CDC interface (endpoint pair `0x01, 0x81`) runs the [ASCII Protocol](ascii-protocol) by default (see `odrv0.config.enable_ascii_protocol_on_usb`). The vendor specific interface (endpoint pair `0x03, 0x83`) runs the [Native Protocol](native-protocol) (the packet based variant). - -The two interfaces can not (yet) be used simultaneously. diff --git a/docs/reStructuredText/usb.rst b/docs/usb.rst similarity index 100% rename from docs/reStructuredText/usb.rst rename to docs/usb.rst