diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index fe8490c2e..c784b2310 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -22,16 +22,8 @@ jobs: lfs: "true" # This makes sure that $GITHUB_WORKSPACE is the catkin workspace path path: "src/mrover" - - name: Ensure Python Requirements - run: . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && pip install --no-cache-dir -e "$GITHUB_WORKSPACE/src/mrover[dev]" - name: Style Check run: . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && cd $GITHUB_WORKSPACE/src/mrover/ && ./style.sh - - name: Update ROS APT - if: github.event.pull_request.draft == false - run: runuser -u mrover -- rosdep update - - name: Ensure ROS APT Requirements - if: github.event.pull_request.draft == false - run: runuser -u mrover -- rosdep install --from-paths "$GITHUB_WORKSPACE/src" --ignore-src -r -y --rosdistro noetic - name: Copy Catkin Profiles if: github.event.pull_request.draft == false run: rsync -r $GITHUB_WORKSPACE/src/mrover/ansible/roles/build/files/profiles $GITHUB_WORKSPACE/.catkin_tools @@ -42,7 +34,7 @@ jobs: if: github.event.pull_request.draft == false && github.event.pull_request.base.ref != 'refs/heads/master' run: . /opt/ros/noetic/setup.sh && . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && catkin build - name: Build With Clang Tidy - if : github.event_name == 'push' && github.event.pull_request.base.ref == 'refs/heads/master' + if: github.event_name == 'push' && github.event.pull_request.base.ref == 'refs/heads/master' run: . /opt/ros/noetic/setup.sh && . /home/mrover/catkin_ws/src/mrover/venv/bin/activate && catkin build -DCMAKE_CXX_CLANG_TIDY=clang-tidy-16 - name: Test if: github.event.pull_request.draft == false diff --git a/.gitmodules b/.gitmodules index 4416faa01..a5bd0ee01 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,18 +1,8 @@ -[submodule "deps/libde265"] - path = deps/libde265 - url = https://github.com/strukturag/libde265.git - shallow = true - branch = v1.0.15 [submodule "deps/dawn"] path = deps/dawn url = https://dawn.googlesource.com/dawn shallow = true - branch = chromium/6108 -[submodule "deps/emsdk"] - path = deps/emsdk - url = git@github.com:emscripten-core/emsdk.git - shallow = true - branch = 3.1.53 + branch = chromium/6376 [submodule "deps/manif"] path = deps/manif url = https://github.com/artivis/manif.git diff --git a/CMakeLists.txt b/CMakeLists.txt index ac179ac15..7c68974f1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -143,42 +143,40 @@ target_link_libraries(lie PUBLIC MANIF::manif) ## ESW -if (NOT APPLE) - mrover_add_vendor_header_only_library(moteus deps/mjbots) - mrover_add_header_only_library(can_device src/esw/can_device) - mrover_add_library(motor_library src/esw/motor_library/*.cpp src/esw/motor_library) - target_link_libraries(motor_library PUBLIC can_device moteus) - - if (NetLink_FOUND AND NetLinkRoute_FOUND) - mrover_add_nodelet(can_driver src/esw/can_driver/*.cpp src/esw/can_driver src/esw/can_driver/pch.hpp) - mrover_nodelet_link_libraries(can_driver ${NetLink_LIBRARIES} ${NetLinkRoute_LIBRARIES}) - mrover_nodelet_include_directories(can_driver ${NetLink_INCLUDE_DIRS} ${NetLinkRoute_INCLUDE_DIRS}) - endif () - - macro(mrover_add_esw_bridge_node name sources) - mrover_add_node(${name} ${sources}) - target_link_libraries(${name} PRIVATE can_device motor_library) - endmacro() - - mrover_add_esw_bridge_node(arm_hw_bridge src/esw/arm_hw_bridge/*.cpp) - mrover_add_esw_bridge_node(arm_translator_bridge src/esw/arm_translator_bridge/*.cpp src/esw/arm_translator_bridge/*.hpp) - mrover_add_esw_bridge_node(cache_bridge src/esw/cache_bridge/*.cpp) - mrover_add_esw_bridge_node(drive_bridge src/esw/drive_bridge/*.cpp) - mrover_add_esw_bridge_node(led_hw_bridge src/esw/led_hw_bridge/*.cpp) - mrover_add_esw_bridge_node(led src/esw/led/*.cpp) - mrover_add_esw_bridge_node(mast_gimbal_bridge src/esw/mast_gimbal_bridge/*.cpp) - mrover_add_esw_bridge_node(pdb_bridge src/esw/pdb_bridge/*.cpp) - mrover_add_esw_bridge_node(sa_hw_bridge src/esw/sa_hw_bridge/*.cpp) - mrover_add_esw_bridge_node(sa_translator_bridge src/esw/sa_translator_bridge/*.cpp) - mrover_add_esw_bridge_node(science_bridge src/esw/science_bridge/*.cpp) - mrover_add_esw_bridge_node(brushless_test_bridge src/esw/brushless_test_bridge/*.cpp motor_library) - mrover_add_esw_bridge_node(brushed_test_bridge src/esw/brushed_test_bridge/*.cpp) - mrover_add_esw_bridge_node(test_arm_bridge src/esw/test_arm_bridge/*.cpp) - mrover_add_esw_bridge_node(pdb_test_bridge src/esw/pdb_test_bridge/*.cpp) - mrover_add_esw_bridge_node(arm_position_test_bridge src/esw/arm_position_test_bridge/*.cpp) - # mrover_add_esw_bridge_node(sa_sensor src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino) +mrover_add_vendor_header_only_library(moteus deps/mjbots) +mrover_add_header_only_library(can_device src/esw/can_device) +mrover_add_library(motor_library src/esw/motor_library/*.cpp src/esw/motor_library) +target_link_libraries(motor_library PUBLIC can_device moteus) + +if (NetLink_FOUND AND NetLinkRoute_FOUND) + mrover_add_nodelet(can_driver src/esw/can_driver/*.cpp src/esw/can_driver src/esw/can_driver/pch.hpp) + mrover_nodelet_link_libraries(can_driver ${NetLink_LIBRARIES} ${NetLinkRoute_LIBRARIES}) + mrover_nodelet_include_directories(can_driver ${NetLink_INCLUDE_DIRS} ${NetLinkRoute_INCLUDE_DIRS}) endif () +macro(mrover_add_esw_bridge_node name sources) + mrover_add_node(${name} ${sources}) + target_link_libraries(${name} PRIVATE can_device motor_library) +endmacro() + +mrover_add_esw_bridge_node(arm_hw_bridge src/esw/arm_hw_bridge/*.cpp) +mrover_add_esw_bridge_node(arm_translator_bridge src/esw/arm_translator_bridge/*.cpp src/esw/arm_translator_bridge/*.hpp) +mrover_add_esw_bridge_node(cache_bridge src/esw/cache_bridge/*.cpp) +mrover_add_esw_bridge_node(drive_bridge src/esw/drive_bridge/*.cpp) +mrover_add_esw_bridge_node(led_hw_bridge src/esw/led_hw_bridge/*.cpp) +mrover_add_esw_bridge_node(led src/esw/led/*.cpp) +mrover_add_esw_bridge_node(mast_gimbal_bridge src/esw/mast_gimbal_bridge/*.cpp) +mrover_add_esw_bridge_node(pdb_bridge src/esw/pdb_bridge/*.cpp) +mrover_add_esw_bridge_node(sa_bridge src/esw/sa_bridge/*.cpp) +mrover_add_esw_bridge_node(science_bridge src/esw/science_bridge/*.cpp) +mrover_add_esw_bridge_node(brushless_test_bridge src/esw/brushless_test_bridge/*.cpp) +mrover_add_esw_bridge_node(brushed_test_bridge src/esw/brushed_test_bridge/*.cpp) +mrover_add_esw_bridge_node(science_test_bridge src/esw/science_test_bridge/*.cpp) +mrover_add_esw_bridge_node(test_arm_bridge src/esw/test_arm_bridge/*.cpp) +mrover_add_esw_bridge_node(pdb_test_bridge src/esw/pdb_test_bridge/*.cpp) +# mrover_add_esw_bridge_node(arm_position_test_bridge src/esw/arm_position_test_bridge/*.cpp) +# mrover_add_esw_bridge_node(sa_sensor src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino) + ## Perception mrover_add_library(websocket_server src/esw/websocket_server/*.cpp src/esw/websocket_server) diff --git a/ansible/roles/build/tasks/main.yml b/ansible/roles/build/tasks/main.yml index bc8d866b6..6d91a9651 100644 --- a/ansible/roles/build/tasks/main.yml +++ b/ansible/roles/build/tasks/main.yml @@ -96,6 +96,7 @@ - libopencv-dev - libgstreamer1.0-dev - libgstreamer-plugins-base1.0-dev + - vainfo - name: Install Local APT Packages become: True @@ -205,3 +206,8 @@ - "{{ catkin_workspace }}/src/mrover[dev]" virtualenv: "{{ catkin_workspace }}/src/mrover/venv" virtualenv_command: /usr/bin/python3.10 -m venv + +- name: Install Chromium + become: True + snap: + name: chromium diff --git a/ansible/roles/dev/files/home/.zshrc b/ansible/roles/dev/files/home/.zshrc index 9f5ba8429..6cf4f05bd 100644 --- a/ansible/roles/dev/files/home/.zshrc +++ b/ansible/roles/dev/files/home/.zshrc @@ -70,7 +70,7 @@ ZSH_THEME="mrover" # Custom plugins may be added to $ZSH_CUSTOM/plugins/ # Example format: plugins=(rails git textmate ruby lighthouse) # Add wisely, as too many plugins slow down shell startup. -plugins=(git virtualenvwrapper fzf) +plugins=(git virtualenvwrapper fzf zsh-autosuggestions zsh-syntax-highlighting) source $ZSH/oh-my-zsh.sh diff --git a/ansible/roles/dev/tasks/main.yml b/ansible/roles/dev/tasks/main.yml index 641a81aad..e064a2571 100644 --- a/ansible/roles/dev/tasks/main.yml +++ b/ansible/roles/dev/tasks/main.yml @@ -13,6 +13,16 @@ dest: ~/ recursive: true +- name: ZSH Automatic Suggestions Plugin + git: + repo: https://github.com/zsh-users/zsh-autosuggestions + dest: ~/.oh-my-zsh/custom/plugins/zsh-autosuggestions + +- name: ZSH Syntax Highlighting Plugin + git: + repo: https://github.com/zsh-users/zsh-syntax-highlighting + dest: ~/.oh-my-zsh/custom/plugins/zsh-syntax-highlighting + - name: Use ZSH as a default shell become: true command: chsh --shell /usr/bin/zsh {{ ansible_user_id }} diff --git a/ansible/roles/esw/tasks/main.yml b/ansible/roles/esw/tasks/main.yml index c734c770b..f9a81d7a5 100644 --- a/ansible/roles/esw/tasks/main.yml +++ b/ansible/roles/esw/tasks/main.yml @@ -13,6 +13,13 @@ become: true command: udevadm trigger --subsystem-match=tty +- name: Install fdcanusb Binary + become: true + copy: + src: files/bin/fdcanusb_daemon + dest: /usr/local/bin/ + mode: 0755 + - name: Install Moteus GUI pip: name: moteus_gui diff --git a/ansible/roles/jetson_build/tasks/main.yml b/ansible/roles/jetson_build/tasks/main.yml index e4258e594..9736001c0 100644 --- a/ansible/roles/jetson_build/tasks/main.yml +++ b/ansible/roles/jetson_build/tasks/main.yml @@ -23,17 +23,17 @@ state: latest name: - zstd # Required to unpack ZED installer - - cuda + - cuda-12-3 - nvidia-jetpack - name: ZED SDK Download get_url: - url: https://download.stereolabs.com/zedsdk/4.0/l4t35.4/jetsons - dest: /tmp/ZED_SDK_Tegra_L4T35.4_v4.0.7.zstd.run + url: https://download.stereolabs.com/zedsdk/4.1/l4t35.4/jetsons + dest: /tmp/ZED_SDK_Tegra_L4T35.4_v4.1.zstd.run mode: 0755 - name: ZED SDK Install # Silent mode prevents any user input prompting - command: /tmp/Downloads/ZED_SDK_Tegra_L4T35.4_v4.0.7.zstd.run -- silent + command: /tmp/Downloads/ZED_SDK_Tegra_L4T35.4_v4.1.zstd.run -- silent args: creates: /usr/local/zed diff --git a/ansible/roles/jetson_services/files/99-usb-serial.rules b/ansible/roles/jetson_services/files/99-usb-serial.rules deleted file mode 100644 index dfdc52298..000000000 --- a/ansible/roles/jetson_services/files/99-usb-serial.rules +++ /dev/null @@ -1,2 +0,0 @@ -SUBSYSTEM=="tty", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", SYMLINK+="raman" -SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0043", SYMLINK+="auton_led" diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.service deleted file mode 100644 index 7480d3f85..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 0 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5000 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-0.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.service deleted file mode 100644 index 1032633da..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 1 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5001 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-1.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.service deleted file mode 100644 index deb6543dc..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 2 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5002 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-2.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.service b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.service deleted file mode 100644 index 06be0fc58..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.service +++ /dev/null @@ -1,9 +0,0 @@ -[Unit] -Description=Base Station Gstreamer Service 3 - -[Service] -Environment="DISPLAY=:1" -Environment="XAUTHORITY=/home/mrover/.Xauthority" -User=mrover -ExecStart=/usr/bin/gst-launch-1.0 udpsrc port=5003 ! "application/x-rtp, encoding-name=(string)H264, payload=96" ! rtph264depay ! decodebin ! videoconvert ! autovideosink -Restart=on-failure \ No newline at end of file diff --git a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.timer b/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.timer deleted file mode 100644 index 402352bf1..000000000 --- a/ansible/roles/jetson_services/files/rover-base-station-gstreamer-3.timer +++ /dev/null @@ -1,5 +0,0 @@ -[Timer] -OnBootSec=20s - -[Install] -WantedBy=multi-user.target \ No newline at end of file diff --git a/bun.lockb b/bun.lockb deleted file mode 100755 index ec15adb6b..000000000 Binary files a/bun.lockb and /dev/null differ diff --git a/cmake/deps.cmake b/cmake/deps.cmake index 89bf0dd88..b73637ce8 100644 --- a/cmake/deps.cmake +++ b/cmake/deps.cmake @@ -1,3 +1,9 @@ +# The simulator will only be built if Dawn (low-level graphics API) is found: +# 1) Installed system-wide with the .deb package in the pkg/ folder. This is ONLY for Ubuntu 20 +# If this is the case then "find_package" will set "dawn_FOUND" to true +# 2) Built from source with the build_dawn.sh script. This is for all other systems (non-Ubuntu, macOS, etc.) +# If this is the case libwebgpu_dawn.* will be found in deps/dawn/out/Release and "dawn_FOUND" will be set to true + find_package(dawn QUIET) if (dawn_FOUND) message(STATUS "Using Dawn system install") @@ -43,6 +49,7 @@ find_package(OpenCV REQUIRED) find_package(ZED QUIET) find_package(Eigen3 REQUIRED) +# Same idea as dawn, ideally installed via a package, but if not then build from source find_package(manif QUIET) if (NOT manif_FOUND) if (EXISTS ${CMAKE_CURRENT_LIST_DIR}/../deps/manif/include/manif) @@ -55,6 +62,8 @@ if (NOT manif_FOUND) endif () endif () +# These are old packages so they do not support "find_package" and must be found with pkg-config +# Thankfully CMake has a built-in module for this find_package(PkgConfig REQUIRED) pkg_search_module(NetLink libnl-3.0 QUIET) pkg_search_module(NetLinkRoute libnl-route-3.0 QUIET) diff --git a/config/esw.yaml b/config/esw.yaml index ab80e6d2c..cff8e0030 100644 --- a/config/esw.yaml +++ b/config/esw.yaml @@ -11,6 +11,12 @@ gps: can: devices: + - name: "jetson" + bus: 0 + id: 0x10 + - name: "jetson" + bus: 1 + id: 0x10 - name: "jetson" bus: 2 id: 0x10 @@ -33,28 +39,28 @@ can: bus: 2 id: 0x16 - name: "back_right" - bus: 3 + bus: 2 id: 0x15 - name: "joint_a" - bus: 3 + bus: 1 id: 0x20 - name: "joint_b" - bus: 3 + bus: 1 id: 0x21 - name: "joint_c" - bus: 3 + bus: 1 id: 0x22 - name: "joint_de_0" - bus: 3 + bus: 1 id: 0x23 - name: "joint_de_1" - bus: 3 + bus: 1 id: 0x24 - name: "allen_key" - bus: 3 + bus: 1 id: 0x25 - name: "gripper" - bus: 3 + bus: 1 id: 0x26 - name: "mast_gimbal_y" bus: 3 @@ -63,22 +69,22 @@ can: bus: 3 id: 0x27 - name: "sa_x" - bus: 3 + bus: 1 id: 0x29 - name: "sa_y" - bus: 3 + bus: 1 id: 0x30 - name: "sa_z" - bus: 3 + bus: 1 id: 0x31 - name: "sampler" - bus: 3 + bus: 1 id: 0x32 - name: "sensor_actuator" - bus: 3 + bus: 1 id: 0x33 - name: "cache" - bus: 3 + bus: 2 id: 0x34 - name: "pdlb" bus: 3 @@ -89,36 +95,37 @@ can: brushless_motors: controllers: + # TODO(quintin): These units are in terms of the rotor revolutions, not the output shaft. + # At some point we should modify the moteus firmware to set the rotor to output ratio. front_left: - velocity_multiplier: -1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -20.0 + max_velocity: 20.0 + max_torque: 5.0 front_right: - velocity_multiplier: 1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -20.0 + max_velocity: 20.0 + max_torque: 5.0 middle_left: - velocity_multiplier: -1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -20.0 + max_velocity: 20.0 + max_torque: 5.0 middle_right: - velocity_multiplier: 1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -20.0 + max_velocity: 20.0 + max_torque: 5.0 back_left: - velocity_multiplier: -1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -20.0 + max_velocity: 20.0 + max_torque: 5.0 back_right: - velocity_multiplier: 1.0 - min_velocity: -70.0 - max_velocity: 70.0 + min_velocity: -20.0 + max_velocity: 20.0 + max_torque: 5.0 joint_a: - velocity_multiplier: 1.0 - min_velocity: -100.0 - max_velocity: 100.0 - is_linear: true - rad_to_meters_ratio: 1236.8475 # 5.0 = 5 motor radians -> 1 meter + # 1236.8475 rad/meter, or 196.850393476 rev/meter, and we want a max vel of 40 meter/s. + # gear ratio is currently at 0.005080 revolutions = 1 meter + min_velocity: -0.10 # this means -0.10 meters per second. + max_velocity: 0.10 limit_0_present: true limit_1_present: true limit_0_enabled: true @@ -129,32 +136,34 @@ brushless_motors: limit_1_is_active_high: false limit_0_used_for_readjustment: true limit_1_used_for_readjustment: true - limit_0_readjust_position: 0.0 # radians TODO - limit_1_readjust_position: 494.739 # radians + limit_0_readjust_position: 0.4 + limit_1_readjust_position: 0.0 limit_max_forward_pos: true limit_max_backward_pos: true max_forward_pos: 0.4 max_backward_pos: 0.0 + max_torque: 20.0 joint_c: - velocity_multiplier: -1.0 - min_velocity: -3.0 # gear ratio: 484:1 - max_velocity: 3.0 - min_position: 0.0 - max_position: 3.8 # 220 degrees of motion + min_velocity: -0.08 # in terms of output + max_velocity: 0.08 # max output shaft speed: 5 rpm (for now) + min_position: -0.125 + max_position: 0.30 # 220 degrees of motion is the entire range + max_torque: 20.0 joint_de_0: - velocity_multiplier: 1.0 - min_velocity: -67.0 - max_velocity: 67.0 + min_velocity: -5.0 + max_velocity: 5.0 + min_position: -10000.0 + max_position: 10000.0 + max_torque: 20.0 joint_de_1: - velocity_multiplier: 1.0 - min_velocity: -67.0 - max_velocity: 67.0 + min_velocity: -5.0 + max_velocity: 5.0 + min_position: -10000.0 + max_position: 10000.0 + max_torque: 20.0 sa_z: - velocity_multiplier: 1.0 - min_velocity: -100.0 - max_velocity: 100.0 - is_linear: true - rad_to_meters_ratio: 157.48 #rad/m + min_velocity: -0.05 + max_velocity: 0.05 limit_0_present: false limit_1_present: false limit_0_enabled: true @@ -167,10 +176,7 @@ brushless_motors: limit_1_used_for_readjustment: true limit_0_readjust_position: 0.0 # radians TODO limit_1_readjust_position: 0.0 # radians TODO - max_torque: 0.5 -joint_de: - pitch_offset: 0.0 - roll_offset: 0.0 + max_torque: 30.0 brushed_motors: controllers: @@ -215,16 +221,15 @@ brushed_motors: # max_backward_pos: 0.0 # calibration_throttle: 5.0 joint_b: - velocity_multiplier: 1.0 + is_inverted: False gear_ratio: 1.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: true limit_0_enabled: true limit_0_is_active_high: false limit_0_limits_fwd: false - limit_0_used_for_readjustment: true + limit_0_used_for_readjustment: false abs_present: true abs_is_fwd_polarity: true - limit_0_readjust_position: -0.7853981633974483 # radians abs_ratio: 1.0 # encoder ratio compared to motor abs_offset: 0.0 # 0 for joint position corresponds to this radians reading by absolute encoder driver_voltage: 12.0 # used to calculate max pwm @@ -236,7 +241,6 @@ brushed_motors: max_velocity: 1.0 calibration_throttle: 0.5 # throttle during calibration allen_key: - velocity_multiplier: 1.0 gear_ratio: 30.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: true limit_1_present: true @@ -255,9 +259,8 @@ brushed_motors: quad_ratio: 1.0 # encoder ratio compared to motor driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 12.0 # used to calculate max pwm - calibration_throttle: 0.5 # throttle during calibration + calibration_throttle: 0.9 # throttle during calibration, does not move unless close to max voltage gripper: - velocity_multiplier: 1.0 gear_ratio: 47.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint quad_present: false quad_is_fwd_polarity: true @@ -268,19 +271,15 @@ brushed_motors: motor_max_voltage: 12.0 # used to calculate max pwm calibration_throttle: 0.5 # throttle during calibration mast_gimbal_y: - velocity_multiplier: 1.0 gear_ratio: 1000.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 12.0 # used to calculate max pwm mast_gimbal_z: - velocity_multiplier: 1.0 gear_ratio: 1000.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 12.0 # used to calculate max pwm sa_x: - velocity_multiplier: 1.0 gear_ratio: 75.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint - is_linear: true rad_to_meters_ratio: 1.0 #TODO 5.0 = 5 motor radians -> 1 meter limit_0_present: false limit_1_present: false @@ -308,12 +307,10 @@ brushed_motors: max_velocity: 1.0 calibration_throttle: 0.5 # throttle during calibration sa_y: - velocity_multiplier: -1.0 gear_ratio: 75.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint - is_linear: true rad_to_meters_ratio: 1.0 #TODO 5.0 = 5 motor radians -> 1 meter - limit_0_present: false - limit_1_present: false + limit_0_present: true + limit_1_present: true limit_0_enabled: true limit_1_enabled: true limit_0_is_active_high: false @@ -334,7 +331,6 @@ brushed_motors: calibration_throttle: 0.5 # throttle during calibration sampler: gear_ratio: 75.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint - is_linear: true rad_to_meters_ratio: 1.0 #TODO 5.0 = 5 motor radians -> 1 meter limit_0_present: false limit_1_present: false @@ -355,7 +351,6 @@ brushed_motors: motor_max_voltage: 6.0 # used to calculate max pwm calibration_throttle: 0.5 # throttle during calibration sensor_actuator: - velocity_multiplier: 1.0 gear_ratio: 1.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: false limit_1_present: false @@ -372,7 +367,6 @@ brushed_motors: driver_voltage: 12.0 # used to calculate max pwm motor_max_voltage: 6.0 # used to calculate max pwm cache: - velocity_multiplier: 1.0 gear_ratio: 1.0 # motor ratio compared to joint, e.g. if 5, then 5 rotations of motor = 1 rotation of joint limit_0_present: false limit_1_present: false @@ -514,7 +508,7 @@ cameras: rover: length: 0.86 width: 0.86 - max_speed: 2.0 + max_speed: 1.25 wheel: gear_ratio: 50.0 @@ -534,24 +528,25 @@ motors_group: - "mast_gimbal_z" cache: - "cache_motor" - sa_hw: + sa: - "sa_x" - "sa_y" - "sa_z" - "sampler" - "sensor_actuator" - drive: + drive_left: - "front_left" - - "front_right" - "middle_left" - - "middle_right" - "back_left" + drive_right: + - "front_right" + - "middle_right" - "back_right" motors: controllers: joint_a: - type: "brushless" + type: "brushless_linear" joint_b: type: "brushed" joint_c: @@ -598,3 +593,6 @@ default_network_iface: "enp0s31f6" auton_led_driver: port: "/dev/ttyACM0" baud: 115200 + +science: + shutoff_temp: 50.0f \ No newline at end of file diff --git a/config/moteus/back_left.cfg b/config/moteus/back_left.cfg new file mode 100644 index 000000000..ad86539b4 --- /dev/null +++ b/config/moteus/back_left.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 149 +uuid.uuid.1 226 +uuid.uuid.2 10 +uuid.uuid.3 140 +uuid.uuid.4 38 +uuid.uuid.5 208 +uuid.uuid.6 66 +uuid.uuid.7 69 +uuid.uuid.8 174 +uuid.uuid.9 196 +uuid.uuid.10 56 +uuid.uuid.11 198 +uuid.uuid.12 118 +uuid.uuid.13 164 +uuid.uuid.14 192 +uuid.uuid.15 153 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 1 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 6 +aux2.pins.0.pull 1 +aux2.pins.1.mode 6 +aux2.pins.1.pull 1 +aux2.pins.2.mode 6 +aux2.pins.2.pull 1 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -3.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 80.000000 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign -1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.258464 +motor.v_per_hz 0.409335 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.234858 +servo.pid_dq.ki 162.397873 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 22 +can.prefix 0 + diff --git a/config/moteus/back_right.cfg b/config/moteus/back_right.cfg new file mode 100644 index 000000000..920c0382b --- /dev/null +++ b/config/moteus/back_right.cfg @@ -0,0 +1,350 @@ +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.200000 +servo.pid_dq.ki 157.382980 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 4.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 21 +can.prefix 0 + diff --git a/config/moteus/front_left.cfg b/config/moteus/front_left.cfg new file mode 100644 index 000000000..21c7f1cfd --- /dev/null +++ b/config/moteus/front_left.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 229 +uuid.uuid.1 88 +uuid.uuid.2 217 +uuid.uuid.3 47 +uuid.uuid.4 29 +uuid.uuid.5 180 +uuid.uuid.6 75 +uuid.uuid.7 173 +uuid.uuid.8 178 +uuid.uuid.9 53 +uuid.uuid.10 239 +uuid.uuid.11 190 +uuid.uuid.12 69 +uuid.uuid.13 242 +uuid.uuid.14 159 +uuid.uuid.15 48 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -5.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 61.997570 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign -1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.235030 +motor.v_per_hz 0.437548 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.202691 +servo.pid_dq.ki 147.673920 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 18 +can.prefix 0 + diff --git a/config/moteus/front_right.cfg b/config/moteus/front_right.cfg new file mode 100644 index 000000000..658a54eb5 --- /dev/null +++ b/config/moteus/front_right.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 15 +uuid.uuid.1 46 +uuid.uuid.2 69 +uuid.uuid.3 9 +uuid.uuid.4 98 +uuid.uuid.5 199 +uuid.uuid.6 66 +uuid.uuid.7 137 +uuid.uuid.8 171 +uuid.uuid.9 14 +uuid.uuid.10 84 +uuid.uuid.11 252 +uuid.uuid.12 189 +uuid.uuid.13 133 +uuid.uuid.14 74 +uuid.uuid.15 234 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 0 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -1.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 71.065834 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 84 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 10.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.240511 +motor.v_per_hz 0.444322 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.176827 +servo.pid_dq.ki 151.117355 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 4.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 17 +can.prefix 0 + diff --git a/config/moteus/joint_a.cfg b/config/moteus/joint_a.cfg new file mode 100644 index 000000000..aaab74389 --- /dev/null +++ b/config/moteus/joint_a.cfg @@ -0,0 +1,1399 @@ +uuid.uuid.0 55 +uuid.uuid.1 182 +uuid.uuid.2 228 +uuid.uuid.3 110 +uuid.uuid.4 120 +uuid.uuid.5 156 +uuid.uuid.6 75 +uuid.uuid.7 137 +uuid.uuid.8 129 +uuid.uuid.9 230 +uuid.uuid.10 178 +uuid.uuid.11 201 +uuid.uuid.12 154 +uuid.uuid.13 163 +uuid.uuid.14 21 +uuid.uuid.15 188 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_rate_us 1000 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_rate_us 1000 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_rate_us 1000 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 0 +aux1.pins.0.pull 0 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 6 +aux1.pins.3.pull 1 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_rate_us 1000 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_rate_us 1000 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_rate_us 1000 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 14 +aux2.pins.0.pull 1 +aux2.pins.1.mode 14 +aux2.pins.1.pull 1 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 42 +motor_position.sources.0.offset -5.000000 +motor_position.sources.0.sign -1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 100.000000 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 0.005080 +motor.poles 14 +motor.phase_invert 0 +motor.resistance_ohm 0.160509 +motor.v_per_hz 0.132894 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.060857 +servo.pid_dq.ki 100.850487 +servo.pid_position.kp 3000.000000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 200.000000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit 0.150000 +servo.default_accel_limit 0.300000 +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip nan +servo.max_velocity_slip nan +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 100.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 0.180000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.timing_fault 0 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 32 +can.prefix 0 + diff --git a/config/moteus/joint_c.cfg b/config/moteus/joint_c.cfg new file mode 100644 index 000000000..c475f8708 --- /dev/null +++ b/config/moteus/joint_c.cfg @@ -0,0 +1,1398 @@ +uuid.uuid.0 23 +uuid.uuid.1 245 +uuid.uuid.2 107 +uuid.uuid.3 1 +uuid.uuid.4 115 +uuid.uuid.5 71 +uuid.uuid.6 69 +uuid.uuid.7 218 +uuid.uuid.8 176 +uuid.uuid.9 234 +uuid.uuid.10 13 +uuid.uuid.11 64 +uuid.uuid.12 20 +uuid.uuid.13 175 +uuid.uuid.14 129 +uuid.uuid.15 210 +clock.hsitrim 64 +aux1.i2c.i2c_hz 100000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 1 +aux1.i2c.devices.0.type 1 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_rate_us 1000 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_rate_us 1000 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_rate_us 1000 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 0 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 0 +aux1.pins.0.pull 0 +aux1.pins.1.mode 0 +aux1.pins.1.pull 0 +aux1.pins.2.mode 0 +aux1.pins.2.pull 0 +aux1.pins.3.mode 13 +aux1.pins.3.pull 1 +aux1.pins.4.mode 13 +aux1.pins.4.pull 1 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_rate_us 1000 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_rate_us 1000 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_rate_us 1000 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 1 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 6 +aux2.pins.0.pull 1 +aux2.pins.1.mode 6 +aux2.pins.1.pull 1 +aux2.pins.2.mode 6 +aux2.pins.2.pull 1 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 2 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 42 +motor_position.sources.0.offset -1.000000 +motor_position.sources.0.sign -1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 100.000000 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 7 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 65536 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign -1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 1 +motor_position.sources.1.pll_filter_hz 100.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.297363 +motor_position.output.sign 1 +motor_position.output.reference_source 1 +motor_position.rotor_to_output_ratio 0.002066 +motor.poles 14 +motor.phase_invert 0 +motor.resistance_ohm 0.162850 +motor.v_per_hz 0.000505 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 150 +drv8323_conf.idriven_hs_ma 300 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 150 +drv8323_conf.idriven_ls_ma 300 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 56.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.060606 +servo.pid_dq.ki 102.321388 +servo.pid_position.kp 14.000000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 1.450000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit 0.080000 +servo.default_accel_limit 0.200000 +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 0.100000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 53.000000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 100.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 0.100000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.timing_fault 0 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 34 +can.prefix 0 + diff --git a/config/moteus/joint_de_0.cfg b/config/moteus/joint_de_0.cfg new file mode 100644 index 000000000..c116946d8 --- /dev/null +++ b/config/moteus/joint_de_0.cfg @@ -0,0 +1,1399 @@ +uuid.uuid.0 174 +uuid.uuid.1 214 +uuid.uuid.2 243 +uuid.uuid.3 248 +uuid.uuid.4 175 +uuid.uuid.5 138 +uuid.uuid.6 65 +uuid.uuid.7 14 +uuid.uuid.8 153 +uuid.uuid.9 120 +uuid.uuid.10 43 +uuid.uuid.11 164 +uuid.uuid.12 127 +uuid.uuid.13 181 +uuid.uuid.14 167 +uuid.uuid.15 144 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 1 +aux1.i2c.devices.0.type 1 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_rate_us 1000 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_rate_us 1000 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_rate_us 1000 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 0 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 0 +aux1.pins.0.pull 0 +aux1.pins.1.mode 0 +aux1.pins.1.pull 0 +aux1.pins.2.mode 0 +aux1.pins.2.pull 0 +aux1.pins.3.mode 13 +aux1.pins.3.pull 1 +aux1.pins.4.mode 13 +aux1.pins.4.pull 1 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_rate_us 1000 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_rate_us 1000 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_rate_us 1000 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 1 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 6 +aux2.pins.0.pull 1 +aux2.pins.1.mode 6 +aux2.pins.1.pull 1 +aux2.pins.2.mode 6 +aux2.pins.2.pull 1 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 2 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 48 +motor_position.sources.0.offset -3.000000 +motor_position.sources.0.sign -1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 100.000000 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 7 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 65536 +motor_position.sources.1.offset -34783.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 100.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 16 +motor.phase_invert 0 +motor.resistance_ohm 3.711431 +motor.v_per_hz 0.576525 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 150 +drv8323_conf.idriven_hs_ma 300 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 150 +drv8323_conf.idriven_ls_ma 300 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 56.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 1.387107 +servo.pid_dq.ki 2331.960449 +servo.pid_position.kp 1.300000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.010000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit 5.000000 +servo.default_accel_limit 10.000000 +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip nan +servo.max_velocity_slip nan +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 53.000000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 5.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 10.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.timing_fault 0 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 35 +can.prefix 0 + diff --git a/config/moteus/joint_de_1.cfg b/config/moteus/joint_de_1.cfg new file mode 100644 index 000000000..68c5e7f78 --- /dev/null +++ b/config/moteus/joint_de_1.cfg @@ -0,0 +1,1399 @@ +uuid.uuid.0 210 +uuid.uuid.1 42 +uuid.uuid.2 55 +uuid.uuid.3 197 +uuid.uuid.4 115 +uuid.uuid.5 183 +uuid.uuid.6 70 +uuid.uuid.7 194 +uuid.uuid.8 179 +uuid.uuid.9 54 +uuid.uuid.10 50 +uuid.uuid.11 137 +uuid.uuid.12 91 +uuid.uuid.13 149 +uuid.uuid.14 200 +uuid.uuid.15 194 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 1 +aux1.i2c.devices.0.type 1 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_rate_us 1000 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_rate_us 1000 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_rate_us 1000 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 0 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 0 +aux1.pins.0.pull 0 +aux1.pins.1.mode 0 +aux1.pins.1.pull 0 +aux1.pins.2.mode 0 +aux1.pins.2.pull 0 +aux1.pins.3.mode 13 +aux1.pins.3.pull 1 +aux1.pins.4.mode 13 +aux1.pins.4.pull 1 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_rate_us 1000 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_rate_us 1000 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_rate_us 1000 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 1 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 6 +aux2.pins.0.pull 1 +aux2.pins.1.mode 6 +aux2.pins.1.pull 1 +aux2.pins.2.mode 6 +aux2.pins.2.pull 1 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 2 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 48 +motor_position.sources.0.offset -1.000000 +motor_position.sources.0.sign -1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 100.000000 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 7 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 65536 +motor_position.sources.1.offset -52120.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 1 +motor_position.sources.1.pll_filter_hz 100.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 16 +motor.phase_invert 0 +motor.resistance_ohm 3.353775 +motor.v_per_hz 0.571181 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 150 +drv8323_conf.idriven_hs_ma 300 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 150 +drv8323_conf.idriven_ls_ma 300 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 56.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 3.135870 +servo.pid_dq.ki 4214.477539 +servo.pid_position.kp 0.900000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.085000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit 5.000000 +servo.default_accel_limit 10.000000 +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip nan +servo.max_velocity_slip nan +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 53.000000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 5.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 10.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.timing_fault 0 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 36 +can.prefix 0 + diff --git a/config/moteus/middle_left.cfg b/config/moteus/middle_left.cfg new file mode 100644 index 000000000..6b0689bc5 --- /dev/null +++ b/config/moteus/middle_left.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 251 +uuid.uuid.1 136 +uuid.uuid.2 255 +uuid.uuid.3 85 +uuid.uuid.4 115 +uuid.uuid.5 82 +uuid.uuid.6 71 +uuid.uuid.7 65 +uuid.uuid.8 167 +uuid.uuid.9 42 +uuid.uuid.10 202 +uuid.uuid.11 217 +uuid.uuid.12 60 +uuid.uuid.13 130 +uuid.uuid.14 211 +uuid.uuid.15 64 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -5.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 65.305252 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign -1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.248204 +motor.v_per_hz 0.338219 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.192425 +servo.pid_dq.ki 155.951324 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 45.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 20 +can.prefix 0 + diff --git a/config/moteus/middle_right.cfg b/config/moteus/middle_right.cfg new file mode 100644 index 000000000..c8a4cf73c --- /dev/null +++ b/config/moteus/middle_right.cfg @@ -0,0 +1,1397 @@ +uuid.uuid.0 105 +uuid.uuid.1 13 +uuid.uuid.2 118 +uuid.uuid.3 61 +uuid.uuid.4 27 +uuid.uuid.5 255 +uuid.uuid.6 74 +uuid.uuid.7 237 +uuid.uuid.8 130 +uuid.uuid.9 123 +uuid.uuid.10 70 +uuid.uuid.11 92 +uuid.uuid.12 86 +uuid.uuid.13 59 +uuid.uuid.14 11 +uuid.uuid.15 26 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_ms 10 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_ms 10 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_ms 10 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 6 +aux1.pins.0.pull 1 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 0 +aux1.pins.3.pull 0 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_ms 10 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_ms 10 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_ms 10 +aux2.spi.mode 0 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 0 +aux2.pins.0.pull 0 +aux2.pins.1.mode 0 +aux2.pins.1.pull 0 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 84 +motor_position.sources.0.offset -5.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 60.370068 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 10.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 1.000000 +motor.poles 28 +motor.phase_invert 0 +motor.resistance_ohm 0.217140 +motor.v_per_hz 0.436649 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 0.208156 +servo.pid_dq.ki 136.432968 +servo.pid_position.kp 0.500000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.050000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit nan +servo.default_accel_limit nan +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip 10.000000 +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 7.500000 +servo.derate_current_A -20.000000 +servo.max_velocity 500.000000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 19 +can.prefix 0 + diff --git a/config/moteus/sa_z.cfg b/config/moteus/sa_z.cfg new file mode 100644 index 000000000..b0654bd1c --- /dev/null +++ b/config/moteus/sa_z.cfg @@ -0,0 +1,1399 @@ +uuid.uuid.0 95 +uuid.uuid.1 37 +uuid.uuid.2 12 +uuid.uuid.3 27 +uuid.uuid.4 4 +uuid.uuid.5 16 +uuid.uuid.6 65 +uuid.uuid.7 193 +uuid.uuid.8 152 +uuid.uuid.9 64 +uuid.uuid.10 17 +uuid.uuid.11 161 +uuid.uuid.12 239 +uuid.uuid.13 203 +uuid.uuid.14 94 +uuid.uuid.15 81 +clock.hsitrim 64 +aux1.i2c.i2c_hz 400000 +aux1.i2c.i2c_mode 1 +aux1.i2c.pullup 0 +aux1.i2c.devices.0.type 0 +aux1.i2c.devices.0.address 64 +aux1.i2c.devices.0.poll_rate_us 1000 +aux1.i2c.devices.1.type 0 +aux1.i2c.devices.1.address 64 +aux1.i2c.devices.1.poll_rate_us 1000 +aux1.i2c.devices.2.type 0 +aux1.i2c.devices.2.address 64 +aux1.i2c.devices.2.poll_rate_us 1000 +aux1.spi.mode 1 +aux1.spi.rate_hz 12000000 +aux1.spi.filter_us 64 +aux1.spi.bct 0 +aux1.uart.mode 0 +aux1.uart.baud_rate 115200 +aux1.uart.poll_rate_us 100 +aux1.uart.rs422 0 +aux1.uart.cui_amt21_address 84 +aux1.quadrature.enabled 0 +aux1.quadrature.cpr 16384 +aux1.hall.enabled 1 +aux1.hall.polarity 0 +aux1.index.enabled 0 +aux1.sine_cosine.enabled 0 +aux1.sine_cosine.common 1700 +aux1.i2c_startup_delay_ms 30 +aux1.pins.0.mode 0 +aux1.pins.0.pull 0 +aux1.pins.1.mode 6 +aux1.pins.1.pull 1 +aux1.pins.2.mode 6 +aux1.pins.2.pull 1 +aux1.pins.3.mode 6 +aux1.pins.3.pull 1 +aux1.pins.4.mode 0 +aux1.pins.4.pull 0 +aux2.i2c.i2c_hz 400000 +aux2.i2c.i2c_mode 1 +aux2.i2c.pullup 0 +aux2.i2c.devices.0.type 0 +aux2.i2c.devices.0.address 64 +aux2.i2c.devices.0.poll_rate_us 1000 +aux2.i2c.devices.1.type 0 +aux2.i2c.devices.1.address 64 +aux2.i2c.devices.1.poll_rate_us 1000 +aux2.i2c.devices.2.type 0 +aux2.i2c.devices.2.address 64 +aux2.i2c.devices.2.poll_rate_us 1000 +aux2.spi.mode 1 +aux2.spi.rate_hz 12000000 +aux2.spi.filter_us 64 +aux2.spi.bct 0 +aux2.uart.mode 0 +aux2.uart.baud_rate 115200 +aux2.uart.poll_rate_us 100 +aux2.uart.rs422 0 +aux2.uart.cui_amt21_address 84 +aux2.quadrature.enabled 0 +aux2.quadrature.cpr 16384 +aux2.hall.enabled 0 +aux2.hall.polarity 0 +aux2.index.enabled 0 +aux2.sine_cosine.enabled 0 +aux2.sine_cosine.common 1700 +aux2.i2c_startup_delay_ms 30 +aux2.pins.0.mode 14 +aux2.pins.0.pull 1 +aux2.pins.1.mode 14 +aux2.pins.1.pull 1 +aux2.pins.2.mode 0 +aux2.pins.2.pull 0 +aux2.pins.3.mode 0 +aux2.pins.3.pull 0 +aux2.pins.4.mode 0 +aux2.pins.4.pull 0 +motor_position.sources.0.aux_number 1 +motor_position.sources.0.type 4 +motor_position.sources.0.i2c_device 0 +motor_position.sources.0.incremental_index -1 +motor_position.sources.0.cpr 48 +motor_position.sources.0.offset -3.000000 +motor_position.sources.0.sign 1 +motor_position.sources.0.debug_override -1 +motor_position.sources.0.reference 0 +motor_position.sources.0.pll_filter_hz 100.000000 +motor_position.sources.0.compensation_table.0 0.000000 +motor_position.sources.0.compensation_table.1 0.000000 +motor_position.sources.0.compensation_table.2 0.000000 +motor_position.sources.0.compensation_table.3 0.000000 +motor_position.sources.0.compensation_table.4 0.000000 +motor_position.sources.0.compensation_table.5 0.000000 +motor_position.sources.0.compensation_table.6 0.000000 +motor_position.sources.0.compensation_table.7 0.000000 +motor_position.sources.0.compensation_table.8 0.000000 +motor_position.sources.0.compensation_table.9 0.000000 +motor_position.sources.0.compensation_table.10 0.000000 +motor_position.sources.0.compensation_table.11 0.000000 +motor_position.sources.0.compensation_table.12 0.000000 +motor_position.sources.0.compensation_table.13 0.000000 +motor_position.sources.0.compensation_table.14 0.000000 +motor_position.sources.0.compensation_table.15 0.000000 +motor_position.sources.0.compensation_table.16 0.000000 +motor_position.sources.0.compensation_table.17 0.000000 +motor_position.sources.0.compensation_table.18 0.000000 +motor_position.sources.0.compensation_table.19 0.000000 +motor_position.sources.0.compensation_table.20 0.000000 +motor_position.sources.0.compensation_table.21 0.000000 +motor_position.sources.0.compensation_table.22 0.000000 +motor_position.sources.0.compensation_table.23 0.000000 +motor_position.sources.0.compensation_table.24 0.000000 +motor_position.sources.0.compensation_table.25 0.000000 +motor_position.sources.0.compensation_table.26 0.000000 +motor_position.sources.0.compensation_table.27 0.000000 +motor_position.sources.0.compensation_table.28 0.000000 +motor_position.sources.0.compensation_table.29 0.000000 +motor_position.sources.0.compensation_table.30 0.000000 +motor_position.sources.0.compensation_table.31 0.000000 +motor_position.sources.1.aux_number 1 +motor_position.sources.1.type 0 +motor_position.sources.1.i2c_device 0 +motor_position.sources.1.incremental_index -1 +motor_position.sources.1.cpr 16384 +motor_position.sources.1.offset 0.000000 +motor_position.sources.1.sign 1 +motor_position.sources.1.debug_override -1 +motor_position.sources.1.reference 0 +motor_position.sources.1.pll_filter_hz 400.000000 +motor_position.sources.1.compensation_table.0 0.000000 +motor_position.sources.1.compensation_table.1 0.000000 +motor_position.sources.1.compensation_table.2 0.000000 +motor_position.sources.1.compensation_table.3 0.000000 +motor_position.sources.1.compensation_table.4 0.000000 +motor_position.sources.1.compensation_table.5 0.000000 +motor_position.sources.1.compensation_table.6 0.000000 +motor_position.sources.1.compensation_table.7 0.000000 +motor_position.sources.1.compensation_table.8 0.000000 +motor_position.sources.1.compensation_table.9 0.000000 +motor_position.sources.1.compensation_table.10 0.000000 +motor_position.sources.1.compensation_table.11 0.000000 +motor_position.sources.1.compensation_table.12 0.000000 +motor_position.sources.1.compensation_table.13 0.000000 +motor_position.sources.1.compensation_table.14 0.000000 +motor_position.sources.1.compensation_table.15 0.000000 +motor_position.sources.1.compensation_table.16 0.000000 +motor_position.sources.1.compensation_table.17 0.000000 +motor_position.sources.1.compensation_table.18 0.000000 +motor_position.sources.1.compensation_table.19 0.000000 +motor_position.sources.1.compensation_table.20 0.000000 +motor_position.sources.1.compensation_table.21 0.000000 +motor_position.sources.1.compensation_table.22 0.000000 +motor_position.sources.1.compensation_table.23 0.000000 +motor_position.sources.1.compensation_table.24 0.000000 +motor_position.sources.1.compensation_table.25 0.000000 +motor_position.sources.1.compensation_table.26 0.000000 +motor_position.sources.1.compensation_table.27 0.000000 +motor_position.sources.1.compensation_table.28 0.000000 +motor_position.sources.1.compensation_table.29 0.000000 +motor_position.sources.1.compensation_table.30 0.000000 +motor_position.sources.1.compensation_table.31 0.000000 +motor_position.sources.2.aux_number 1 +motor_position.sources.2.type 0 +motor_position.sources.2.i2c_device 0 +motor_position.sources.2.incremental_index -1 +motor_position.sources.2.cpr 16384 +motor_position.sources.2.offset 0.000000 +motor_position.sources.2.sign 1 +motor_position.sources.2.debug_override -1 +motor_position.sources.2.reference 0 +motor_position.sources.2.pll_filter_hz 400.000000 +motor_position.sources.2.compensation_table.0 0.000000 +motor_position.sources.2.compensation_table.1 0.000000 +motor_position.sources.2.compensation_table.2 0.000000 +motor_position.sources.2.compensation_table.3 0.000000 +motor_position.sources.2.compensation_table.4 0.000000 +motor_position.sources.2.compensation_table.5 0.000000 +motor_position.sources.2.compensation_table.6 0.000000 +motor_position.sources.2.compensation_table.7 0.000000 +motor_position.sources.2.compensation_table.8 0.000000 +motor_position.sources.2.compensation_table.9 0.000000 +motor_position.sources.2.compensation_table.10 0.000000 +motor_position.sources.2.compensation_table.11 0.000000 +motor_position.sources.2.compensation_table.12 0.000000 +motor_position.sources.2.compensation_table.13 0.000000 +motor_position.sources.2.compensation_table.14 0.000000 +motor_position.sources.2.compensation_table.15 0.000000 +motor_position.sources.2.compensation_table.16 0.000000 +motor_position.sources.2.compensation_table.17 0.000000 +motor_position.sources.2.compensation_table.18 0.000000 +motor_position.sources.2.compensation_table.19 0.000000 +motor_position.sources.2.compensation_table.20 0.000000 +motor_position.sources.2.compensation_table.21 0.000000 +motor_position.sources.2.compensation_table.22 0.000000 +motor_position.sources.2.compensation_table.23 0.000000 +motor_position.sources.2.compensation_table.24 0.000000 +motor_position.sources.2.compensation_table.25 0.000000 +motor_position.sources.2.compensation_table.26 0.000000 +motor_position.sources.2.compensation_table.27 0.000000 +motor_position.sources.2.compensation_table.28 0.000000 +motor_position.sources.2.compensation_table.29 0.000000 +motor_position.sources.2.compensation_table.30 0.000000 +motor_position.sources.2.compensation_table.31 0.000000 +motor_position.commutation_source 0 +motor_position.output.source 0 +motor_position.output.offset 0.000000 +motor_position.output.sign 1 +motor_position.output.reference_source -1 +motor_position.rotor_to_output_ratio 0.001587 +motor.poles 16 +motor.phase_invert 0 +motor.resistance_ohm 4.000340 +motor.v_per_hz 0.575865 +motor.offset.0 0.000000 +motor.offset.1 0.000000 +motor.offset.2 0.000000 +motor.offset.3 0.000000 +motor.offset.4 0.000000 +motor.offset.5 0.000000 +motor.offset.6 0.000000 +motor.offset.7 0.000000 +motor.offset.8 0.000000 +motor.offset.9 0.000000 +motor.offset.10 0.000000 +motor.offset.11 0.000000 +motor.offset.12 0.000000 +motor.offset.13 0.000000 +motor.offset.14 0.000000 +motor.offset.15 0.000000 +motor.offset.16 0.000000 +motor.offset.17 0.000000 +motor.offset.18 0.000000 +motor.offset.19 0.000000 +motor.offset.20 0.000000 +motor.offset.21 0.000000 +motor.offset.22 0.000000 +motor.offset.23 0.000000 +motor.offset.24 0.000000 +motor.offset.25 0.000000 +motor.offset.26 0.000000 +motor.offset.27 0.000000 +motor.offset.28 0.000000 +motor.offset.29 0.000000 +motor.offset.30 0.000000 +motor.offset.31 0.000000 +motor.offset.32 0.000000 +motor.offset.33 0.000000 +motor.offset.34 0.000000 +motor.offset.35 0.000000 +motor.offset.36 0.000000 +motor.offset.37 0.000000 +motor.offset.38 0.000000 +motor.offset.39 0.000000 +motor.offset.40 0.000000 +motor.offset.41 0.000000 +motor.offset.42 0.000000 +motor.offset.43 0.000000 +motor.offset.44 0.000000 +motor.offset.45 0.000000 +motor.offset.46 0.000000 +motor.offset.47 0.000000 +motor.offset.48 0.000000 +motor.offset.49 0.000000 +motor.offset.50 0.000000 +motor.offset.51 0.000000 +motor.offset.52 0.000000 +motor.offset.53 0.000000 +motor.offset.54 0.000000 +motor.offset.55 0.000000 +motor.offset.56 0.000000 +motor.offset.57 0.000000 +motor.offset.58 0.000000 +motor.offset.59 0.000000 +motor.offset.60 0.000000 +motor.offset.61 0.000000 +motor.offset.62 0.000000 +motor.offset.63 0.000000 +motor.rotation_current_cutoff_A 10000.000000 +motor.rotation_current_scale 0.050000 +motor.rotation_torque_scale 14.700000 +motor.cogging_dq_scale 0.000000 +motor.cogging_dq_comp.0 0 +motor.cogging_dq_comp.1 0 +motor.cogging_dq_comp.2 0 +motor.cogging_dq_comp.3 0 +motor.cogging_dq_comp.4 0 +motor.cogging_dq_comp.5 0 +motor.cogging_dq_comp.6 0 +motor.cogging_dq_comp.7 0 +motor.cogging_dq_comp.8 0 +motor.cogging_dq_comp.9 0 +motor.cogging_dq_comp.10 0 +motor.cogging_dq_comp.11 0 +motor.cogging_dq_comp.12 0 +motor.cogging_dq_comp.13 0 +motor.cogging_dq_comp.14 0 +motor.cogging_dq_comp.15 0 +motor.cogging_dq_comp.16 0 +motor.cogging_dq_comp.17 0 +motor.cogging_dq_comp.18 0 +motor.cogging_dq_comp.19 0 +motor.cogging_dq_comp.20 0 +motor.cogging_dq_comp.21 0 +motor.cogging_dq_comp.22 0 +motor.cogging_dq_comp.23 0 +motor.cogging_dq_comp.24 0 +motor.cogging_dq_comp.25 0 +motor.cogging_dq_comp.26 0 +motor.cogging_dq_comp.27 0 +motor.cogging_dq_comp.28 0 +motor.cogging_dq_comp.29 0 +motor.cogging_dq_comp.30 0 +motor.cogging_dq_comp.31 0 +motor.cogging_dq_comp.32 0 +motor.cogging_dq_comp.33 0 +motor.cogging_dq_comp.34 0 +motor.cogging_dq_comp.35 0 +motor.cogging_dq_comp.36 0 +motor.cogging_dq_comp.37 0 +motor.cogging_dq_comp.38 0 +motor.cogging_dq_comp.39 0 +motor.cogging_dq_comp.40 0 +motor.cogging_dq_comp.41 0 +motor.cogging_dq_comp.42 0 +motor.cogging_dq_comp.43 0 +motor.cogging_dq_comp.44 0 +motor.cogging_dq_comp.45 0 +motor.cogging_dq_comp.46 0 +motor.cogging_dq_comp.47 0 +motor.cogging_dq_comp.48 0 +motor.cogging_dq_comp.49 0 +motor.cogging_dq_comp.50 0 +motor.cogging_dq_comp.51 0 +motor.cogging_dq_comp.52 0 +motor.cogging_dq_comp.53 0 +motor.cogging_dq_comp.54 0 +motor.cogging_dq_comp.55 0 +motor.cogging_dq_comp.56 0 +motor.cogging_dq_comp.57 0 +motor.cogging_dq_comp.58 0 +motor.cogging_dq_comp.59 0 +motor.cogging_dq_comp.60 0 +motor.cogging_dq_comp.61 0 +motor.cogging_dq_comp.62 0 +motor.cogging_dq_comp.63 0 +motor.cogging_dq_comp.64 0 +motor.cogging_dq_comp.65 0 +motor.cogging_dq_comp.66 0 +motor.cogging_dq_comp.67 0 +motor.cogging_dq_comp.68 0 +motor.cogging_dq_comp.69 0 +motor.cogging_dq_comp.70 0 +motor.cogging_dq_comp.71 0 +motor.cogging_dq_comp.72 0 +motor.cogging_dq_comp.73 0 +motor.cogging_dq_comp.74 0 +motor.cogging_dq_comp.75 0 +motor.cogging_dq_comp.76 0 +motor.cogging_dq_comp.77 0 +motor.cogging_dq_comp.78 0 +motor.cogging_dq_comp.79 0 +motor.cogging_dq_comp.80 0 +motor.cogging_dq_comp.81 0 +motor.cogging_dq_comp.82 0 +motor.cogging_dq_comp.83 0 +motor.cogging_dq_comp.84 0 +motor.cogging_dq_comp.85 0 +motor.cogging_dq_comp.86 0 +motor.cogging_dq_comp.87 0 +motor.cogging_dq_comp.88 0 +motor.cogging_dq_comp.89 0 +motor.cogging_dq_comp.90 0 +motor.cogging_dq_comp.91 0 +motor.cogging_dq_comp.92 0 +motor.cogging_dq_comp.93 0 +motor.cogging_dq_comp.94 0 +motor.cogging_dq_comp.95 0 +motor.cogging_dq_comp.96 0 +motor.cogging_dq_comp.97 0 +motor.cogging_dq_comp.98 0 +motor.cogging_dq_comp.99 0 +motor.cogging_dq_comp.100 0 +motor.cogging_dq_comp.101 0 +motor.cogging_dq_comp.102 0 +motor.cogging_dq_comp.103 0 +motor.cogging_dq_comp.104 0 +motor.cogging_dq_comp.105 0 +motor.cogging_dq_comp.106 0 +motor.cogging_dq_comp.107 0 +motor.cogging_dq_comp.108 0 +motor.cogging_dq_comp.109 0 +motor.cogging_dq_comp.110 0 +motor.cogging_dq_comp.111 0 +motor.cogging_dq_comp.112 0 +motor.cogging_dq_comp.113 0 +motor.cogging_dq_comp.114 0 +motor.cogging_dq_comp.115 0 +motor.cogging_dq_comp.116 0 +motor.cogging_dq_comp.117 0 +motor.cogging_dq_comp.118 0 +motor.cogging_dq_comp.119 0 +motor.cogging_dq_comp.120 0 +motor.cogging_dq_comp.121 0 +motor.cogging_dq_comp.122 0 +motor.cogging_dq_comp.123 0 +motor.cogging_dq_comp.124 0 +motor.cogging_dq_comp.125 0 +motor.cogging_dq_comp.126 0 +motor.cogging_dq_comp.127 0 +motor.cogging_dq_comp.128 0 +motor.cogging_dq_comp.129 0 +motor.cogging_dq_comp.130 0 +motor.cogging_dq_comp.131 0 +motor.cogging_dq_comp.132 0 +motor.cogging_dq_comp.133 0 +motor.cogging_dq_comp.134 0 +motor.cogging_dq_comp.135 0 +motor.cogging_dq_comp.136 0 +motor.cogging_dq_comp.137 0 +motor.cogging_dq_comp.138 0 +motor.cogging_dq_comp.139 0 +motor.cogging_dq_comp.140 0 +motor.cogging_dq_comp.141 0 +motor.cogging_dq_comp.142 0 +motor.cogging_dq_comp.143 0 +motor.cogging_dq_comp.144 0 +motor.cogging_dq_comp.145 0 +motor.cogging_dq_comp.146 0 +motor.cogging_dq_comp.147 0 +motor.cogging_dq_comp.148 0 +motor.cogging_dq_comp.149 0 +motor.cogging_dq_comp.150 0 +motor.cogging_dq_comp.151 0 +motor.cogging_dq_comp.152 0 +motor.cogging_dq_comp.153 0 +motor.cogging_dq_comp.154 0 +motor.cogging_dq_comp.155 0 +motor.cogging_dq_comp.156 0 +motor.cogging_dq_comp.157 0 +motor.cogging_dq_comp.158 0 +motor.cogging_dq_comp.159 0 +motor.cogging_dq_comp.160 0 +motor.cogging_dq_comp.161 0 +motor.cogging_dq_comp.162 0 +motor.cogging_dq_comp.163 0 +motor.cogging_dq_comp.164 0 +motor.cogging_dq_comp.165 0 +motor.cogging_dq_comp.166 0 +motor.cogging_dq_comp.167 0 +motor.cogging_dq_comp.168 0 +motor.cogging_dq_comp.169 0 +motor.cogging_dq_comp.170 0 +motor.cogging_dq_comp.171 0 +motor.cogging_dq_comp.172 0 +motor.cogging_dq_comp.173 0 +motor.cogging_dq_comp.174 0 +motor.cogging_dq_comp.175 0 +motor.cogging_dq_comp.176 0 +motor.cogging_dq_comp.177 0 +motor.cogging_dq_comp.178 0 +motor.cogging_dq_comp.179 0 +motor.cogging_dq_comp.180 0 +motor.cogging_dq_comp.181 0 +motor.cogging_dq_comp.182 0 +motor.cogging_dq_comp.183 0 +motor.cogging_dq_comp.184 0 +motor.cogging_dq_comp.185 0 +motor.cogging_dq_comp.186 0 +motor.cogging_dq_comp.187 0 +motor.cogging_dq_comp.188 0 +motor.cogging_dq_comp.189 0 +motor.cogging_dq_comp.190 0 +motor.cogging_dq_comp.191 0 +motor.cogging_dq_comp.192 0 +motor.cogging_dq_comp.193 0 +motor.cogging_dq_comp.194 0 +motor.cogging_dq_comp.195 0 +motor.cogging_dq_comp.196 0 +motor.cogging_dq_comp.197 0 +motor.cogging_dq_comp.198 0 +motor.cogging_dq_comp.199 0 +motor.cogging_dq_comp.200 0 +motor.cogging_dq_comp.201 0 +motor.cogging_dq_comp.202 0 +motor.cogging_dq_comp.203 0 +motor.cogging_dq_comp.204 0 +motor.cogging_dq_comp.205 0 +motor.cogging_dq_comp.206 0 +motor.cogging_dq_comp.207 0 +motor.cogging_dq_comp.208 0 +motor.cogging_dq_comp.209 0 +motor.cogging_dq_comp.210 0 +motor.cogging_dq_comp.211 0 +motor.cogging_dq_comp.212 0 +motor.cogging_dq_comp.213 0 +motor.cogging_dq_comp.214 0 +motor.cogging_dq_comp.215 0 +motor.cogging_dq_comp.216 0 +motor.cogging_dq_comp.217 0 +motor.cogging_dq_comp.218 0 +motor.cogging_dq_comp.219 0 +motor.cogging_dq_comp.220 0 +motor.cogging_dq_comp.221 0 +motor.cogging_dq_comp.222 0 +motor.cogging_dq_comp.223 0 +motor.cogging_dq_comp.224 0 +motor.cogging_dq_comp.225 0 +motor.cogging_dq_comp.226 0 +motor.cogging_dq_comp.227 0 +motor.cogging_dq_comp.228 0 +motor.cogging_dq_comp.229 0 +motor.cogging_dq_comp.230 0 +motor.cogging_dq_comp.231 0 +motor.cogging_dq_comp.232 0 +motor.cogging_dq_comp.233 0 +motor.cogging_dq_comp.234 0 +motor.cogging_dq_comp.235 0 +motor.cogging_dq_comp.236 0 +motor.cogging_dq_comp.237 0 +motor.cogging_dq_comp.238 0 +motor.cogging_dq_comp.239 0 +motor.cogging_dq_comp.240 0 +motor.cogging_dq_comp.241 0 +motor.cogging_dq_comp.242 0 +motor.cogging_dq_comp.243 0 +motor.cogging_dq_comp.244 0 +motor.cogging_dq_comp.245 0 +motor.cogging_dq_comp.246 0 +motor.cogging_dq_comp.247 0 +motor.cogging_dq_comp.248 0 +motor.cogging_dq_comp.249 0 +motor.cogging_dq_comp.250 0 +motor.cogging_dq_comp.251 0 +motor.cogging_dq_comp.252 0 +motor.cogging_dq_comp.253 0 +motor.cogging_dq_comp.254 0 +motor.cogging_dq_comp.255 0 +motor.cogging_dq_comp.256 0 +motor.cogging_dq_comp.257 0 +motor.cogging_dq_comp.258 0 +motor.cogging_dq_comp.259 0 +motor.cogging_dq_comp.260 0 +motor.cogging_dq_comp.261 0 +motor.cogging_dq_comp.262 0 +motor.cogging_dq_comp.263 0 +motor.cogging_dq_comp.264 0 +motor.cogging_dq_comp.265 0 +motor.cogging_dq_comp.266 0 +motor.cogging_dq_comp.267 0 +motor.cogging_dq_comp.268 0 +motor.cogging_dq_comp.269 0 +motor.cogging_dq_comp.270 0 +motor.cogging_dq_comp.271 0 +motor.cogging_dq_comp.272 0 +motor.cogging_dq_comp.273 0 +motor.cogging_dq_comp.274 0 +motor.cogging_dq_comp.275 0 +motor.cogging_dq_comp.276 0 +motor.cogging_dq_comp.277 0 +motor.cogging_dq_comp.278 0 +motor.cogging_dq_comp.279 0 +motor.cogging_dq_comp.280 0 +motor.cogging_dq_comp.281 0 +motor.cogging_dq_comp.282 0 +motor.cogging_dq_comp.283 0 +motor.cogging_dq_comp.284 0 +motor.cogging_dq_comp.285 0 +motor.cogging_dq_comp.286 0 +motor.cogging_dq_comp.287 0 +motor.cogging_dq_comp.288 0 +motor.cogging_dq_comp.289 0 +motor.cogging_dq_comp.290 0 +motor.cogging_dq_comp.291 0 +motor.cogging_dq_comp.292 0 +motor.cogging_dq_comp.293 0 +motor.cogging_dq_comp.294 0 +motor.cogging_dq_comp.295 0 +motor.cogging_dq_comp.296 0 +motor.cogging_dq_comp.297 0 +motor.cogging_dq_comp.298 0 +motor.cogging_dq_comp.299 0 +motor.cogging_dq_comp.300 0 +motor.cogging_dq_comp.301 0 +motor.cogging_dq_comp.302 0 +motor.cogging_dq_comp.303 0 +motor.cogging_dq_comp.304 0 +motor.cogging_dq_comp.305 0 +motor.cogging_dq_comp.306 0 +motor.cogging_dq_comp.307 0 +motor.cogging_dq_comp.308 0 +motor.cogging_dq_comp.309 0 +motor.cogging_dq_comp.310 0 +motor.cogging_dq_comp.311 0 +motor.cogging_dq_comp.312 0 +motor.cogging_dq_comp.313 0 +motor.cogging_dq_comp.314 0 +motor.cogging_dq_comp.315 0 +motor.cogging_dq_comp.316 0 +motor.cogging_dq_comp.317 0 +motor.cogging_dq_comp.318 0 +motor.cogging_dq_comp.319 0 +motor.cogging_dq_comp.320 0 +motor.cogging_dq_comp.321 0 +motor.cogging_dq_comp.322 0 +motor.cogging_dq_comp.323 0 +motor.cogging_dq_comp.324 0 +motor.cogging_dq_comp.325 0 +motor.cogging_dq_comp.326 0 +motor.cogging_dq_comp.327 0 +motor.cogging_dq_comp.328 0 +motor.cogging_dq_comp.329 0 +motor.cogging_dq_comp.330 0 +motor.cogging_dq_comp.331 0 +motor.cogging_dq_comp.332 0 +motor.cogging_dq_comp.333 0 +motor.cogging_dq_comp.334 0 +motor.cogging_dq_comp.335 0 +motor.cogging_dq_comp.336 0 +motor.cogging_dq_comp.337 0 +motor.cogging_dq_comp.338 0 +motor.cogging_dq_comp.339 0 +motor.cogging_dq_comp.340 0 +motor.cogging_dq_comp.341 0 +motor.cogging_dq_comp.342 0 +motor.cogging_dq_comp.343 0 +motor.cogging_dq_comp.344 0 +motor.cogging_dq_comp.345 0 +motor.cogging_dq_comp.346 0 +motor.cogging_dq_comp.347 0 +motor.cogging_dq_comp.348 0 +motor.cogging_dq_comp.349 0 +motor.cogging_dq_comp.350 0 +motor.cogging_dq_comp.351 0 +motor.cogging_dq_comp.352 0 +motor.cogging_dq_comp.353 0 +motor.cogging_dq_comp.354 0 +motor.cogging_dq_comp.355 0 +motor.cogging_dq_comp.356 0 +motor.cogging_dq_comp.357 0 +motor.cogging_dq_comp.358 0 +motor.cogging_dq_comp.359 0 +motor.cogging_dq_comp.360 0 +motor.cogging_dq_comp.361 0 +motor.cogging_dq_comp.362 0 +motor.cogging_dq_comp.363 0 +motor.cogging_dq_comp.364 0 +motor.cogging_dq_comp.365 0 +motor.cogging_dq_comp.366 0 +motor.cogging_dq_comp.367 0 +motor.cogging_dq_comp.368 0 +motor.cogging_dq_comp.369 0 +motor.cogging_dq_comp.370 0 +motor.cogging_dq_comp.371 0 +motor.cogging_dq_comp.372 0 +motor.cogging_dq_comp.373 0 +motor.cogging_dq_comp.374 0 +motor.cogging_dq_comp.375 0 +motor.cogging_dq_comp.376 0 +motor.cogging_dq_comp.377 0 +motor.cogging_dq_comp.378 0 +motor.cogging_dq_comp.379 0 +motor.cogging_dq_comp.380 0 +motor.cogging_dq_comp.381 0 +motor.cogging_dq_comp.382 0 +motor.cogging_dq_comp.383 0 +motor.cogging_dq_comp.384 0 +motor.cogging_dq_comp.385 0 +motor.cogging_dq_comp.386 0 +motor.cogging_dq_comp.387 0 +motor.cogging_dq_comp.388 0 +motor.cogging_dq_comp.389 0 +motor.cogging_dq_comp.390 0 +motor.cogging_dq_comp.391 0 +motor.cogging_dq_comp.392 0 +motor.cogging_dq_comp.393 0 +motor.cogging_dq_comp.394 0 +motor.cogging_dq_comp.395 0 +motor.cogging_dq_comp.396 0 +motor.cogging_dq_comp.397 0 +motor.cogging_dq_comp.398 0 +motor.cogging_dq_comp.399 0 +motor.cogging_dq_comp.400 0 +motor.cogging_dq_comp.401 0 +motor.cogging_dq_comp.402 0 +motor.cogging_dq_comp.403 0 +motor.cogging_dq_comp.404 0 +motor.cogging_dq_comp.405 0 +motor.cogging_dq_comp.406 0 +motor.cogging_dq_comp.407 0 +motor.cogging_dq_comp.408 0 +motor.cogging_dq_comp.409 0 +motor.cogging_dq_comp.410 0 +motor.cogging_dq_comp.411 0 +motor.cogging_dq_comp.412 0 +motor.cogging_dq_comp.413 0 +motor.cogging_dq_comp.414 0 +motor.cogging_dq_comp.415 0 +motor.cogging_dq_comp.416 0 +motor.cogging_dq_comp.417 0 +motor.cogging_dq_comp.418 0 +motor.cogging_dq_comp.419 0 +motor.cogging_dq_comp.420 0 +motor.cogging_dq_comp.421 0 +motor.cogging_dq_comp.422 0 +motor.cogging_dq_comp.423 0 +motor.cogging_dq_comp.424 0 +motor.cogging_dq_comp.425 0 +motor.cogging_dq_comp.426 0 +motor.cogging_dq_comp.427 0 +motor.cogging_dq_comp.428 0 +motor.cogging_dq_comp.429 0 +motor.cogging_dq_comp.430 0 +motor.cogging_dq_comp.431 0 +motor.cogging_dq_comp.432 0 +motor.cogging_dq_comp.433 0 +motor.cogging_dq_comp.434 0 +motor.cogging_dq_comp.435 0 +motor.cogging_dq_comp.436 0 +motor.cogging_dq_comp.437 0 +motor.cogging_dq_comp.438 0 +motor.cogging_dq_comp.439 0 +motor.cogging_dq_comp.440 0 +motor.cogging_dq_comp.441 0 +motor.cogging_dq_comp.442 0 +motor.cogging_dq_comp.443 0 +motor.cogging_dq_comp.444 0 +motor.cogging_dq_comp.445 0 +motor.cogging_dq_comp.446 0 +motor.cogging_dq_comp.447 0 +motor.cogging_dq_comp.448 0 +motor.cogging_dq_comp.449 0 +motor.cogging_dq_comp.450 0 +motor.cogging_dq_comp.451 0 +motor.cogging_dq_comp.452 0 +motor.cogging_dq_comp.453 0 +motor.cogging_dq_comp.454 0 +motor.cogging_dq_comp.455 0 +motor.cogging_dq_comp.456 0 +motor.cogging_dq_comp.457 0 +motor.cogging_dq_comp.458 0 +motor.cogging_dq_comp.459 0 +motor.cogging_dq_comp.460 0 +motor.cogging_dq_comp.461 0 +motor.cogging_dq_comp.462 0 +motor.cogging_dq_comp.463 0 +motor.cogging_dq_comp.464 0 +motor.cogging_dq_comp.465 0 +motor.cogging_dq_comp.466 0 +motor.cogging_dq_comp.467 0 +motor.cogging_dq_comp.468 0 +motor.cogging_dq_comp.469 0 +motor.cogging_dq_comp.470 0 +motor.cogging_dq_comp.471 0 +motor.cogging_dq_comp.472 0 +motor.cogging_dq_comp.473 0 +motor.cogging_dq_comp.474 0 +motor.cogging_dq_comp.475 0 +motor.cogging_dq_comp.476 0 +motor.cogging_dq_comp.477 0 +motor.cogging_dq_comp.478 0 +motor.cogging_dq_comp.479 0 +motor.cogging_dq_comp.480 0 +motor.cogging_dq_comp.481 0 +motor.cogging_dq_comp.482 0 +motor.cogging_dq_comp.483 0 +motor.cogging_dq_comp.484 0 +motor.cogging_dq_comp.485 0 +motor.cogging_dq_comp.486 0 +motor.cogging_dq_comp.487 0 +motor.cogging_dq_comp.488 0 +motor.cogging_dq_comp.489 0 +motor.cogging_dq_comp.490 0 +motor.cogging_dq_comp.491 0 +motor.cogging_dq_comp.492 0 +motor.cogging_dq_comp.493 0 +motor.cogging_dq_comp.494 0 +motor.cogging_dq_comp.495 0 +motor.cogging_dq_comp.496 0 +motor.cogging_dq_comp.497 0 +motor.cogging_dq_comp.498 0 +motor.cogging_dq_comp.499 0 +motor.cogging_dq_comp.500 0 +motor.cogging_dq_comp.501 0 +motor.cogging_dq_comp.502 0 +motor.cogging_dq_comp.503 0 +motor.cogging_dq_comp.504 0 +motor.cogging_dq_comp.505 0 +motor.cogging_dq_comp.506 0 +motor.cogging_dq_comp.507 0 +motor.cogging_dq_comp.508 0 +motor.cogging_dq_comp.509 0 +motor.cogging_dq_comp.510 0 +motor.cogging_dq_comp.511 0 +motor.cogging_dq_comp.512 0 +motor.cogging_dq_comp.513 0 +motor.cogging_dq_comp.514 0 +motor.cogging_dq_comp.515 0 +motor.cogging_dq_comp.516 0 +motor.cogging_dq_comp.517 0 +motor.cogging_dq_comp.518 0 +motor.cogging_dq_comp.519 0 +motor.cogging_dq_comp.520 0 +motor.cogging_dq_comp.521 0 +motor.cogging_dq_comp.522 0 +motor.cogging_dq_comp.523 0 +motor.cogging_dq_comp.524 0 +motor.cogging_dq_comp.525 0 +motor.cogging_dq_comp.526 0 +motor.cogging_dq_comp.527 0 +motor.cogging_dq_comp.528 0 +motor.cogging_dq_comp.529 0 +motor.cogging_dq_comp.530 0 +motor.cogging_dq_comp.531 0 +motor.cogging_dq_comp.532 0 +motor.cogging_dq_comp.533 0 +motor.cogging_dq_comp.534 0 +motor.cogging_dq_comp.535 0 +motor.cogging_dq_comp.536 0 +motor.cogging_dq_comp.537 0 +motor.cogging_dq_comp.538 0 +motor.cogging_dq_comp.539 0 +motor.cogging_dq_comp.540 0 +motor.cogging_dq_comp.541 0 +motor.cogging_dq_comp.542 0 +motor.cogging_dq_comp.543 0 +motor.cogging_dq_comp.544 0 +motor.cogging_dq_comp.545 0 +motor.cogging_dq_comp.546 0 +motor.cogging_dq_comp.547 0 +motor.cogging_dq_comp.548 0 +motor.cogging_dq_comp.549 0 +motor.cogging_dq_comp.550 0 +motor.cogging_dq_comp.551 0 +motor.cogging_dq_comp.552 0 +motor.cogging_dq_comp.553 0 +motor.cogging_dq_comp.554 0 +motor.cogging_dq_comp.555 0 +motor.cogging_dq_comp.556 0 +motor.cogging_dq_comp.557 0 +motor.cogging_dq_comp.558 0 +motor.cogging_dq_comp.559 0 +motor.cogging_dq_comp.560 0 +motor.cogging_dq_comp.561 0 +motor.cogging_dq_comp.562 0 +motor.cogging_dq_comp.563 0 +motor.cogging_dq_comp.564 0 +motor.cogging_dq_comp.565 0 +motor.cogging_dq_comp.566 0 +motor.cogging_dq_comp.567 0 +motor.cogging_dq_comp.568 0 +motor.cogging_dq_comp.569 0 +motor.cogging_dq_comp.570 0 +motor.cogging_dq_comp.571 0 +motor.cogging_dq_comp.572 0 +motor.cogging_dq_comp.573 0 +motor.cogging_dq_comp.574 0 +motor.cogging_dq_comp.575 0 +motor.cogging_dq_comp.576 0 +motor.cogging_dq_comp.577 0 +motor.cogging_dq_comp.578 0 +motor.cogging_dq_comp.579 0 +motor.cogging_dq_comp.580 0 +motor.cogging_dq_comp.581 0 +motor.cogging_dq_comp.582 0 +motor.cogging_dq_comp.583 0 +motor.cogging_dq_comp.584 0 +motor.cogging_dq_comp.585 0 +motor.cogging_dq_comp.586 0 +motor.cogging_dq_comp.587 0 +motor.cogging_dq_comp.588 0 +motor.cogging_dq_comp.589 0 +motor.cogging_dq_comp.590 0 +motor.cogging_dq_comp.591 0 +motor.cogging_dq_comp.592 0 +motor.cogging_dq_comp.593 0 +motor.cogging_dq_comp.594 0 +motor.cogging_dq_comp.595 0 +motor.cogging_dq_comp.596 0 +motor.cogging_dq_comp.597 0 +motor.cogging_dq_comp.598 0 +motor.cogging_dq_comp.599 0 +motor.cogging_dq_comp.600 0 +motor.cogging_dq_comp.601 0 +motor.cogging_dq_comp.602 0 +motor.cogging_dq_comp.603 0 +motor.cogging_dq_comp.604 0 +motor.cogging_dq_comp.605 0 +motor.cogging_dq_comp.606 0 +motor.cogging_dq_comp.607 0 +motor.cogging_dq_comp.608 0 +motor.cogging_dq_comp.609 0 +motor.cogging_dq_comp.610 0 +motor.cogging_dq_comp.611 0 +motor.cogging_dq_comp.612 0 +motor.cogging_dq_comp.613 0 +motor.cogging_dq_comp.614 0 +motor.cogging_dq_comp.615 0 +motor.cogging_dq_comp.616 0 +motor.cogging_dq_comp.617 0 +motor.cogging_dq_comp.618 0 +motor.cogging_dq_comp.619 0 +motor.cogging_dq_comp.620 0 +motor.cogging_dq_comp.621 0 +motor.cogging_dq_comp.622 0 +motor.cogging_dq_comp.623 0 +motor.cogging_dq_comp.624 0 +motor.cogging_dq_comp.625 0 +motor.cogging_dq_comp.626 0 +motor.cogging_dq_comp.627 0 +motor.cogging_dq_comp.628 0 +motor.cogging_dq_comp.629 0 +motor.cogging_dq_comp.630 0 +motor.cogging_dq_comp.631 0 +motor.cogging_dq_comp.632 0 +motor.cogging_dq_comp.633 0 +motor.cogging_dq_comp.634 0 +motor.cogging_dq_comp.635 0 +motor.cogging_dq_comp.636 0 +motor.cogging_dq_comp.637 0 +motor.cogging_dq_comp.638 0 +motor.cogging_dq_comp.639 0 +motor.cogging_dq_comp.640 0 +motor.cogging_dq_comp.641 0 +motor.cogging_dq_comp.642 0 +motor.cogging_dq_comp.643 0 +motor.cogging_dq_comp.644 0 +motor.cogging_dq_comp.645 0 +motor.cogging_dq_comp.646 0 +motor.cogging_dq_comp.647 0 +motor.cogging_dq_comp.648 0 +motor.cogging_dq_comp.649 0 +motor.cogging_dq_comp.650 0 +motor.cogging_dq_comp.651 0 +motor.cogging_dq_comp.652 0 +motor.cogging_dq_comp.653 0 +motor.cogging_dq_comp.654 0 +motor.cogging_dq_comp.655 0 +motor.cogging_dq_comp.656 0 +motor.cogging_dq_comp.657 0 +motor.cogging_dq_comp.658 0 +motor.cogging_dq_comp.659 0 +motor.cogging_dq_comp.660 0 +motor.cogging_dq_comp.661 0 +motor.cogging_dq_comp.662 0 +motor.cogging_dq_comp.663 0 +motor.cogging_dq_comp.664 0 +motor.cogging_dq_comp.665 0 +motor.cogging_dq_comp.666 0 +motor.cogging_dq_comp.667 0 +motor.cogging_dq_comp.668 0 +motor.cogging_dq_comp.669 0 +motor.cogging_dq_comp.670 0 +motor.cogging_dq_comp.671 0 +motor.cogging_dq_comp.672 0 +motor.cogging_dq_comp.673 0 +motor.cogging_dq_comp.674 0 +motor.cogging_dq_comp.675 0 +motor.cogging_dq_comp.676 0 +motor.cogging_dq_comp.677 0 +motor.cogging_dq_comp.678 0 +motor.cogging_dq_comp.679 0 +motor.cogging_dq_comp.680 0 +motor.cogging_dq_comp.681 0 +motor.cogging_dq_comp.682 0 +motor.cogging_dq_comp.683 0 +motor.cogging_dq_comp.684 0 +motor.cogging_dq_comp.685 0 +motor.cogging_dq_comp.686 0 +motor.cogging_dq_comp.687 0 +motor.cogging_dq_comp.688 0 +motor.cogging_dq_comp.689 0 +motor.cogging_dq_comp.690 0 +motor.cogging_dq_comp.691 0 +motor.cogging_dq_comp.692 0 +motor.cogging_dq_comp.693 0 +motor.cogging_dq_comp.694 0 +motor.cogging_dq_comp.695 0 +motor.cogging_dq_comp.696 0 +motor.cogging_dq_comp.697 0 +motor.cogging_dq_comp.698 0 +motor.cogging_dq_comp.699 0 +motor.cogging_dq_comp.700 0 +motor.cogging_dq_comp.701 0 +motor.cogging_dq_comp.702 0 +motor.cogging_dq_comp.703 0 +motor.cogging_dq_comp.704 0 +motor.cogging_dq_comp.705 0 +motor.cogging_dq_comp.706 0 +motor.cogging_dq_comp.707 0 +motor.cogging_dq_comp.708 0 +motor.cogging_dq_comp.709 0 +motor.cogging_dq_comp.710 0 +motor.cogging_dq_comp.711 0 +motor.cogging_dq_comp.712 0 +motor.cogging_dq_comp.713 0 +motor.cogging_dq_comp.714 0 +motor.cogging_dq_comp.715 0 +motor.cogging_dq_comp.716 0 +motor.cogging_dq_comp.717 0 +motor.cogging_dq_comp.718 0 +motor.cogging_dq_comp.719 0 +motor.cogging_dq_comp.720 0 +motor.cogging_dq_comp.721 0 +motor.cogging_dq_comp.722 0 +motor.cogging_dq_comp.723 0 +motor.cogging_dq_comp.724 0 +motor.cogging_dq_comp.725 0 +motor.cogging_dq_comp.726 0 +motor.cogging_dq_comp.727 0 +motor.cogging_dq_comp.728 0 +motor.cogging_dq_comp.729 0 +motor.cogging_dq_comp.730 0 +motor.cogging_dq_comp.731 0 +motor.cogging_dq_comp.732 0 +motor.cogging_dq_comp.733 0 +motor.cogging_dq_comp.734 0 +motor.cogging_dq_comp.735 0 +motor.cogging_dq_comp.736 0 +motor.cogging_dq_comp.737 0 +motor.cogging_dq_comp.738 0 +motor.cogging_dq_comp.739 0 +motor.cogging_dq_comp.740 0 +motor.cogging_dq_comp.741 0 +motor.cogging_dq_comp.742 0 +motor.cogging_dq_comp.743 0 +motor.cogging_dq_comp.744 0 +motor.cogging_dq_comp.745 0 +motor.cogging_dq_comp.746 0 +motor.cogging_dq_comp.747 0 +motor.cogging_dq_comp.748 0 +motor.cogging_dq_comp.749 0 +motor.cogging_dq_comp.750 0 +motor.cogging_dq_comp.751 0 +motor.cogging_dq_comp.752 0 +motor.cogging_dq_comp.753 0 +motor.cogging_dq_comp.754 0 +motor.cogging_dq_comp.755 0 +motor.cogging_dq_comp.756 0 +motor.cogging_dq_comp.757 0 +motor.cogging_dq_comp.758 0 +motor.cogging_dq_comp.759 0 +motor.cogging_dq_comp.760 0 +motor.cogging_dq_comp.761 0 +motor.cogging_dq_comp.762 0 +motor.cogging_dq_comp.763 0 +motor.cogging_dq_comp.764 0 +motor.cogging_dq_comp.765 0 +motor.cogging_dq_comp.766 0 +motor.cogging_dq_comp.767 0 +motor.cogging_dq_comp.768 0 +motor.cogging_dq_comp.769 0 +motor.cogging_dq_comp.770 0 +motor.cogging_dq_comp.771 0 +motor.cogging_dq_comp.772 0 +motor.cogging_dq_comp.773 0 +motor.cogging_dq_comp.774 0 +motor.cogging_dq_comp.775 0 +motor.cogging_dq_comp.776 0 +motor.cogging_dq_comp.777 0 +motor.cogging_dq_comp.778 0 +motor.cogging_dq_comp.779 0 +motor.cogging_dq_comp.780 0 +motor.cogging_dq_comp.781 0 +motor.cogging_dq_comp.782 0 +motor.cogging_dq_comp.783 0 +motor.cogging_dq_comp.784 0 +motor.cogging_dq_comp.785 0 +motor.cogging_dq_comp.786 0 +motor.cogging_dq_comp.787 0 +motor.cogging_dq_comp.788 0 +motor.cogging_dq_comp.789 0 +motor.cogging_dq_comp.790 0 +motor.cogging_dq_comp.791 0 +motor.cogging_dq_comp.792 0 +motor.cogging_dq_comp.793 0 +motor.cogging_dq_comp.794 0 +motor.cogging_dq_comp.795 0 +motor.cogging_dq_comp.796 0 +motor.cogging_dq_comp.797 0 +motor.cogging_dq_comp.798 0 +motor.cogging_dq_comp.799 0 +motor.cogging_dq_comp.800 0 +motor.cogging_dq_comp.801 0 +motor.cogging_dq_comp.802 0 +motor.cogging_dq_comp.803 0 +motor.cogging_dq_comp.804 0 +motor.cogging_dq_comp.805 0 +motor.cogging_dq_comp.806 0 +motor.cogging_dq_comp.807 0 +motor.cogging_dq_comp.808 0 +motor.cogging_dq_comp.809 0 +motor.cogging_dq_comp.810 0 +motor.cogging_dq_comp.811 0 +motor.cogging_dq_comp.812 0 +motor.cogging_dq_comp.813 0 +motor.cogging_dq_comp.814 0 +motor.cogging_dq_comp.815 0 +motor.cogging_dq_comp.816 0 +motor.cogging_dq_comp.817 0 +motor.cogging_dq_comp.818 0 +motor.cogging_dq_comp.819 0 +motor.cogging_dq_comp.820 0 +motor.cogging_dq_comp.821 0 +motor.cogging_dq_comp.822 0 +motor.cogging_dq_comp.823 0 +motor.cogging_dq_comp.824 0 +motor.cogging_dq_comp.825 0 +motor.cogging_dq_comp.826 0 +motor.cogging_dq_comp.827 0 +motor.cogging_dq_comp.828 0 +motor.cogging_dq_comp.829 0 +motor.cogging_dq_comp.830 0 +motor.cogging_dq_comp.831 0 +motor.cogging_dq_comp.832 0 +motor.cogging_dq_comp.833 0 +motor.cogging_dq_comp.834 0 +motor.cogging_dq_comp.835 0 +motor.cogging_dq_comp.836 0 +motor.cogging_dq_comp.837 0 +motor.cogging_dq_comp.838 0 +motor.cogging_dq_comp.839 0 +motor.cogging_dq_comp.840 0 +motor.cogging_dq_comp.841 0 +motor.cogging_dq_comp.842 0 +motor.cogging_dq_comp.843 0 +motor.cogging_dq_comp.844 0 +motor.cogging_dq_comp.845 0 +motor.cogging_dq_comp.846 0 +motor.cogging_dq_comp.847 0 +motor.cogging_dq_comp.848 0 +motor.cogging_dq_comp.849 0 +motor.cogging_dq_comp.850 0 +motor.cogging_dq_comp.851 0 +motor.cogging_dq_comp.852 0 +motor.cogging_dq_comp.853 0 +motor.cogging_dq_comp.854 0 +motor.cogging_dq_comp.855 0 +motor.cogging_dq_comp.856 0 +motor.cogging_dq_comp.857 0 +motor.cogging_dq_comp.858 0 +motor.cogging_dq_comp.859 0 +motor.cogging_dq_comp.860 0 +motor.cogging_dq_comp.861 0 +motor.cogging_dq_comp.862 0 +motor.cogging_dq_comp.863 0 +motor.cogging_dq_comp.864 0 +motor.cogging_dq_comp.865 0 +motor.cogging_dq_comp.866 0 +motor.cogging_dq_comp.867 0 +motor.cogging_dq_comp.868 0 +motor.cogging_dq_comp.869 0 +motor.cogging_dq_comp.870 0 +motor.cogging_dq_comp.871 0 +motor.cogging_dq_comp.872 0 +motor.cogging_dq_comp.873 0 +motor.cogging_dq_comp.874 0 +motor.cogging_dq_comp.875 0 +motor.cogging_dq_comp.876 0 +motor.cogging_dq_comp.877 0 +motor.cogging_dq_comp.878 0 +motor.cogging_dq_comp.879 0 +motor.cogging_dq_comp.880 0 +motor.cogging_dq_comp.881 0 +motor.cogging_dq_comp.882 0 +motor.cogging_dq_comp.883 0 +motor.cogging_dq_comp.884 0 +motor.cogging_dq_comp.885 0 +motor.cogging_dq_comp.886 0 +motor.cogging_dq_comp.887 0 +motor.cogging_dq_comp.888 0 +motor.cogging_dq_comp.889 0 +motor.cogging_dq_comp.890 0 +motor.cogging_dq_comp.891 0 +motor.cogging_dq_comp.892 0 +motor.cogging_dq_comp.893 0 +motor.cogging_dq_comp.894 0 +motor.cogging_dq_comp.895 0 +motor.cogging_dq_comp.896 0 +motor.cogging_dq_comp.897 0 +motor.cogging_dq_comp.898 0 +motor.cogging_dq_comp.899 0 +motor.cogging_dq_comp.900 0 +motor.cogging_dq_comp.901 0 +motor.cogging_dq_comp.902 0 +motor.cogging_dq_comp.903 0 +motor.cogging_dq_comp.904 0 +motor.cogging_dq_comp.905 0 +motor.cogging_dq_comp.906 0 +motor.cogging_dq_comp.907 0 +motor.cogging_dq_comp.908 0 +motor.cogging_dq_comp.909 0 +motor.cogging_dq_comp.910 0 +motor.cogging_dq_comp.911 0 +motor.cogging_dq_comp.912 0 +motor.cogging_dq_comp.913 0 +motor.cogging_dq_comp.914 0 +motor.cogging_dq_comp.915 0 +motor.cogging_dq_comp.916 0 +motor.cogging_dq_comp.917 0 +motor.cogging_dq_comp.918 0 +motor.cogging_dq_comp.919 0 +motor.cogging_dq_comp.920 0 +motor.cogging_dq_comp.921 0 +motor.cogging_dq_comp.922 0 +motor.cogging_dq_comp.923 0 +motor.cogging_dq_comp.924 0 +motor.cogging_dq_comp.925 0 +motor.cogging_dq_comp.926 0 +motor.cogging_dq_comp.927 0 +motor.cogging_dq_comp.928 0 +motor.cogging_dq_comp.929 0 +motor.cogging_dq_comp.930 0 +motor.cogging_dq_comp.931 0 +motor.cogging_dq_comp.932 0 +motor.cogging_dq_comp.933 0 +motor.cogging_dq_comp.934 0 +motor.cogging_dq_comp.935 0 +motor.cogging_dq_comp.936 0 +motor.cogging_dq_comp.937 0 +motor.cogging_dq_comp.938 0 +motor.cogging_dq_comp.939 0 +motor.cogging_dq_comp.940 0 +motor.cogging_dq_comp.941 0 +motor.cogging_dq_comp.942 0 +motor.cogging_dq_comp.943 0 +motor.cogging_dq_comp.944 0 +motor.cogging_dq_comp.945 0 +motor.cogging_dq_comp.946 0 +motor.cogging_dq_comp.947 0 +motor.cogging_dq_comp.948 0 +motor.cogging_dq_comp.949 0 +motor.cogging_dq_comp.950 0 +motor.cogging_dq_comp.951 0 +motor.cogging_dq_comp.952 0 +motor.cogging_dq_comp.953 0 +motor.cogging_dq_comp.954 0 +motor.cogging_dq_comp.955 0 +motor.cogging_dq_comp.956 0 +motor.cogging_dq_comp.957 0 +motor.cogging_dq_comp.958 0 +motor.cogging_dq_comp.959 0 +motor.cogging_dq_comp.960 0 +motor.cogging_dq_comp.961 0 +motor.cogging_dq_comp.962 0 +motor.cogging_dq_comp.963 0 +motor.cogging_dq_comp.964 0 +motor.cogging_dq_comp.965 0 +motor.cogging_dq_comp.966 0 +motor.cogging_dq_comp.967 0 +motor.cogging_dq_comp.968 0 +motor.cogging_dq_comp.969 0 +motor.cogging_dq_comp.970 0 +motor.cogging_dq_comp.971 0 +motor.cogging_dq_comp.972 0 +motor.cogging_dq_comp.973 0 +motor.cogging_dq_comp.974 0 +motor.cogging_dq_comp.975 0 +motor.cogging_dq_comp.976 0 +motor.cogging_dq_comp.977 0 +motor.cogging_dq_comp.978 0 +motor.cogging_dq_comp.979 0 +motor.cogging_dq_comp.980 0 +motor.cogging_dq_comp.981 0 +motor.cogging_dq_comp.982 0 +motor.cogging_dq_comp.983 0 +motor.cogging_dq_comp.984 0 +motor.cogging_dq_comp.985 0 +motor.cogging_dq_comp.986 0 +motor.cogging_dq_comp.987 0 +motor.cogging_dq_comp.988 0 +motor.cogging_dq_comp.989 0 +motor.cogging_dq_comp.990 0 +motor.cogging_dq_comp.991 0 +motor.cogging_dq_comp.992 0 +motor.cogging_dq_comp.993 0 +motor.cogging_dq_comp.994 0 +motor.cogging_dq_comp.995 0 +motor.cogging_dq_comp.996 0 +motor.cogging_dq_comp.997 0 +motor.cogging_dq_comp.998 0 +motor.cogging_dq_comp.999 0 +motor.cogging_dq_comp.1000 0 +motor.cogging_dq_comp.1001 0 +motor.cogging_dq_comp.1002 0 +motor.cogging_dq_comp.1003 0 +motor.cogging_dq_comp.1004 0 +motor.cogging_dq_comp.1005 0 +motor.cogging_dq_comp.1006 0 +motor.cogging_dq_comp.1007 0 +motor.cogging_dq_comp.1008 0 +motor.cogging_dq_comp.1009 0 +motor.cogging_dq_comp.1010 0 +motor.cogging_dq_comp.1011 0 +motor.cogging_dq_comp.1012 0 +motor.cogging_dq_comp.1013 0 +motor.cogging_dq_comp.1014 0 +motor.cogging_dq_comp.1015 0 +motor.cogging_dq_comp.1016 0 +motor.cogging_dq_comp.1017 0 +motor.cogging_dq_comp.1018 0 +motor.cogging_dq_comp.1019 0 +motor.cogging_dq_comp.1020 0 +motor.cogging_dq_comp.1021 0 +motor.cogging_dq_comp.1022 0 +motor.cogging_dq_comp.1023 0 +drv8323_conf.dis_cpuv 0 +drv8323_conf.dis_gdf 0 +drv8323_conf.otw_rep 0 +drv8323_conf.pwm_mode 1 +drv8323_conf.pwm_1x_asynchronous 0 +drv8323_conf.pwm_1x_dir 0 +drv8323_conf.idrivep_hs_ma 100 +drv8323_conf.idriven_hs_ma 200 +drv8323_conf.cbc 1 +drv8323_conf.tdrive_ns 1000 +drv8323_conf.idrivep_ls_ma 100 +drv8323_conf.idriven_ls_ma 200 +drv8323_conf.tretry 0 +drv8323_conf.dead_time_ns 50 +drv8323_conf.ocp_mode 0 +drv8323_conf.ocp_deg_us 4 +drv8323_conf.vds_lvl_mv 700 +drv8323_conf.csa_fet 0 +drv8323_conf.vref_div 1 +drv8323_conf.ls_ref 0 +drv8323_conf.csa_gain 20 +drv8323_conf.dis_sen 0 +drv8323_conf.sen_lvl_mv 500 +servo.pwm_rate_hz 30000 +servo.i_gain 20.000000 +servo.current_sense_ohm 0.000500 +servo.pwm_comp_off 0.027000 +servo.pwm_comp_mag 0.005000 +servo.pwm_scale 1.000000 +servo.max_voltage 46.000000 +servo.max_power_W 450.000000 +servo.derate_temperature 50.000000 +servo.fault_temperature 75.000000 +servo.enable_motor_temperature 0 +servo.motor_derate_temperature 50.000000 +servo.motor_fault_temperature nan +servo.velocity_threshold 0.000000 +servo.position_derate 0.020000 +servo.adc_cur_cycles 2 +servo.adc_aux_cycles 47 +servo.pid_dq.kp 1.341388 +servo.pid_dq.ki 2513.487549 +servo.pid_position.kp 1500.000000 +servo.pid_position.ki 0.000000 +servo.pid_position.kd 0.000000 +servo.pid_position.iratelimit -1.000000 +servo.pid_position.ilimit 0.000000 +servo.pid_position.max_desired_rate 0.000000 +servo.pid_position.sign -1 +servo.current_feedforward 1.000000 +servo.bemf_feedforward 1.000000 +servo.default_velocity_limit 0.050000 +servo.default_accel_limit 0.200000 +servo.voltage_mode_control 0 +servo.fixed_voltage_mode 0 +servo.fixed_voltage_control_V 0.000000 +servo.max_position_slip nan +servo.max_velocity_slip nan +servo.default_timeout_s 0.100000 +servo.timeout_max_torque_Nm 5.000000 +servo.timeout_mode 12 +servo.flux_brake_min_voltage 43.500000 +servo.flux_brake_resistance_ohm 0.025000 +servo.max_current_A 100.000000 +servo.derate_current_A -20.000000 +servo.max_velocity 0.100000 +servo.max_velocity_derate 2.000000 +servo.cooldown_cycles 256 +servo.velocity_zero_capture_threshold 0.050000 +servo.timing_fault 0 +servo.emit_debug 0 +servopos.position_min nan +servopos.position_max nan +id.id 49 +can.prefix 0 + diff --git a/config/teleop.yaml b/config/teleop.yaml index 2158f1ef4..8c05ad09a 100644 --- a/config/teleop.yaml +++ b/config/teleop.yaml @@ -4,54 +4,48 @@ teleop: ra_names: ["joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"] ra_controls: joint_a: - multiplier: 1 + multiplier: -1 slow_mode_multiplier: 0.5 - invert: False + invert: True xbox_index: 0 joint_b: - multiplier: -1 + multiplier: 1 slow_mode_multiplier: 1 - invert: True + invert: False xbox_index: 1 joint_c: multiplier: -1 slow_mode_multiplier: 0.6 - invert: True + invert: False xbox_index: 3 joint_de_pitch: multiplier: 0.5 slow_mode_multiplier: 1 - invert: False - xbox_index_left: 4 - xbox_index_right: 5 + invert: True joint_de_roll: - multiplier: 0.5 + multiplier: -0.5 slow_mode_multiplier: 1 - invert: False - xbox_index_left: 4 - xbox_index_right: 5 + invert: True allen_key: multiplier: 1 slow_mode_multiplier: 1 invert: False - # xbox_index: 7 gripper: multiplier: 1 slow_mode_multiplier: 1 - invert: False - # xbox_index: 7 + invert: True sa_controls: sa_x: multiplier: 1 - slow_mode_multiplier: 0.5 + slow_mode_multiplier: 1.0 # 0.5 xbox_index: 1 sa_y: multiplier: -1 - slow_mode_multiplier: 0.5 + slow_mode_multiplier: 1.0 # 0.5 xbox_index: 0 sa_z: - multiplier: -1 + multiplier: 1 slow_mode_multiplier: 0.5 xbox_index: 4 sampler: @@ -80,20 +74,18 @@ teleop: left_js_y: 1 right_js_x: 2 right_js_y: 3 - left_trigger: 4 - right_trigger: 5 + left_trigger: 6 + right_trigger: 7 a: 0 b: 1 - x: 3 - y: 2 + x: 2 + y: 3 left_bumper: 4 right_bumper: 5 - d_pad_x: 6 - d_pad_y: 7 joystick_mappings: - left_right: 1 - forward_back: 0 + left_right: 0 + forward_back: 1 twist: 2 dampen: 3 pan: 4 diff --git a/deps/dawn b/deps/dawn index 5096820bf..e12af2be9 160000 --- a/deps/dawn +++ b/deps/dawn @@ -1 +1 @@ -Subproject commit 5096820bfc553c002ab97c05002b3c22c00a7f8f +Subproject commit e12af2be97514e32ccc0d2d1ec1995bec7201c97 diff --git a/deps/imgui/backends/imgui_impl_wgpu.cpp b/deps/imgui/backends/imgui_impl_wgpu.cpp index f41b8c8d5..94caded3a 100644 --- a/deps/imgui/backends/imgui_impl_wgpu.cpp +++ b/deps/imgui/backends/imgui_impl_wgpu.cpp @@ -16,6 +16,10 @@ // CHANGELOG // (minor and older changes stripped away, please see git history for details) +// 2024-01-22: Added configurable PipelineMultisampleState struct. (#7240) +// 2024-01-22: (Breaking) ImGui_ImplWGPU_Init() now takes a ImGui_ImplWGPU_InitInfo structure instead of variety of parameters, allowing for easier further changes. +// 2024-01-22: Fixed pipeline layout leak. (#7245) +// 2024-01-17: Explicitly fill all of WGPUDepthStencilState since standard removed defaults. // 2023-07-13: Use WGPUShaderModuleWGSLDescriptor's code instead of source. use WGPUMipmapFilterMode_Linear instead of WGPUFilterMode_Linear. (#6602) // 2023-04-11: Align buffer sizes. Use WGSL shaders instead of precompiled SPIR-V. // 2023-04-11: Reorganized backend to pull data from a single structure to facilitate usage with multiple-contexts (all g_XXXX access changed to bd->XXXX). @@ -72,16 +76,17 @@ struct Uniforms struct ImGui_ImplWGPU_Data { - WGPUDevice wgpuDevice = nullptr; - WGPUQueue defaultQueue = nullptr; - WGPUTextureFormat renderTargetFormat = WGPUTextureFormat_Undefined; - WGPUTextureFormat depthStencilFormat = WGPUTextureFormat_Undefined; - WGPURenderPipeline pipelineState = nullptr; - - RenderResources renderResources; - FrameResources* pFrameResources = nullptr; - unsigned int numFramesInFlight = 0; - unsigned int frameIndex = UINT_MAX; + ImGui_ImplWGPU_InitInfo initInfo; + WGPUDevice wgpuDevice = nullptr; + WGPUQueue defaultQueue = nullptr; + WGPUTextureFormat renderTargetFormat = WGPUTextureFormat_Undefined; + WGPUTextureFormat depthStencilFormat = WGPUTextureFormat_Undefined; + WGPURenderPipeline pipelineState = nullptr; + + RenderResources renderResources; + FrameResources* pFrameResources = nullptr; + unsigned int numFramesInFlight = 0; + unsigned int frameIndex = UINT_MAX; }; // Backend data stored in io.BackendRendererUserData to allow support for multiple Dear ImGui contexts @@ -187,6 +192,12 @@ static void SafeRelease(WGPUBuffer& res) wgpuBufferRelease(res); res = nullptr; } +static void SafeRelease(WGPUPipelineLayout& res) +{ + if (res) + wgpuPipelineLayoutRelease(res); + res = nullptr; +} static void SafeRelease(WGPURenderPipeline& res) { if (res) @@ -573,9 +584,7 @@ bool ImGui_ImplWGPU_CreateDeviceObjects() graphics_pipeline_desc.primitive.stripIndexFormat = WGPUIndexFormat_Undefined; graphics_pipeline_desc.primitive.frontFace = WGPUFrontFace_CW; graphics_pipeline_desc.primitive.cullMode = WGPUCullMode_None; - graphics_pipeline_desc.multisample.count = 1; - graphics_pipeline_desc.multisample.mask = UINT_MAX; - graphics_pipeline_desc.multisample.alphaToCoverageEnabled = false; + graphics_pipeline_desc.multisample = bd->initInfo.PipelineMultisampleState; // Bind group layouts WGPUBindGroupLayoutEntry common_bg_layout_entries[2] = {}; @@ -667,7 +676,13 @@ bool ImGui_ImplWGPU_CreateDeviceObjects() depth_stencil_state.depthWriteEnabled = false; depth_stencil_state.depthCompare = WGPUCompareFunction_Always; depth_stencil_state.stencilFront.compare = WGPUCompareFunction_Always; + depth_stencil_state.stencilFront.failOp = WGPUStencilOperation_Keep; + depth_stencil_state.stencilFront.depthFailOp = WGPUStencilOperation_Keep; + depth_stencil_state.stencilFront.passOp = WGPUStencilOperation_Keep; depth_stencil_state.stencilBack.compare = WGPUCompareFunction_Always; + depth_stencil_state.stencilBack.failOp = WGPUStencilOperation_Keep; + depth_stencil_state.stencilBack.depthFailOp = WGPUStencilOperation_Keep; + depth_stencil_state.stencilBack.passOp = WGPUStencilOperation_Keep; // Configure disabled depth-stencil state graphics_pipeline_desc.depthStencil = (bd->depthStencilFormat == WGPUTextureFormat_Undefined) ? nullptr : &depth_stencil_state; @@ -697,6 +712,7 @@ bool ImGui_ImplWGPU_CreateDeviceObjects() SafeRelease(vertex_shader_desc.module); SafeRelease(pixel_shader_desc.module); + SafeRelease(graphics_pipeline_desc.layout); SafeRelease(bg_layouts[0]); return true; @@ -718,7 +734,7 @@ void ImGui_ImplWGPU_InvalidateDeviceObjects() SafeRelease(bd->pFrameResources[i]); } -bool ImGui_ImplWGPU_Init(WGPUDevice device, int num_frames_in_flight, WGPUTextureFormat rt_format, WGPUTextureFormat depth_format) +bool ImGui_ImplWGPU_Init(ImGui_ImplWGPU_InitInfo* init_info) { ImGuiIO& io = ImGui::GetIO(); IM_ASSERT(io.BackendRendererUserData == nullptr && "Already initialized a renderer backend!"); @@ -729,11 +745,12 @@ bool ImGui_ImplWGPU_Init(WGPUDevice device, int num_frames_in_flight, WGPUTextur io.BackendRendererName = "imgui_impl_webgpu"; io.BackendFlags |= ImGuiBackendFlags_RendererHasVtxOffset; // We can honor the ImDrawCmd::VtxOffset field, allowing for large meshes. - bd->wgpuDevice = device; + bd->initInfo = *init_info; + bd->wgpuDevice = init_info->Device; bd->defaultQueue = wgpuDeviceGetQueue(bd->wgpuDevice); - bd->renderTargetFormat = rt_format; - bd->depthStencilFormat = depth_format; - bd->numFramesInFlight = num_frames_in_flight; + bd->renderTargetFormat = init_info->RenderTargetFormat; + bd->depthStencilFormat = init_info->DepthStencilFormat; + bd->numFramesInFlight = init_info->NumFramesInFlight; bd->frameIndex = UINT_MAX; bd->renderResources.FontTexture = nullptr; @@ -746,8 +763,8 @@ bool ImGui_ImplWGPU_Init(WGPUDevice device, int num_frames_in_flight, WGPUTextur bd->renderResources.ImageBindGroupLayout = nullptr; // Create buffers with a default size (they will later be grown as needed) - bd->pFrameResources = new FrameResources[num_frames_in_flight]; - for (int i = 0; i < num_frames_in_flight; i++) + bd->pFrameResources = new FrameResources[bd->numFramesInFlight]; + for (int i = 0; i < bd->numFramesInFlight; i++) { FrameResources* fr = &bd->pFrameResources[i]; fr->IndexBuffer = nullptr; diff --git a/deps/imgui/backends/imgui_impl_wgpu.h b/deps/imgui/backends/imgui_impl_wgpu.h index 14d9fccc1..57ddd78fc 100644 --- a/deps/imgui/backends/imgui_impl_wgpu.h +++ b/deps/imgui/backends/imgui_impl_wgpu.h @@ -20,7 +20,24 @@ #include -IMGUI_IMPL_API bool ImGui_ImplWGPU_Init(WGPUDevice device, int num_frames_in_flight, WGPUTextureFormat rt_format, WGPUTextureFormat depth_format = WGPUTextureFormat_Undefined); +// Initialization data, for ImGui_ImplWGPU_Init() +struct ImGui_ImplWGPU_InitInfo +{ + WGPUDevice Device; + int NumFramesInFlight = 3; + WGPUTextureFormat RenderTargetFormat = WGPUTextureFormat_Undefined; + WGPUTextureFormat DepthStencilFormat = WGPUTextureFormat_Undefined; + WGPUMultisampleState PipelineMultisampleState = {}; + + ImGui_ImplWGPU_InitInfo() + { + PipelineMultisampleState.count = 1; + PipelineMultisampleState.mask = UINT32_MAX; + PipelineMultisampleState.alphaToCoverageEnabled = false; + } +}; + +IMGUI_IMPL_API bool ImGui_ImplWGPU_Init(ImGui_ImplWGPU_InitInfo* init_info); IMGUI_IMPL_API void ImGui_ImplWGPU_Shutdown(); IMGUI_IMPL_API void ImGui_ImplWGPU_NewFrame(); IMGUI_IMPL_API void ImGui_ImplWGPU_RenderDrawData(ImDrawData* draw_data, WGPURenderPassEncoder pass_encoder); @@ -29,4 +46,4 @@ IMGUI_IMPL_API void ImGui_ImplWGPU_RenderDrawData(ImDrawData* draw_data, WGPURen IMGUI_IMPL_API void ImGui_ImplWGPU_InvalidateDeviceObjects(); IMGUI_IMPL_API bool ImGui_ImplWGPU_CreateDeviceObjects(); -#endif // #ifndef IMGUI_DISABLE +#endif // #ifndef IMGUI_DISABLE \ No newline at end of file diff --git a/deps/webgpuhpp/webgpu.hpp b/deps/webgpuhpp/webgpu.hpp index 9cb503b0f..7fc8a2478 100644 --- a/deps/webgpuhpp/webgpu.hpp +++ b/deps/webgpuhpp/webgpu.hpp @@ -3,7 +3,7 @@ * https://github.com/eliemichel/LearnWebGPU * * MIT License - * Copyright (c) 2022 Elie Michel + * Copyright (c) 2022-2024 Elie Michel * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -59,6 +59,7 @@ class Type { \ public: \ typedef Type S; /* S == Self */ \ typedef WGPU ## Type W; /* W == WGPU Type */ \ + Type() : m_raw(nullptr) {} \ Type(const W& w) : m_raw(w) {} \ operator W&() { return m_raw; } \ operator const W&() const { return m_raw; } \ @@ -118,35 +119,50 @@ private: \ #define END }; - +constexpr static uint32_t kDepthSliceUndefined = std::numeric_limits::max(); // Other type aliases using Flags = uint32_t; using Bool = uint32_t; using BufferUsageFlags = WGPUFlags; using ColorWriteMaskFlags = WGPUFlags; +using HeapPropertyFlags = WGPUFlags; using MapModeFlags = WGPUFlags; using ShaderStageFlags = WGPUFlags; using TextureUsageFlags = WGPUFlags; // Enumerations +ENUM(WGSLFeatureName) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(ReadonlyAndReadwriteStorageTextures, 0x00000001) + ENUM_ENTRY(Packed4x8IntegerDotProduct, 0x00000002) + ENUM_ENTRY(UnrestrictedPointerParameters, 0x00000003) + ENUM_ENTRY(PointerCompositeAccess, 0x00000004) + ENUM_ENTRY(ChromiumTestingUnimplemented, 0x000003E8) + ENUM_ENTRY(ChromiumTestingUnsafeExperimental, 0x000003E9) + ENUM_ENTRY(ChromiumTestingExperimental, 0x000003EA) + ENUM_ENTRY(ChromiumTestingShippedWithKillswitch, 0x000003EB) + ENUM_ENTRY(ChromiumTestingShipped, 0x000003EC) + ENUM_ENTRY(Force32, 0x7FFFFFFF) +END ENUM(AdapterType) - ENUM_ENTRY(DiscreteGPU, 0x00000000) - ENUM_ENTRY(IntegratedGPU, 0x00000001) - ENUM_ENTRY(CPU, 0x00000002) - ENUM_ENTRY(Unknown, 0x00000003) + ENUM_ENTRY(DiscreteGPU, 0x00000001) + ENUM_ENTRY(IntegratedGPU, 0x00000002) + ENUM_ENTRY(CPU, 0x00000003) + ENUM_ENTRY(Unknown, 0x00000004) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(AddressMode) - ENUM_ENTRY(Repeat, 0x00000000) - ENUM_ENTRY(MirrorRepeat, 0x00000001) - ENUM_ENTRY(ClampToEdge, 0x00000002) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(ClampToEdge, 0x00000001) + ENUM_ENTRY(Repeat, 0x00000002) + ENUM_ENTRY(MirrorRepeat, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(AlphaMode) - ENUM_ENTRY(Premultiplied, 0x00000000) - ENUM_ENTRY(Unpremultiplied, 0x00000001) - ENUM_ENTRY(Opaque, 0x00000002) + ENUM_ENTRY(Opaque, 0x00000001) + ENUM_ENTRY(Premultiplied, 0x00000002) + ENUM_ENTRY(Unpremultiplied, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(BackendType) @@ -162,31 +178,33 @@ ENUM(BackendType) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(BlendFactor) - ENUM_ENTRY(Zero, 0x00000000) - ENUM_ENTRY(One, 0x00000001) - ENUM_ENTRY(Src, 0x00000002) - ENUM_ENTRY(OneMinusSrc, 0x00000003) - ENUM_ENTRY(SrcAlpha, 0x00000004) - ENUM_ENTRY(OneMinusSrcAlpha, 0x00000005) - ENUM_ENTRY(Dst, 0x00000006) - ENUM_ENTRY(OneMinusDst, 0x00000007) - ENUM_ENTRY(DstAlpha, 0x00000008) - ENUM_ENTRY(OneMinusDstAlpha, 0x00000009) - ENUM_ENTRY(SrcAlphaSaturated, 0x0000000A) - ENUM_ENTRY(Constant, 0x0000000B) - ENUM_ENTRY(OneMinusConstant, 0x0000000C) - ENUM_ENTRY(Src1, 0x0000000D) - ENUM_ENTRY(OneMinusSrc1, 0x0000000E) - ENUM_ENTRY(Src1Alpha, 0x0000000F) - ENUM_ENTRY(OneMinusSrc1Alpha, 0x00000010) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(Zero, 0x00000001) + ENUM_ENTRY(One, 0x00000002) + ENUM_ENTRY(Src, 0x00000003) + ENUM_ENTRY(OneMinusSrc, 0x00000004) + ENUM_ENTRY(SrcAlpha, 0x00000005) + ENUM_ENTRY(OneMinusSrcAlpha, 0x00000006) + ENUM_ENTRY(Dst, 0x00000007) + ENUM_ENTRY(OneMinusDst, 0x00000008) + ENUM_ENTRY(DstAlpha, 0x00000009) + ENUM_ENTRY(OneMinusDstAlpha, 0x0000000A) + ENUM_ENTRY(SrcAlphaSaturated, 0x0000000B) + ENUM_ENTRY(Constant, 0x0000000C) + ENUM_ENTRY(OneMinusConstant, 0x0000000D) + ENUM_ENTRY(Src1, 0x0000000E) + ENUM_ENTRY(OneMinusSrc1, 0x0000000F) + ENUM_ENTRY(Src1Alpha, 0x00000010) + ENUM_ENTRY(OneMinusSrc1Alpha, 0x00000011) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(BlendOperation) - ENUM_ENTRY(Add, 0x00000000) - ENUM_ENTRY(Subtract, 0x00000001) - ENUM_ENTRY(ReverseSubtract, 0x00000002) - ENUM_ENTRY(Min, 0x00000003) - ENUM_ENTRY(Max, 0x00000004) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(Add, 0x00000001) + ENUM_ENTRY(Subtract, 0x00000002) + ENUM_ENTRY(ReverseSubtract, 0x00000003) + ENUM_ENTRY(Min, 0x00000004) + ENUM_ENTRY(Max, 0x00000005) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(BufferBindingType) @@ -198,20 +216,21 @@ ENUM(BufferBindingType) END ENUM(BufferMapAsyncStatus) ENUM_ENTRY(Success, 0x00000000) - ENUM_ENTRY(ValidationError, 0x00000001) - ENUM_ENTRY(Unknown, 0x00000002) - ENUM_ENTRY(DeviceLost, 0x00000003) - ENUM_ENTRY(DestroyedBeforeCallback, 0x00000004) - ENUM_ENTRY(UnmappedBeforeCallback, 0x00000005) - ENUM_ENTRY(MappingAlreadyPending, 0x00000006) - ENUM_ENTRY(OffsetOutOfRange, 0x00000007) - ENUM_ENTRY(SizeOutOfRange, 0x00000008) + ENUM_ENTRY(InstanceDropped, 0x00000001) + ENUM_ENTRY(ValidationError, 0x00000002) + ENUM_ENTRY(Unknown, 0x00000003) + ENUM_ENTRY(DeviceLost, 0x00000004) + ENUM_ENTRY(DestroyedBeforeCallback, 0x00000005) + ENUM_ENTRY(UnmappedBeforeCallback, 0x00000006) + ENUM_ENTRY(MappingAlreadyPending, 0x00000007) + ENUM_ENTRY(OffsetOutOfRange, 0x00000008) + ENUM_ENTRY(SizeOutOfRange, 0x00000009) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(BufferMapState) - ENUM_ENTRY(Unmapped, 0x00000000) - ENUM_ENTRY(Pending, 0x00000001) - ENUM_ENTRY(Mapped, 0x00000002) + ENUM_ENTRY(Unmapped, 0x00000001) + ENUM_ENTRY(Pending, 0x00000002) + ENUM_ENTRY(Mapped, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(CallbackMode) @@ -224,40 +243,43 @@ ENUM(CompareFunction) ENUM_ENTRY(Undefined, 0x00000000) ENUM_ENTRY(Never, 0x00000001) ENUM_ENTRY(Less, 0x00000002) - ENUM_ENTRY(LessEqual, 0x00000003) - ENUM_ENTRY(Greater, 0x00000004) - ENUM_ENTRY(GreaterEqual, 0x00000005) - ENUM_ENTRY(Equal, 0x00000006) - ENUM_ENTRY(NotEqual, 0x00000007) + ENUM_ENTRY(Equal, 0x00000003) + ENUM_ENTRY(LessEqual, 0x00000004) + ENUM_ENTRY(Greater, 0x00000005) + ENUM_ENTRY(NotEqual, 0x00000006) + ENUM_ENTRY(GreaterEqual, 0x00000007) ENUM_ENTRY(Always, 0x00000008) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(CompilationInfoRequestStatus) ENUM_ENTRY(Success, 0x00000000) - ENUM_ENTRY(Error, 0x00000001) - ENUM_ENTRY(DeviceLost, 0x00000002) - ENUM_ENTRY(Unknown, 0x00000003) + ENUM_ENTRY(InstanceDropped, 0x00000001) + ENUM_ENTRY(Error, 0x00000002) + ENUM_ENTRY(DeviceLost, 0x00000003) + ENUM_ENTRY(Unknown, 0x00000004) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(CompilationMessageType) - ENUM_ENTRY(Error, 0x00000000) - ENUM_ENTRY(Warning, 0x00000001) - ENUM_ENTRY(Info, 0x00000002) + ENUM_ENTRY(Error, 0x00000001) + ENUM_ENTRY(Warning, 0x00000002) + ENUM_ENTRY(Info, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(CreatePipelineAsyncStatus) ENUM_ENTRY(Success, 0x00000000) - ENUM_ENTRY(ValidationError, 0x00000001) - ENUM_ENTRY(InternalError, 0x00000002) - ENUM_ENTRY(DeviceLost, 0x00000003) - ENUM_ENTRY(DeviceDestroyed, 0x00000004) - ENUM_ENTRY(Unknown, 0x00000005) + ENUM_ENTRY(InstanceDropped, 0x00000001) + ENUM_ENTRY(ValidationError, 0x00000002) + ENUM_ENTRY(InternalError, 0x00000003) + ENUM_ENTRY(DeviceLost, 0x00000004) + ENUM_ENTRY(DeviceDestroyed, 0x00000005) + ENUM_ENTRY(Unknown, 0x00000006) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(CullMode) - ENUM_ENTRY(None, 0x00000000) - ENUM_ENTRY(Front, 0x00000001) - ENUM_ENTRY(Back, 0x00000002) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(None, 0x00000001) + ENUM_ENTRY(Front, 0x00000002) + ENUM_ENTRY(Back, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(DeviceLostReason) @@ -266,9 +288,9 @@ ENUM(DeviceLostReason) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(ErrorFilter) - ENUM_ENTRY(Validation, 0x00000000) - ENUM_ENTRY(OutOfMemory, 0x00000001) - ENUM_ENTRY(Internal, 0x00000002) + ENUM_ENTRY(Validation, 0x00000001) + ENUM_ENTRY(OutOfMemory, 0x00000002) + ENUM_ENTRY(Internal, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(ErrorType) @@ -303,7 +325,6 @@ ENUM(FeatureName) ENUM_ENTRY(DawnInternalUsages, 0x000003EA) ENUM_ENTRY(DawnMultiPlanarFormats, 0x000003EB) ENUM_ENTRY(DawnNative, 0x000003EC) - ENUM_ENTRY(ChromiumExperimentalDp4a, 0x000003ED) ENUM_ENTRY(ChromiumExperimentalTimestampQueryInsidePasses, 0x000003EE) ENUM_ENTRY(ImplicitDeviceSynchronization, 0x000003EF) ENUM_ENTRY(SurfaceCapabilities, 0x000003F0) @@ -314,7 +335,6 @@ ENUM(FeatureName) ENUM_ENTRY(ANGLETextureSharing, 0x000003F5) ENUM_ENTRY(ChromiumExperimentalSubgroups, 0x000003F6) ENUM_ENTRY(ChromiumExperimentalSubgroupUniformControlFlow, 0x000003F7) - ENUM_ENTRY(ChromiumExperimentalReadWriteStorageTexture, 0x000003F8) ENUM_ENTRY(PixelLocalStorageCoherent, 0x000003F9) ENUM_ENTRY(PixelLocalStorageNonCoherent, 0x000003FA) ENUM_ENTRY(Norm16TextureFormats, 0x000003FB) @@ -322,6 +342,15 @@ ENUM(FeatureName) ENUM_ENTRY(MultiPlanarFormatP010, 0x000003FD) ENUM_ENTRY(HostMappedPointer, 0x000003FE) ENUM_ENTRY(MultiPlanarRenderTargets, 0x000003FF) + ENUM_ENTRY(MultiPlanarFormatNv12a, 0x00000400) + ENUM_ENTRY(FramebufferFetch, 0x00000401) + ENUM_ENTRY(BufferMapExtendedUsages, 0x00000402) + ENUM_ENTRY(AdapterPropertiesMemoryHeaps, 0x00000403) + ENUM_ENTRY(AdapterPropertiesD3D, 0x00000404) + ENUM_ENTRY(AdapterPropertiesVk, 0x00000405) + ENUM_ENTRY(R8UnormStorage, 0x00000406) + ENUM_ENTRY(FormatCapabilities, 0x00000407) + ENUM_ENTRY(DrmFormatCapabilities, 0x00000408) ENUM_ENTRY(SharedTextureMemoryVkDedicatedAllocation, 0x0000044C) ENUM_ENTRY(SharedTextureMemoryAHardwareBuffer, 0x0000044D) ENUM_ENTRY(SharedTextureMemoryDmaBuf, 0x0000044E) @@ -336,16 +365,20 @@ ENUM(FeatureName) ENUM_ENTRY(SharedFenceVkSemaphoreZirconHandle, 0x000004B2) ENUM_ENTRY(SharedFenceDXGISharedHandle, 0x000004B3) ENUM_ENTRY(SharedFenceMTLSharedEvent, 0x000004B4) + ENUM_ENTRY(SharedBufferMemoryD3D12Resource, 0x000004B5) + ENUM_ENTRY(StaticSamplers, 0x000004B6) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(FilterMode) - ENUM_ENTRY(Nearest, 0x00000000) - ENUM_ENTRY(Linear, 0x00000001) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(Nearest, 0x00000001) + ENUM_ENTRY(Linear, 0x00000002) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(FrontFace) - ENUM_ENTRY(CCW, 0x00000000) - ENUM_ENTRY(CW, 0x00000001) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(CCW, 0x00000001) + ENUM_ENTRY(CW, 0x00000002) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(IndexFormat) @@ -361,15 +394,21 @@ ENUM(LoadOp) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(LoggingType) - ENUM_ENTRY(Verbose, 0x00000000) - ENUM_ENTRY(Info, 0x00000001) - ENUM_ENTRY(Warning, 0x00000002) - ENUM_ENTRY(Error, 0x00000003) + ENUM_ENTRY(Verbose, 0x00000001) + ENUM_ENTRY(Info, 0x00000002) + ENUM_ENTRY(Warning, 0x00000003) + ENUM_ENTRY(Error, 0x00000004) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(MipmapFilterMode) - ENUM_ENTRY(Nearest, 0x00000000) - ENUM_ENTRY(Linear, 0x00000001) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(Nearest, 0x00000001) + ENUM_ENTRY(Linear, 0x00000002) + ENUM_ENTRY(Force32, 0x7FFFFFFF) +END +ENUM(PopErrorScopeStatus) + ENUM_ENTRY(Success, 0x00000000) + ENUM_ENTRY(InstanceDropped, 0x00000001) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(PowerPreference) @@ -379,42 +418,46 @@ ENUM(PowerPreference) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(PresentMode) - ENUM_ENTRY(Fifo, 0x00000000) - ENUM_ENTRY(Immediate, 0x00000002) - ENUM_ENTRY(Mailbox, 0x00000003) + ENUM_ENTRY(Fifo, 0x00000001) + ENUM_ENTRY(Immediate, 0x00000003) + ENUM_ENTRY(Mailbox, 0x00000004) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(PrimitiveTopology) - ENUM_ENTRY(PointList, 0x00000000) - ENUM_ENTRY(LineList, 0x00000001) - ENUM_ENTRY(LineStrip, 0x00000002) - ENUM_ENTRY(TriangleList, 0x00000003) - ENUM_ENTRY(TriangleStrip, 0x00000004) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(PointList, 0x00000001) + ENUM_ENTRY(LineList, 0x00000002) + ENUM_ENTRY(LineStrip, 0x00000003) + ENUM_ENTRY(TriangleList, 0x00000004) + ENUM_ENTRY(TriangleStrip, 0x00000005) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(QueryType) - ENUM_ENTRY(Occlusion, 0x00000000) - ENUM_ENTRY(Timestamp, 0x00000001) + ENUM_ENTRY(Occlusion, 0x00000001) + ENUM_ENTRY(Timestamp, 0x00000002) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(QueueWorkDoneStatus) ENUM_ENTRY(Success, 0x00000000) - ENUM_ENTRY(Error, 0x00000001) - ENUM_ENTRY(Unknown, 0x00000002) - ENUM_ENTRY(DeviceLost, 0x00000003) + ENUM_ENTRY(InstanceDropped, 0x00000001) + ENUM_ENTRY(Error, 0x00000002) + ENUM_ENTRY(Unknown, 0x00000003) + ENUM_ENTRY(DeviceLost, 0x00000004) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(RequestAdapterStatus) ENUM_ENTRY(Success, 0x00000000) - ENUM_ENTRY(Unavailable, 0x00000001) - ENUM_ENTRY(Error, 0x00000002) - ENUM_ENTRY(Unknown, 0x00000003) + ENUM_ENTRY(InstanceDropped, 0x00000001) + ENUM_ENTRY(Unavailable, 0x00000002) + ENUM_ENTRY(Error, 0x00000003) + ENUM_ENTRY(Unknown, 0x00000004) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(RequestDeviceStatus) ENUM_ENTRY(Success, 0x00000000) - ENUM_ENTRY(Error, 0x00000001) - ENUM_ENTRY(Unknown, 0x00000002) + ENUM_ENTRY(InstanceDropped, 0x00000001) + ENUM_ENTRY(Error, 0x00000002) + ENUM_ENTRY(Unknown, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(SType) @@ -434,6 +477,7 @@ ENUM(SType) ENUM_ENTRY(SurfaceDescriptorFromWindowsSwapChainPanel, 0x0000000E) ENUM_ENTRY(RenderPassDescriptorMaxDrawCount, 0x0000000F) ENUM_ENTRY(DepthStencilStateDepthWriteDefinedDawn, 0x00000010) + ENUM_ENTRY(TextureBindingViewDimensionDescriptor, 0x00000011) ENUM_ENTRY(DawnTextureInternalUsageDescriptor, 0x000003E8) ENUM_ENTRY(DawnEncoderInternalUsageDescriptor, 0x000003EB) ENUM_ENTRY(DawnInstanceDescriptor, 0x000003EC) @@ -451,6 +495,13 @@ ENUM(SType) ENUM_ENTRY(PipelineLayoutPixelLocalStorage, 0x000003F8) ENUM_ENTRY(BufferHostMappedPointer, 0x000003F9) ENUM_ENTRY(DawnExperimentalSubgroupLimits, 0x000003FA) + ENUM_ENTRY(AdapterPropertiesMemoryHeaps, 0x000003FB) + ENUM_ENTRY(AdapterPropertiesD3D, 0x000003FC) + ENUM_ENTRY(AdapterPropertiesVk, 0x000003FD) + ENUM_ENTRY(DawnComputePipelineFullSubgroups, 0x000003FE) + ENUM_ENTRY(DawnWireWGSLControl, 0x000003FF) + ENUM_ENTRY(DawnWGSLBlocklist, 0x00000400) + ENUM_ENTRY(DrmFormatCapabilities, 0x00000401) ENUM_ENTRY(SharedTextureMemoryVkImageDescriptor, 0x0000044C) ENUM_ENTRY(SharedTextureMemoryVkDedicatedAllocationDescriptor, 0x0000044D) ENUM_ENTRY(SharedTextureMemoryAHardwareBufferDescriptor, 0x0000044E) @@ -475,6 +526,7 @@ ENUM(SType) ENUM_ENTRY(SharedFenceDXGISharedHandleExportInfo, 0x000004BB) ENUM_ENTRY(SharedFenceMTLSharedEventDescriptor, 0x000004BC) ENUM_ENTRY(SharedFenceMTLSharedEventExportInfo, 0x000004BD) + ENUM_ENTRY(SharedBufferMemoryD3D12ResourceDescriptor, 0x000004BE) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(SamplerBindingType) @@ -494,14 +546,15 @@ ENUM(SharedFenceType) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(StencilOperation) - ENUM_ENTRY(Keep, 0x00000000) - ENUM_ENTRY(Zero, 0x00000001) - ENUM_ENTRY(Replace, 0x00000002) - ENUM_ENTRY(Invert, 0x00000003) - ENUM_ENTRY(IncrementClamp, 0x00000004) - ENUM_ENTRY(DecrementClamp, 0x00000005) - ENUM_ENTRY(IncrementWrap, 0x00000006) - ENUM_ENTRY(DecrementWrap, 0x00000007) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(Keep, 0x00000001) + ENUM_ENTRY(Zero, 0x00000002) + ENUM_ENTRY(Replace, 0x00000003) + ENUM_ENTRY(Invert, 0x00000004) + ENUM_ENTRY(IncrementClamp, 0x00000005) + ENUM_ENTRY(DecrementClamp, 0x00000006) + ENUM_ENTRY(IncrementWrap, 0x00000007) + ENUM_ENTRY(DecrementWrap, 0x00000008) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(StorageTextureAccess) @@ -518,17 +571,20 @@ ENUM(StoreOp) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(TextureAspect) - ENUM_ENTRY(All, 0x00000000) - ENUM_ENTRY(StencilOnly, 0x00000001) - ENUM_ENTRY(DepthOnly, 0x00000002) - ENUM_ENTRY(Plane0Only, 0x00000003) - ENUM_ENTRY(Plane1Only, 0x00000004) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(All, 0x00000001) + ENUM_ENTRY(StencilOnly, 0x00000002) + ENUM_ENTRY(DepthOnly, 0x00000003) + ENUM_ENTRY(Plane0Only, 0x00000004) + ENUM_ENTRY(Plane1Only, 0x00000005) + ENUM_ENTRY(Plane2Only, 0x00000006) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(TextureDimension) - ENUM_ENTRY(_1D, 0x00000000) - ENUM_ENTRY(_2D, 0x00000001) - ENUM_ENTRY(_3D, 0x00000002) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(_1D, 0x00000001) + ENUM_ENTRY(_2D, 0x00000002) + ENUM_ENTRY(_3D, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(TextureFormat) @@ -636,6 +692,7 @@ ENUM(TextureFormat) ENUM_ENTRY(RGBA16Snorm, 0x00000065) ENUM_ENTRY(R8BG8Biplanar420Unorm, 0x00000066) ENUM_ENTRY(R10X6BG10X6Biplanar420Unorm, 0x00000067) + ENUM_ENTRY(R8BG8A8Triplanar420Unorm, 0x00000068) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(TextureSampleType) @@ -693,9 +750,10 @@ ENUM(VertexFormat) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(VertexStepMode) - ENUM_ENTRY(Vertex, 0x00000000) - ENUM_ENTRY(Instance, 0x00000001) - ENUM_ENTRY(VertexBufferNotUsed, 0x00000002) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(VertexBufferNotUsed, 0x00000001) + ENUM_ENTRY(Vertex, 0x00000002) + ENUM_ENTRY(Instance, 0x00000003) ENUM_ENTRY(Force32, 0x7FFFFFFF) END ENUM(WaitStatus) @@ -730,6 +788,15 @@ ENUM(ColorWriteMask) ENUM_ENTRY(All, 0x0000000F) ENUM_ENTRY(Force32, 0x7FFFFFFF) END +ENUM(HeapProperty) + ENUM_ENTRY(Undefined, 0x00000000) + ENUM_ENTRY(DeviceLocal, 0x00000001) + ENUM_ENTRY(HostVisible, 0x00000002) + ENUM_ENTRY(HostCoherent, 0x00000004) + ENUM_ENTRY(HostUncached, 0x00000008) + ENUM_ENTRY(HostCached, 0x00000010) + ENUM_ENTRY(Force32, 0x7FFFFFFF) +END ENUM(MapMode) ENUM_ENTRY(None, 0x00000000) ENUM_ENTRY(Read, 0x00000001) @@ -764,6 +831,14 @@ STRUCT(ChainedStructOut) void setDefault(); END +STRUCT(AdapterPropertiesD3D) + void setDefault(); +END + +STRUCT(AdapterPropertiesVk) + void setDefault(); +END + STRUCT(BlendComponent) void setDefault(); END @@ -781,6 +856,10 @@ STRUCT(ComputePassTimestampWrites) void setDefault(); END +STRUCT(DawnWGSLBlocklist) + void setDefault(); +END + STRUCT(DawnAdapterPropertiesPowerPreference) void setDefault(); END @@ -793,6 +872,10 @@ STRUCT(DawnCacheDeviceDescriptor) void setDefault(); END +STRUCT(DawnComputePipelineFullSubgroups) + void setDefault(); +END + STRUCT(DawnEncoderInternalUsageDescriptor) void setDefault(); END @@ -821,10 +904,18 @@ STRUCT(DawnTogglesDescriptor) void setDefault(); END +STRUCT(DawnWireWGSLControl) + void setDefault(); +END + STRUCT(DepthStencilStateDepthWriteDefinedDawn) void setDefault(); END +STRUCT(DrmFormatProperties) + void setDefault(); +END + STRUCT(Extent2D) void setDefault(); END @@ -850,6 +941,10 @@ STRUCT(Limits) void setDefault(); END +STRUCT(MemoryHeapInfo) + void setDefault(); +END + STRUCT(Origin2D) void setDefault(); END @@ -923,23 +1018,23 @@ STRUCT(SharedFenceVkSemaphoreZirconHandleExportInfo) void setDefault(); END -STRUCT(SharedTextureMemoryAHardwareBufferDescriptor) +STRUCT(SharedTextureMemoryDXGISharedHandleDescriptor) void setDefault(); END -STRUCT(SharedTextureMemoryDmaBufDescriptor) +STRUCT(SharedTextureMemoryEGLImageDescriptor) void setDefault(); END -STRUCT(SharedTextureMemoryDXGISharedHandleDescriptor) +STRUCT(SharedTextureMemoryIOSurfaceDescriptor) void setDefault(); END -STRUCT(SharedTextureMemoryEGLImageDescriptor) +STRUCT(SharedTextureMemoryAHardwareBufferDescriptor) void setDefault(); END -STRUCT(SharedTextureMemoryIOSurfaceDescriptor) +STRUCT(SharedTextureMemoryDmaBufPlane) void setDefault(); END @@ -983,11 +1078,11 @@ STRUCT(SurfaceDescriptorFromWaylandSurface) void setDefault(); END -STRUCT(SurfaceDescriptorFromWindowsCoreWindow) +STRUCT(SurfaceDescriptorFromWindowsHWND) void setDefault(); END -STRUCT(SurfaceDescriptorFromWindowsHWND) +STRUCT(SurfaceDescriptorFromWindowsCoreWindow) void setDefault(); END @@ -999,14 +1094,28 @@ STRUCT(SurfaceDescriptorFromXlibWindow) void setDefault(); END +STRUCT(TextureBindingViewDimensionDescriptor) + void setDefault(); +END + STRUCT(VertexAttribute) void setDefault(); END +STRUCT(AdapterPropertiesMemoryHeaps) + void setDefault(); + void freeMembers(); +END + STRUCT(BlendState) void setDefault(); END +STRUCT(DrmFormatCapabilities) + void setDefault(); + void freeMembers(); +END + STRUCT(FutureWaitInfo) void setDefault(); END @@ -1015,6 +1124,10 @@ STRUCT(PipelineLayoutPixelLocalStorage) void setDefault(); END +STRUCT(SharedTextureMemoryDmaBufDescriptor) + void setDefault(); +END + STRUCT(SharedTextureMemoryVkImageDescriptor) void setDefault(); END @@ -1058,6 +1171,10 @@ DESCRIPTOR(CommandEncoderDescriptor) void setDefault(); END +DESCRIPTOR(CompilationInfoCallbackInfo) + void setDefault(); +END + DESCRIPTOR(CompilationMessage) void setDefault(); END @@ -1070,6 +1187,18 @@ DESCRIPTOR(CopyTextureForBrowserOptions) void setDefault(); END +DESCRIPTOR(CreateComputePipelineAsyncCallbackInfo) + void setDefault(); +END + +DESCRIPTOR(CreateRenderPipelineAsyncCallbackInfo) + void setDefault(); +END + +DESCRIPTOR(FormatCapabilities) + void setDefault(); +END + DESCRIPTOR(InstanceFeatures) void setDefault(); END @@ -1086,6 +1215,10 @@ DESCRIPTOR(PipelineLayoutStorageAttachment) void setDefault(); END +DESCRIPTOR(PopErrorScopeCallbackInfo) + void setDefault(); +END + DESCRIPTOR(PrimitiveState) void setDefault(); END @@ -1110,10 +1243,18 @@ DESCRIPTOR(RenderBundleEncoderDescriptor) void setDefault(); END +DESCRIPTOR(RequestAdapterCallbackInfo) + void setDefault(); +END + DESCRIPTOR(RequestAdapterOptions) void setDefault(); END +DESCRIPTOR(RequestDeviceCallbackInfo) + void setDefault(); +END + DESCRIPTOR(SamplerBindingLayout) void setDefault(); END @@ -1126,6 +1267,23 @@ DESCRIPTOR(ShaderModuleDescriptor) void setDefault(); END +DESCRIPTOR(SharedBufferMemoryBeginAccessDescriptor) + void setDefault(); +END + +DESCRIPTOR(SharedBufferMemoryDescriptor) + void setDefault(); +END + +DESCRIPTOR(SharedBufferMemoryEndAccessState) + void setDefault(); + void freeMembers(); +END + +DESCRIPTOR(SharedBufferMemoryProperties) + void setDefault(); +END + DESCRIPTOR(SharedFenceDescriptor) void setDefault(); END @@ -1293,6 +1451,7 @@ class RenderPassEncoder; class RenderPipeline; class Sampler; class ShaderModule; +class SharedBufferMemory; class SharedFence; class SharedTextureMemory; class Surface; @@ -1308,6 +1467,7 @@ using CreateRenderPipelineAsyncCallback = std::function; using ErrorCallback = std::function; using LoggingCallback = std::function; +using PopErrorScopeCallback = std::function; using QueueWorkDoneCallback = std::function; using RequestAdapterCallback = std::function; using RequestDeviceCallback = std::function; @@ -1320,11 +1480,13 @@ HANDLE(Adapter) Device createDevice(const DeviceDescriptor& descriptor); Device createDevice(); size_t enumerateFeatures(FeatureName * features); + Bool getFormatCapabilities(TextureFormat format, FormatCapabilities * capabilities); Instance getInstance(); Bool getLimits(SupportedLimits * limits); void getProperties(AdapterProperties * properties); Bool hasFeature(FeatureName feature); std::unique_ptr requestDevice(const DeviceDescriptor& descriptor, RequestDeviceCallback&& callback); + Future requestDeviceF(const DeviceDescriptor& options, RequestDeviceCallbackInfo callbackInfo); void reference(); void release(); Device requestDevice(const DeviceDescriptor& descriptor); @@ -1350,6 +1512,7 @@ HANDLE(Buffer) uint64_t getSize(); BufferUsageFlags getUsage(); std::unique_ptr mapAsync(MapModeFlags mode, size_t offset, size_t size, BufferMapCallback&& callback); + Future mapAsyncF(MapModeFlags mode, size_t offset, size_t size, BufferMapCallbackInfo callbackInfo); void setLabel(char const * label); void unmap(); void reference(); @@ -1417,6 +1580,7 @@ HANDLE(Device) CommandEncoder createCommandEncoder(); ComputePipeline createComputePipeline(const ComputePipelineDescriptor& descriptor); std::unique_ptr createComputePipelineAsync(const ComputePipelineDescriptor& descriptor, CreateComputePipelineAsyncCallback&& callback); + Future createComputePipelineAsyncF(const ComputePipelineDescriptor& descriptor, CreateComputePipelineAsyncCallbackInfo callbackInfo); Buffer createErrorBuffer(const BufferDescriptor& descriptor); ExternalTexture createErrorExternalTexture(); ShaderModule createErrorShaderModule(const ShaderModuleDescriptor& descriptor, char const * errorMessage); @@ -1427,6 +1591,7 @@ HANDLE(Device) RenderBundleEncoder createRenderBundleEncoder(const RenderBundleEncoderDescriptor& descriptor); RenderPipeline createRenderPipeline(const RenderPipelineDescriptor& descriptor); std::unique_ptr createRenderPipelineAsync(const RenderPipelineDescriptor& descriptor, CreateRenderPipelineAsyncCallback&& callback); + Future createRenderPipelineAsyncF(const RenderPipelineDescriptor& descriptor, CreateRenderPipelineAsyncCallbackInfo callbackInfo); Sampler createSampler(const SamplerDescriptor& descriptor); Sampler createSampler(); ShaderModule createShaderModule(const ShaderModuleDescriptor& descriptor); @@ -1440,10 +1605,11 @@ HANDLE(Device) Queue getQueue(); TextureUsageFlags getSupportedSurfaceUsage(Surface surface); Bool hasFeature(FeatureName feature); + SharedBufferMemory importSharedBufferMemory(const SharedBufferMemoryDescriptor& descriptor); SharedFence importSharedFence(const SharedFenceDescriptor& descriptor); SharedTextureMemory importSharedTextureMemory(const SharedTextureMemoryDescriptor& descriptor); void injectError(ErrorType type, char const * message); - std::unique_ptr popErrorScope(ErrorCallback&& callback); + Future popErrorScopeF(PopErrorScopeCallbackInfo callbackInfo); void pushErrorScope(ErrorFilter filter); std::unique_ptr setDeviceLostCallback(DeviceLostCallback&& callback); void setLabel(char const * label); @@ -1466,8 +1632,11 @@ END HANDLE(Instance) Surface createSurface(const SurfaceDescriptor& descriptor); + size_t enumerateWGSLLanguageFeatures(WGSLFeatureName * features); + Bool hasWGSLLanguageFeature(WGSLFeatureName feature); void processEvents(); std::unique_ptr requestAdapter(const RequestAdapterOptions& options, RequestAdapterCallback&& callback); + Future requestAdapterF(const RequestAdapterOptions& options, RequestAdapterCallbackInfo callbackInfo); WaitStatus waitAny(size_t futureCount, FutureWaitInfo * futures, uint64_t timeoutNS); void reference(); void release(); @@ -1577,6 +1746,19 @@ END HANDLE(ShaderModule) std::unique_ptr getCompilationInfo(CompilationInfoCallback&& callback); + Future getCompilationInfoF(CompilationInfoCallbackInfo callbackInfo); + void setLabel(char const * label); + void reference(); + void release(); +END + +HANDLE(SharedBufferMemory) + Bool beginAccess(Buffer buffer, const SharedBufferMemoryBeginAccessDescriptor& descriptor); + Buffer createBuffer(const BufferDescriptor& descriptor); + Buffer createBuffer(); + Bool endAccess(Buffer buffer, SharedBufferMemoryEndAccessState * descriptor); + void getProperties(SharedBufferMemoryProperties * properties); + Bool isDeviceLost(); void setLabel(char const * label); void reference(); void release(); @@ -1594,12 +1776,14 @@ HANDLE(SharedTextureMemory) Texture createTexture(); Bool endAccess(Texture texture, SharedTextureMemoryEndAccessState * descriptor); void getProperties(SharedTextureMemoryProperties * properties); + Bool isDeviceLost(); void setLabel(char const * label); void reference(); void release(); END HANDLE(Surface) + TextureFormat getPreferredFormat(Adapter adapter); void reference(); void release(); END @@ -1613,6 +1797,8 @@ HANDLE(SwapChain) END HANDLE(Texture) + TextureView createErrorView(const TextureViewDescriptor& descriptor); + TextureView createErrorView(); TextureView createView(const TextureViewDescriptor& descriptor); TextureView createView(); void destroy(); @@ -1667,6 +1853,20 @@ void AdapterProperties::freeMembers() { } +// Methods of AdapterPropertiesD3D +void AdapterPropertiesD3D::setDefault() { + ((ChainedStructOut*)&chain)->setDefault(); + chain.sType = SType::AdapterPropertiesD3D; +} + + +// Methods of AdapterPropertiesVk +void AdapterPropertiesVk::setDefault() { + ((ChainedStructOut*)&chain)->setDefault(); + chain.sType = SType::AdapterPropertiesVk; +} + + // Methods of BindGroupEntry void BindGroupEntry::setDefault() { offset = 0; @@ -1722,6 +1922,11 @@ void CommandEncoderDescriptor::setDefault() { } +// Methods of CompilationInfoCallbackInfo +void CompilationInfoCallbackInfo::setDefault() { +} + + // Methods of CompilationMessage void CompilationMessage::setDefault() { } @@ -1742,6 +1947,23 @@ void CopyTextureForBrowserOptions::setDefault() { } +// Methods of CreateComputePipelineAsyncCallbackInfo +void CreateComputePipelineAsyncCallbackInfo::setDefault() { +} + + +// Methods of CreateRenderPipelineAsyncCallbackInfo +void CreateRenderPipelineAsyncCallbackInfo::setDefault() { +} + + +// Methods of DawnWGSLBlocklist +void DawnWGSLBlocklist::setDefault() { + ((ChainedStruct*)&chain)->setDefault(); + chain.sType = SType::DawnWGSLBlocklist; +} + + // Methods of DawnAdapterPropertiesPowerPreference void DawnAdapterPropertiesPowerPreference::setDefault() { powerPreference = PowerPreference::Undefined; @@ -1764,6 +1986,13 @@ void DawnCacheDeviceDescriptor::setDefault() { } +// Methods of DawnComputePipelineFullSubgroups +void DawnComputePipelineFullSubgroups::setDefault() { + ((ChainedStruct*)&chain)->setDefault(); + chain.sType = SType::DawnComputePipelineFullSubgroups; +} + + // Methods of DawnEncoderInternalUsageDescriptor void DawnEncoderInternalUsageDescriptor::setDefault() { ((ChainedStruct*)&chain)->setDefault(); @@ -1813,6 +2042,13 @@ void DawnTogglesDescriptor::setDefault() { } +// Methods of DawnWireWGSLControl +void DawnWireWGSLControl::setDefault() { + ((ChainedStruct*)&chain)->setDefault(); + chain.sType = SType::DawnWireWGSLControl; +} + + // Methods of DepthStencilStateDepthWriteDefinedDawn void DepthStencilStateDepthWriteDefinedDawn::setDefault() { ((ChainedStruct*)&chain)->setDefault(); @@ -1820,6 +2056,11 @@ void DepthStencilStateDepthWriteDefinedDawn::setDefault() { } +// Methods of DrmFormatProperties +void DrmFormatProperties::setDefault() { +} + + // Methods of Extent2D void Extent2D::setDefault() { } @@ -1846,6 +2087,11 @@ void ExternalTextureBindingLayout::setDefault() { } +// Methods of FormatCapabilities +void FormatCapabilities::setDefault() { +} + + // Methods of Future void Future::setDefault() { } @@ -1892,6 +2138,11 @@ void Limits::setDefault() { } +// Methods of MemoryHeapInfo +void MemoryHeapInfo::setDefault() { +} + + // Methods of MultisampleState void MultisampleState::setDefault() { count = 1; @@ -1924,6 +2175,11 @@ void PipelineLayoutStorageAttachment::setDefault() { } +// Methods of PopErrorScopeCallbackInfo +void PopErrorScopeCallbackInfo::setDefault() { +} + + // Methods of PrimitiveDepthClipControl void PrimitiveDepthClipControl::setDefault() { unclippedDepth = false; @@ -1994,6 +2250,11 @@ void RenderPassTimestampWrites::setDefault() { } +// Methods of RequestAdapterCallbackInfo +void RequestAdapterCallbackInfo::setDefault() { +} + + // Methods of RequestAdapterOptions void RequestAdapterOptions::setDefault() { powerPreference = PowerPreference::Undefined; @@ -2002,6 +2263,11 @@ void RequestAdapterOptions::setDefault() { } +// Methods of RequestDeviceCallbackInfo +void RequestDeviceCallbackInfo::setDefault() { +} + + // Methods of SamplerBindingLayout void SamplerBindingLayout::setDefault() { type = SamplerBindingType::Filtering; @@ -2022,11 +2288,6 @@ void SamplerDescriptor::setDefault() { } -// Methods of ShaderModuleDescriptor -void ShaderModuleDescriptor::setDefault() { -} - - // Methods of ShaderModuleSPIRVDescriptor void ShaderModuleSPIRVDescriptor::setDefault() { ((ChainedStruct*)&chain)->setDefault(); @@ -2041,8 +2302,31 @@ void ShaderModuleWGSLDescriptor::setDefault() { } -// Methods of SharedFenceDescriptor -void SharedFenceDescriptor::setDefault() { +// Methods of ShaderModuleDescriptor +void ShaderModuleDescriptor::setDefault() { +} + + +// Methods of SharedBufferMemoryBeginAccessDescriptor +void SharedBufferMemoryBeginAccessDescriptor::setDefault() { +} + + +// Methods of SharedBufferMemoryDescriptor +void SharedBufferMemoryDescriptor::setDefault() { +} + + +// Methods of SharedBufferMemoryEndAccessState +void SharedBufferMemoryEndAccessState::setDefault() { +} +void SharedBufferMemoryEndAccessState::freeMembers() { + return wgpuSharedBufferMemoryEndAccessStateFreeMembers(*this); +} + + +// Methods of SharedBufferMemoryProperties +void SharedBufferMemoryProperties::setDefault() { } @@ -2060,12 +2344,6 @@ void SharedFenceDXGISharedHandleExportInfo::setDefault() { } -// Methods of SharedFenceExportInfo -void SharedFenceExportInfo::setDefault() { - type = SharedFenceType::Undefined; -} - - // Methods of SharedFenceMTLSharedEventDescriptor void SharedFenceMTLSharedEventDescriptor::setDefault() { ((ChainedStruct*)&chain)->setDefault(); @@ -2080,6 +2358,17 @@ void SharedFenceMTLSharedEventExportInfo::setDefault() { } +// Methods of SharedFenceDescriptor +void SharedFenceDescriptor::setDefault() { +} + + +// Methods of SharedFenceExportInfo +void SharedFenceExportInfo::setDefault() { + type = SharedFenceType::Undefined; +} + + // Methods of SharedFenceVkSemaphoreOpaqueFDDescriptor void SharedFenceVkSemaphoreOpaqueFDDescriptor::setDefault() { ((ChainedStruct*)&chain)->setDefault(); @@ -2122,41 +2411,46 @@ void SharedFenceVkSemaphoreZirconHandleExportInfo::setDefault() { } -// Methods of SharedTextureMemoryAHardwareBufferDescriptor -void SharedTextureMemoryAHardwareBufferDescriptor::setDefault() { +// Methods of SharedTextureMemoryDXGISharedHandleDescriptor +void SharedTextureMemoryDXGISharedHandleDescriptor::setDefault() { ((ChainedStruct*)&chain)->setDefault(); - chain.sType = SType::SharedTextureMemoryAHardwareBufferDescriptor; + chain.sType = SType::SharedTextureMemoryDXGISharedHandleDescriptor; } -// Methods of SharedTextureMemoryBeginAccessDescriptor -void SharedTextureMemoryBeginAccessDescriptor::setDefault() { +// Methods of SharedTextureMemoryEGLImageDescriptor +void SharedTextureMemoryEGLImageDescriptor::setDefault() { + ((ChainedStruct*)&chain)->setDefault(); + chain.sType = SType::SharedTextureMemoryEGLImageDescriptor; } -// Methods of SharedTextureMemoryDescriptor -void SharedTextureMemoryDescriptor::setDefault() { +// Methods of SharedTextureMemoryIOSurfaceDescriptor +void SharedTextureMemoryIOSurfaceDescriptor::setDefault() { + ((ChainedStruct*)&chain)->setDefault(); + chain.sType = SType::SharedTextureMemoryIOSurfaceDescriptor; } -// Methods of SharedTextureMemoryDmaBufDescriptor -void SharedTextureMemoryDmaBufDescriptor::setDefault() { +// Methods of SharedTextureMemoryAHardwareBufferDescriptor +void SharedTextureMemoryAHardwareBufferDescriptor::setDefault() { ((ChainedStruct*)&chain)->setDefault(); - chain.sType = SType::SharedTextureMemoryDmaBufDescriptor; + chain.sType = SType::SharedTextureMemoryAHardwareBufferDescriptor; } -// Methods of SharedTextureMemoryDXGISharedHandleDescriptor -void SharedTextureMemoryDXGISharedHandleDescriptor::setDefault() { - ((ChainedStruct*)&chain)->setDefault(); - chain.sType = SType::SharedTextureMemoryDXGISharedHandleDescriptor; +// Methods of SharedTextureMemoryBeginAccessDescriptor +void SharedTextureMemoryBeginAccessDescriptor::setDefault() { } -// Methods of SharedTextureMemoryEGLImageDescriptor -void SharedTextureMemoryEGLImageDescriptor::setDefault() { - ((ChainedStruct*)&chain)->setDefault(); - chain.sType = SType::SharedTextureMemoryEGLImageDescriptor; +// Methods of SharedTextureMemoryDescriptor +void SharedTextureMemoryDescriptor::setDefault() { +} + + +// Methods of SharedTextureMemoryDmaBufPlane +void SharedTextureMemoryDmaBufPlane::setDefault() { } @@ -2168,13 +2462,6 @@ void SharedTextureMemoryEndAccessState::freeMembers() { } -// Methods of SharedTextureMemoryIOSurfaceDescriptor -void SharedTextureMemoryIOSurfaceDescriptor::setDefault() { - ((ChainedStruct*)&chain)->setDefault(); - chain.sType = SType::SharedTextureMemoryIOSurfaceDescriptor; -} - - // Methods of SharedTextureMemoryOpaqueFDDescriptor void SharedTextureMemoryOpaqueFDDescriptor::setDefault() { ((ChainedStruct*)&chain)->setDefault(); @@ -2260,17 +2547,17 @@ void SurfaceDescriptorFromWaylandSurface::setDefault() { } -// Methods of SurfaceDescriptorFromWindowsCoreWindow -void SurfaceDescriptorFromWindowsCoreWindow::setDefault() { +// Methods of SurfaceDescriptorFromWindowsHWND +void SurfaceDescriptorFromWindowsHWND::setDefault() { ((ChainedStruct*)&chain)->setDefault(); - chain.sType = SType::SurfaceDescriptorFromWindowsCoreWindow; + chain.sType = SType::SurfaceDescriptorFromWindowsHWND; } -// Methods of SurfaceDescriptorFromWindowsHWND -void SurfaceDescriptorFromWindowsHWND::setDefault() { +// Methods of SurfaceDescriptorFromWindowsCoreWindow +void SurfaceDescriptorFromWindowsCoreWindow::setDefault() { ((ChainedStruct*)&chain)->setDefault(); - chain.sType = SType::SurfaceDescriptorFromWindowsHWND; + chain.sType = SType::SurfaceDescriptorFromWindowsCoreWindow; } @@ -2302,6 +2589,14 @@ void TextureBindingLayout::setDefault() { } +// Methods of TextureBindingViewDimensionDescriptor +void TextureBindingViewDimensionDescriptor::setDefault() { + textureBindingViewDimension = TextureViewDimension::Undefined; + ((ChainedStruct*)&chain)->setDefault(); + chain.sType = SType::TextureBindingViewDimensionDescriptor; +} + + // Methods of TextureDataLayout void TextureDataLayout::setDefault() { } @@ -2323,6 +2618,16 @@ void VertexAttribute::setDefault() { } +// Methods of AdapterPropertiesMemoryHeaps +void AdapterPropertiesMemoryHeaps::setDefault() { + ((ChainedStructOut*)&chain)->setDefault(); + chain.sType = SType::AdapterPropertiesMemoryHeaps; +} +void AdapterPropertiesMemoryHeaps::freeMembers() { + return wgpuAdapterPropertiesMemoryHeapsFreeMembers(*this); +} + + // Methods of BindGroupDescriptor void BindGroupDescriptor::setDefault() { } @@ -2372,6 +2677,16 @@ void DepthStencilState::setDefault() { } +// Methods of DrmFormatCapabilities +void DrmFormatCapabilities::setDefault() { + ((ChainedStructOut*)&chain)->setDefault(); + chain.sType = SType::DrmFormatCapabilities; +} +void DrmFormatCapabilities::freeMembers() { + return wgpuDrmFormatCapabilitiesFreeMembers(*this); +} + + // Methods of ExternalTextureDescriptor void ExternalTextureDescriptor::setDefault() { ((Origin2D*)&visibleOrigin)->setDefault(); @@ -2446,6 +2761,14 @@ void RequiredLimits::setDefault() { } +// Methods of SharedTextureMemoryDmaBufDescriptor +void SharedTextureMemoryDmaBufDescriptor::setDefault() { + ((ChainedStruct*)&chain)->setDefault(); + ((Extent3D*)&size)->setDefault(); + chain.sType = SType::SharedTextureMemoryDmaBufDescriptor; +} + + // Methods of SharedTextureMemoryProperties void SharedTextureMemoryProperties::setDefault() { format = TextureFormat::Undefined; @@ -2546,6 +2869,9 @@ Device Adapter::createDevice() { size_t Adapter::enumerateFeatures(FeatureName * features) { return wgpuAdapterEnumerateFeatures(m_raw, reinterpret_cast(features)); } +Bool Adapter::getFormatCapabilities(TextureFormat format, FormatCapabilities * capabilities) { + return wgpuAdapterGetFormatCapabilities(m_raw, static_cast(format), capabilities); +} Instance Adapter::getInstance() { return wgpuAdapterGetInstance(m_raw); } @@ -2567,6 +2893,9 @@ std::unique_ptr Adapter::requestDevice(const DeviceDescri wgpuAdapterRequestDevice(m_raw, &descriptor, cCallback, reinterpret_cast(handle.get())); return handle; } +Future Adapter::requestDeviceF(const DeviceDescriptor& options, RequestDeviceCallbackInfo callbackInfo) { + return wgpuAdapterRequestDeviceF(m_raw, &options, callbackInfo); +} void Adapter::reference() { return wgpuAdapterReference(m_raw); } @@ -2627,6 +2956,9 @@ std::unique_ptr Buffer::mapAsync(MapModeFlags mode, size_t of wgpuBufferMapAsync(m_raw, mode, offset, size, cCallback, reinterpret_cast(handle.get())); return handle; } +Future Buffer::mapAsyncF(MapModeFlags mode, size_t offset, size_t size, BufferMapCallbackInfo callbackInfo) { + return wgpuBufferMapAsyncF(m_raw, mode, offset, size, callbackInfo); +} void Buffer::setLabel(char const * label) { return wgpuBufferSetLabel(m_raw, label); } @@ -2804,6 +3136,9 @@ std::unique_ptr Device::createComputePipelin wgpuDeviceCreateComputePipelineAsync(m_raw, &descriptor, cCallback, reinterpret_cast(handle.get())); return handle; } +Future Device::createComputePipelineAsyncF(const ComputePipelineDescriptor& descriptor, CreateComputePipelineAsyncCallbackInfo callbackInfo) { + return wgpuDeviceCreateComputePipelineAsyncF(m_raw, &descriptor, callbackInfo); +} Buffer Device::createErrorBuffer(const BufferDescriptor& descriptor) { return wgpuDeviceCreateErrorBuffer(m_raw, &descriptor); } @@ -2840,6 +3175,9 @@ std::unique_ptr Device::createRenderPipelineA wgpuDeviceCreateRenderPipelineAsync(m_raw, &descriptor, cCallback, reinterpret_cast(handle.get())); return handle; } +Future Device::createRenderPipelineAsyncF(const RenderPipelineDescriptor& descriptor, CreateRenderPipelineAsyncCallbackInfo callbackInfo) { + return wgpuDeviceCreateRenderPipelineAsyncF(m_raw, &descriptor, callbackInfo); +} Sampler Device::createSampler(const SamplerDescriptor& descriptor) { return wgpuDeviceCreateSampler(m_raw, &descriptor); } @@ -2879,6 +3217,9 @@ TextureUsageFlags Device::getSupportedSurfaceUsage(Surface surface) { Bool Device::hasFeature(FeatureName feature) { return wgpuDeviceHasFeature(m_raw, static_cast(feature)); } +SharedBufferMemory Device::importSharedBufferMemory(const SharedBufferMemoryDescriptor& descriptor) { + return wgpuDeviceImportSharedBufferMemory(m_raw, &descriptor); +} SharedFence Device::importSharedFence(const SharedFenceDescriptor& descriptor) { return wgpuDeviceImportSharedFence(m_raw, &descriptor); } @@ -2888,14 +3229,8 @@ SharedTextureMemory Device::importSharedTextureMemory(const SharedTextureMemoryD void Device::injectError(ErrorType type, char const * message) { return wgpuDeviceInjectError(m_raw, static_cast(type), message); } -std::unique_ptr Device::popErrorScope(ErrorCallback&& callback) { - auto handle = std::make_unique(callback); - static auto cCallback = [](WGPUErrorType type, char const * message, void * userdata) -> void { - ErrorCallback& callback = *reinterpret_cast(userdata); - callback(static_cast(type), message); - }; - wgpuDevicePopErrorScope(m_raw, cCallback, reinterpret_cast(handle.get())); - return handle; +Future Device::popErrorScopeF(PopErrorScopeCallbackInfo callbackInfo) { + return wgpuDevicePopErrorScopeF(m_raw, callbackInfo); } void Device::pushErrorScope(ErrorFilter filter) { return wgpuDevicePushErrorScope(m_raw, static_cast(filter)); @@ -2969,6 +3304,12 @@ void ExternalTexture::release() { Surface Instance::createSurface(const SurfaceDescriptor& descriptor) { return wgpuInstanceCreateSurface(m_raw, &descriptor); } +size_t Instance::enumerateWGSLLanguageFeatures(WGSLFeatureName * features) { + return wgpuInstanceEnumerateWGSLLanguageFeatures(m_raw, reinterpret_cast(features)); +} +Bool Instance::hasWGSLLanguageFeature(WGSLFeatureName feature) { + return wgpuInstanceHasWGSLLanguageFeature(m_raw, static_cast(feature)); +} void Instance::processEvents() { return wgpuInstanceProcessEvents(m_raw); } @@ -2981,6 +3322,9 @@ std::unique_ptr Instance::requestAdapter(const RequestAd wgpuInstanceRequestAdapter(m_raw, &options, cCallback, reinterpret_cast(handle.get())); return handle; } +Future Instance::requestAdapterF(const RequestAdapterOptions& options, RequestAdapterCallbackInfo callbackInfo) { + return wgpuInstanceRequestAdapterF(m_raw, &options, callbackInfo); +} WaitStatus Instance::waitAny(size_t futureCount, FutureWaitInfo * futures, uint64_t timeoutNS) { return static_cast(wgpuInstanceWaitAny(m_raw, futureCount, futures, timeoutNS)); } @@ -3263,6 +3607,9 @@ std::unique_ptr ShaderModule::getCompilationInfo(Compil wgpuShaderModuleGetCompilationInfo(m_raw, cCallback, reinterpret_cast(handle.get())); return handle; } +Future ShaderModule::getCompilationInfoF(CompilationInfoCallbackInfo callbackInfo) { + return wgpuShaderModuleGetCompilationInfoF(m_raw, callbackInfo); +} void ShaderModule::setLabel(char const * label) { return wgpuShaderModuleSetLabel(m_raw, label); } @@ -3274,6 +3621,36 @@ void ShaderModule::release() { } +// Methods of SharedBufferMemory +Bool SharedBufferMemory::beginAccess(Buffer buffer, const SharedBufferMemoryBeginAccessDescriptor& descriptor) { + return wgpuSharedBufferMemoryBeginAccess(m_raw, buffer, &descriptor); +} +Buffer SharedBufferMemory::createBuffer(const BufferDescriptor& descriptor) { + return wgpuSharedBufferMemoryCreateBuffer(m_raw, &descriptor); +} +Buffer SharedBufferMemory::createBuffer() { + return wgpuSharedBufferMemoryCreateBuffer(m_raw, nullptr); +} +Bool SharedBufferMemory::endAccess(Buffer buffer, SharedBufferMemoryEndAccessState * descriptor) { + return wgpuSharedBufferMemoryEndAccess(m_raw, buffer, descriptor); +} +void SharedBufferMemory::getProperties(SharedBufferMemoryProperties * properties) { + return wgpuSharedBufferMemoryGetProperties(m_raw, properties); +} +Bool SharedBufferMemory::isDeviceLost() { + return wgpuSharedBufferMemoryIsDeviceLost(m_raw); +} +void SharedBufferMemory::setLabel(char const * label) { + return wgpuSharedBufferMemorySetLabel(m_raw, label); +} +void SharedBufferMemory::reference() { + return wgpuSharedBufferMemoryReference(m_raw); +} +void SharedBufferMemory::release() { + return wgpuSharedBufferMemoryRelease(m_raw); +} + + // Methods of SharedFence void SharedFence::exportInfo(SharedFenceExportInfo * info) { return wgpuSharedFenceExportInfo(m_raw, info); @@ -3302,6 +3679,9 @@ Bool SharedTextureMemory::endAccess(Texture texture, SharedTextureMemoryEndAcces void SharedTextureMemory::getProperties(SharedTextureMemoryProperties * properties) { return wgpuSharedTextureMemoryGetProperties(m_raw, properties); } +Bool SharedTextureMemory::isDeviceLost() { + return wgpuSharedTextureMemoryIsDeviceLost(m_raw); +} void SharedTextureMemory::setLabel(char const * label) { return wgpuSharedTextureMemorySetLabel(m_raw, label); } @@ -3314,6 +3694,9 @@ void SharedTextureMemory::release() { // Methods of Surface +TextureFormat Surface::getPreferredFormat(Adapter adapter) { + return static_cast(wgpuSurfaceGetPreferredFormat(m_raw, adapter)); +} void Surface::reference() { return wgpuSurfaceReference(m_raw); } @@ -3341,6 +3724,12 @@ void SwapChain::release() { // Methods of Texture +TextureView Texture::createErrorView(const TextureViewDescriptor& descriptor) { + return wgpuTextureCreateErrorView(m_raw, &descriptor); +} +TextureView Texture::createErrorView() { + return wgpuTextureCreateErrorView(m_raw, nullptr); +} TextureView Texture::createView(const TextureViewDescriptor& descriptor) { return wgpuTextureCreateView(m_raw, &descriptor); } diff --git a/launch/basestation.launch b/launch/basestation.launch index fc32e47fa..b5039bcbe 100644 --- a/launch/basestation.launch +++ b/launch/basestation.launch @@ -11,6 +11,7 @@ + diff --git a/launch/esw_base.launch b/launch/esw_base.launch index c5fb90cb5..e2ccf7d2d 100644 --- a/launch/esw_base.launch +++ b/launch/esw_base.launch @@ -2,34 +2,52 @@ - + + --> + + + + - - - - + + + - - + + - - + + - @@ -56,4 +74,4 @@ output="screen" /> - \ No newline at end of file + diff --git a/launch/esw_science.launch b/launch/esw_science.launch index 587d4add4..07e1dbd37 100644 --- a/launch/esw_science.launch +++ b/launch/esw_science.launch @@ -2,13 +2,11 @@ - - - + + - - + \ No newline at end of file diff --git a/msg/MotorsAdjust.msg b/msg/MotorsAdjust.msg new file mode 100644 index 000000000..93ddff782 --- /dev/null +++ b/msg/MotorsAdjust.msg @@ -0,0 +1,2 @@ +string[] names # names of joints +float32[] values # position should be in radians for the joints \ No newline at end of file diff --git a/msg/Spectral.msg b/msg/Spectral.msg index e03372eb4..4c0376ddb 100644 --- a/msg/Spectral.msg +++ b/msg/Spectral.msg @@ -1,3 +1,3 @@ uint8 site -float64[6] data +float32[6] data bool error \ No newline at end of file diff --git a/msg/SpectralGroup.msg b/msg/SpectralGroup.msg deleted file mode 100644 index 015dc773a..000000000 --- a/msg/SpectralGroup.msg +++ /dev/null @@ -1 +0,0 @@ -Spectral[3] spectrals \ No newline at end of file diff --git a/pkg/libdawn-dev.deb b/pkg/libdawn-dev.deb index 950699c32..98a82d987 100644 --- a/pkg/libdawn-dev.deb +++ b/pkg/libdawn-dev.deb @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:252984a13ad2dfa510c4414720044fc1f9148d27f27796fbdcbcbc37276bbe7e -size 5208066 +oid sha256:a71d028745d79b179b6f1fab01bb87bccef31326c7656e3298ca6ba163ebb5f6 +size 4385188 diff --git a/pyproject.toml b/pyproject.toml index bc40a70bd..beb9da872 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -21,7 +21,7 @@ dependencies = [ "pyarrow==15.0.0", "shapely==2.0.1", "pyserial==3.5", - "moteus==0.3.59", + "moteus==0.3.67", "pymap3d==3.0.1", "aenum==3.1.15", "daphne==4.0.0", diff --git a/science-spectral.zip b/science-spectral.zip new file mode 100644 index 000000000..6576025c2 Binary files /dev/null and b/science-spectral.zip differ diff --git a/scripts/moteusConfigManage.py b/scripts/moteusConfigManage.py new file mode 100755 index 000000000..1886ec1f9 --- /dev/null +++ b/scripts/moteusConfigManage.py @@ -0,0 +1,98 @@ +#!/usr/bin/env python3 +# \/\/\/\/ Help displayed below: \/\/\/\/ +help = """ +moteusConfigConvert: a script to help with saving and retrieving past moteus configs + +How to use: + +To save a config: + ./scripts/moteusConfigConvert save + +To list configs saved: + ./scripts/moteusConfigConvert list + +To flash a saved config onto the moteus: + ./scripts/moteusConfigConvert flash + +Then, follow the provided instructions. + +To retrieve a saved config: + +""" +import sys +import shutil +import os +import subprocess +from pathlib import Path + +MOTEUS_SAVE_DIR = str(Path.cwd()) + "/config/moteus/" # Need to change this for other laptops. + + +def list_cfgs(): + files = os.listdir(MOTEUS_SAVE_DIR) + print("Saved configs:\n\t") + print(*files, sep="\n\t") + + +def main(): + command: str + if len(sys.argv) >= 2: + command = sys.argv[1] + else: + command = input("Please enter a command {save, flash, list}: ") + + if command == "save": + saveFName = input("Please enter name for saved config: ") + if not saveFName.endswith("cfg"): + saveFName += ".cfg" + id = int(input("Please enter ID of moteus: ")) + + print("Saving config - this may ~30 seconds") + result = subprocess.run(["moteus_tool", "-t", str(id), "--dump-config"], capture_output=True) + if result.returncode != 0: + print( + "Moteus_tool returned an error trying to load config from moteus. Check moteus is correctly connected and that you chose the correct ID" + ) + print("Moteus_tool stdout: ", result.stdout.decode()) + print("Moteus_tool stderr: ", result.stderr.decode()) + return + + saveFile = open(MOTEUS_SAVE_DIR + saveFName, "w") + saveFile.write(result.stdout.decode()) + saveFile.close() + + print(f"Saved config {saveFName}") + + elif command == "list": + list_cfgs() + + elif command == "flash": + list_cfgs() + storedConfigName = input("Please enter name for config to flash: ") + id = int(input("Please enter ID of moteus: ")) + + files = os.listdir(MOTEUS_SAVE_DIR) + if storedConfigName not in files: + print("Error: given config name not in saved configs") + return + print("Flashing config - this may ~30 seconds") + result = subprocess.run( + ["moteus_tool", "-t", str(id), "--restore-config", MOTEUS_SAVE_DIR + storedConfigName], capture_output=True + ) + if result.returncode != 0: + print( + "Moteus_tool returned an error trying to save config to moteus. Check moteus is correctly connected and that you chose the correct ID" + ) + print("Moteus_tool stdout: ", result.stdout.decode()) + print("Moteus_tool stderr: ", result.stderr.decode()) + return + + print("Wrote config to moteus") + + else: + print("Unknown command entered - \/please see usage\/") + print(help) + + +if __name__ == "__main__": + main() diff --git a/scripts/moteusConfigConvert.py b/scripts/moteus_config_tool.py similarity index 98% rename from scripts/moteusConfigConvert.py rename to scripts/moteus_config_tool.py index 6503829ce..e33a1e056 100644 --- a/scripts/moteusConfigConvert.py +++ b/scripts/moteus_config_tool.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + """ Script for converting moteus config into a writable format. Takes in file generated from: diff --git a/scripts/plot_bdcmc_debug_messages.py b/scripts/plot_bdcmc_debug_messages.py index 72937d3c2..d8cfaffdd 100644 --- a/scripts/plot_bdcmc_debug_messages.py +++ b/scripts/plot_bdcmc_debug_messages.py @@ -9,6 +9,8 @@ import pyqtgraph as pg from pyqtgraph.Qt import QtCore +from math import pi + if __name__ == "__main__": app = pg.mkQApp() @@ -24,12 +26,12 @@ # curve3 = plot.plot(pen='r') plot.enableAutoRange("xy", True) - plot.setYRange(0, 1 << 14) + plot.setYRange(-pi, pi) xs = np.zeros(40) ys = np.zeros((40, 4)) - with can.interface.Bus(channel="vcan0", interface="socketcan", fd=True) as bus: + with can.interface.Bus(channel="can1", interface="socketcan", fd=True) as bus: def update(): message = bus.recv() diff --git a/src/esw/arm_hw_bridge/main.cpp b/src/esw/arm_hw_bridge/main.cpp index 7a3762427..28480cc13 100644 --- a/src/esw/arm_hw_bridge/main.cpp +++ b/src/esw/arm_hw_bridge/main.cpp @@ -13,7 +13,6 @@ auto armLaserCallback(std_srvs::SetBool::Request& req, std_srvs::SetBool::Respon } auto main(int argc, char** argv) -> int { - // Initialize the ROS node ros::init(argc, argv, "arm_hw_bridge"); ros::NodeHandle nh; @@ -23,7 +22,6 @@ auto main(int argc, char** argv) -> int { ros::ServiceServer armLaserService = nh.advertiseService("enable_arm_laser", armLaserCallback); - // Enter the ROS event loop ros::spin(); return EXIT_SUCCESS; diff --git a/src/esw/arm_position_test_bridge/arm_position.cpp b/src/esw/arm_position_test_bridge/arm_position.cpp index 32dc61d23..8229c70b5 100644 --- a/src/esw/arm_position_test_bridge/arm_position.cpp +++ b/src/esw/arm_position_test_bridge/arm_position.cpp @@ -2,135 +2,73 @@ #include "ros/ros.h" #include "std_srvs/SetBool.h" #include -#include -#include #include #include #include void sleep(int ms); -void set_arm_position(ros::Publisher& publisher, std::vector positions, int delay); +void set_arm_position(ros::Publisher& publisher, float position); -std::vector position_data; +float position_data[7] = {0, 0, 0, 0, 0, 0, 0}; -auto arm_position_callback(sensor_msgs::JointState::ConstPtr const& msg) { - ROS_INFO(";)"); +auto arm_position_callback(Position::ConstPtr const& msg) { position_data = msg->position; - ROS_INFO("hey"); } -void reset_pos(ros::Publisher armPublisher, int delay) { - set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}, delay); -} - -void de_roll(float position, ros::Publisher armPublisher, int delay = 5000) { - set_arm_position(armPublisher, {0, 0, 0, 0, 0, position, 0}, delay); - ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); - reset_pos(armPublisher, delay); -} - -void de_pitch(float position, ros::Publisher armPublisher, int delay = 5000) { - set_arm_position(armPublisher, {0, 0, 0, position, 0, 0, 0}, delay); - ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); - reset_pos(armPublisher, delay); -} - -auto main(int argc, char** argv) -> int { - // Delay between operations - int delay = 5000; - position_data.resize(7); - +int main(int argc, char** argv) { ros::init(argc, argv, "arm_position_test_bridge"); ros::NodeHandle nh; ros::Rate rate(10); - ros::Publisher armPublisher = nh.advertise("arm_position_cmd", 1); - ros::Subscriber armSubscriber = nh.subscribe("arm_joint_data", 10, arm_position_callback); - while (ros::ok()) { /* Arm Position Test */ - ROS_INFO("****BEGIN BASIC AUTON ARM POSITION TEST****"); - - - // ROS_INFO("MOVE A"); - - // set_arm_position(armPublisher, {0.4, 0, 0, 0, 0, 0, 0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - //reset_pos(armPublisher, delay); - - // Test forwards limit switch - //set_arm_position(armPublisher, {1, 0, 0, 0, 0, 0, 0}, delay); - //ROS_INFO("Joint_A: %f", position_data[0]); - //reset_pos(armPublisher, delay); - - // Test backwards limit switch - //set_arm_position(armPublisher, {-0.4, 0, 0, 0, 0, 0, 0}, delay); - //ROS_INFO("Joint_A: %f", position_data[0]); - //reset_pos(armPublisher, delay); - - - // ROS_INFO("MOVE B"); - // set_arm_position(armPublisher, {0, -0.70, 0, 0, 0, 0, 0}, delay); - // ROS_INFO("Joint_B: %f", position_data[1]); - // reset_pos(armPublisher, delay); + ROS_INFO("****BEGIN AUTON ARM POSITION TEST****"); + ros::Publisher armPublisher = nh.advertise("arm_position_cmd", 1); + ros::Subscriber armSubscriber = nh.subscribe("arm_joint_data", 10, arm_position_callback); + + ROS_INFO("MOVE A"); + set_arm_position(armPublisher, {0.4, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_A: %f", position_data[0]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_A: %f", position_data[0]); + sleep(5000); + + ROS_INFO("MOVE B"); + set_arm_position(armPublisher, {0, -0.78, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_B: %f", position_data[1]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_B: %f", position_data[1]); + sleep(5000); ROS_INFO("MOVE C"); - set_arm_position(armPublisher, {0, 0, 2, 0, 0, 0, 0}, delay); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); ROS_INFO("Joint_C: %f", position_data[2]); - reset_pos(armPublisher, delay); - - // set_arm_position(armPublisher, {0, 0, 1.7, 0, 0, 0, 0}, delay); - // ROS_INFO("Joint_C: %f", position_data[2]); - // reset_pos(armPublisher, delay); - - // ROS_INFO("MOVE DE PITCH"); - // float test_de_pitch_positions[4] = {2.35, -2.35, 1.17, -1.17}; - // for(float value : test_de_pitch_positions) { - // de_pitch(value, armPublisher); - // } - - // ROS_INFO("MOVE DE ROLL"); - // float test_de_roll_positions[4] = {6.28, -6.28, 3.14, -3.14}; - // for(float value : test_de_roll_positions){ - // de_roll(value, armPublisher); - // } - ROS_INFO("****END BASIC ARM POSITION TEST****"); - // ROS_INFO("****BEGIN COMPLEX AUTON ARM POSITION TEST****"); - - // ROS_INFO("BOTH DE"); - // for(int i = 0; i < 4; i++){ - // set_arm_position(armPublisher, {0,0,0,0,test_de_pitch_positions[i],test_de_roll_positions[i],0}, delay); - // ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); - // ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); - // reset_pos(armPublisher, delay); - // } - - // // Joint A: [0.0, 1.0] - // // Joint B: [-0.78540, 0.0] - // // Joint C: [-2.094, 1.745] 220 degrees of motion - // // Joint DE-Pitch: [-2.268, 2.268] - // // Joint DE-Roll: [-inf,inf] - // ROS_INFO("A,B,C"); - // //min position - // set_arm_position(armPublisher, {0,-0.78,-2.0,0,0,0,0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - // ROS_INFO("Joint_B: %f", position_data[1]); - // ROS_INFO("Joint_C: %f", position_data[2]); - // reset_pos(armPublisher, delay); - - // // max position - // set_arm_position(armPublisher, {0.9,0.0,1.7,0,0,0,0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - // ROS_INFO("Joint_B: %f", position_data[1]); - // ROS_INFO("Joint_C: %f", position_data[2]); - // reset_pos(armPublisher, delay); - - // set_arm_position(armPublisher, {0.3,-0.32,-1.2,0,0,0,0}, delay); - // ROS_INFO("Joint_A: %f", position_data[0]); - // ROS_INFO("Joint_B: %f", position_data[1]); - // ROS_INFO("Joint_C: %f", position_data[2]); - // ROS_INFO("****END COMPLEX AUTON ARM POSITION TEST****"); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_C: %f", position_data[2]); + sleep(5000); + + ROS_INFO("MOVE DE PITCH"); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_PITCH: %f", position_data[3]); + sleep(5000); + + ROS_INFO("MOVE DE ROLL"); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); + sleep(5000); + set_arm_position(armPublisher, {0, 0, 0, 0, 0, 0, 0}); + ROS_INFO("Joint_DE_ROLL: %f", position_data[4]); + + ROS_INFO("****END ARM POSITION TEST****"); + + nh.spinOnce(); } return 0; @@ -140,15 +78,10 @@ void sleep(int ms) { std::this_thread::sleep_for(std::chrono::milliseconds(ms)); } -void set_arm_position(ros::Publisher& publisher, std::vector positions, int delay) { +void set_arm_position(ros::Publisher& publisher, float positions_arr[7]) { mrover::Position armMsg; // TODO: figure out how to set allen_key and gripper to nan armMsg.names = {"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; - armMsg.positions = std::move(positions); - ROS_INFO("[0]: %f, [1]: %f, [2]: %f", armMsg.positions[0], armMsg.positions[1], armMsg.positions[2]); - - for (int i = 0; i < delay; i += 50) { - sleep(50); - publisher.publish(armMsg); - } + armMsg.positions = positions_arr; + publisher.publish(armMsg); } diff --git a/src/esw/arm_translator_bridge/arm_translator.cpp b/src/esw/arm_translator_bridge/arm_translator.cpp index 058ac7128..0be5f66fe 100644 --- a/src/esw/arm_translator_bridge/arm_translator.cpp +++ b/src/esw/arm_translator_bridge/arm_translator.cpp @@ -1,318 +1,171 @@ #include "arm_translator.hpp" -#include "joint_de_translation.hpp" -#include "linear_joint_translation.hpp" +#include -#include #include +#include +#include namespace mrover { - ArmTranslator::ArmTranslator(ros::NodeHandle& nh) { - assert(mJointDEPitchIndex == mJointDE0Index); - assert(mJointDERollIndex == mJointDE1Index); - assert(mArmHWNames.size() == mRawArmNames.size()); - ROS_INFO("hi"); - for (std::size_t i = 0; i < mRawArmNames.size(); ++i) { - if (i != mJointDEPitchIndex && i != mJointDERollIndex) { - assert(mArmHWNames.at(i) == mRawArmNames.at(i)); - } - { - auto rawName = static_cast(mRawArmNames[i]); - [[maybe_unused]] auto [_, was_inserted] = mAdjustServersByRawArmNames.try_emplace(rawName, nh.advertiseService(std::format("{}_adjust", rawName), &ArmTranslator::adjustServiceCallback, this)); - assert(was_inserted); - } - { - auto hwName = static_cast(mArmHWNames[i]); - [[maybe_unused]] auto [_, was_inserted] = mAdjustClientsByArmHWNames.try_emplace(hwName, nh.serviceClient(std::format("{}_adjust", hwName))); - assert(was_inserted); - } - } - - mJointDEPitchOffset = requireParamAsUnit(nh, "joint_de/pitch_offset"); - mJointDERollOffset = requireParamAsUnit(nh, "joint_de/roll_offset"); - - mMinRadPerSecDE0 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_0/min_velocity"); - mMaxRadPerSecDE0 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_0/max_velocity"); - mMinRadPerSecDE1 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_1/min_velocity"); - mMaxRadPerSecDE1 = requireParamAsUnit(nh, "brushless_motors/controllers/joint_de_1/max_velocity"); + // Maps pitch and roll values to the DE0 and DE1 motors outputs + // For example when only pitching the motor, both controllers should be moving in the same direction + // When rolling, the controllers should move in opposite directions + auto static const PITCH_ROLL_TO_0_1 = (Matrix2{} << -1, -1, -1, 1).finished(); + Dimensionless static constexpr PITCH_ROLL_TO_01_SCALE{40}; - mJointDEPitchPosSub = nh.subscribe("joint_de_pitch_raw_position_data", 1, &ArmTranslator::processPitchRawPositionData, this); - mJointDERollPosSub = nh.subscribe("joint_de_roll_raw_position_data", 1, &ArmTranslator::processRollRawPositionData, this); + // How often we send an adjust command to the DE motors + // This corrects the HALL-effect motor source on the Moteus based on the absolute encoder readings + double static constexpr DE_OFFSET_TIMER_PERIOD = 1; - mJointALinMult = requireParamAsUnit(nh, "brushless_motors/controllers/joint_a/rad_to_meters_ratio"); + ArmTranslator::ArmTranslator(ros::NodeHandle& nh) { + for (std::string const& hwName: mArmHWNames) { + [[maybe_unused]] auto [_, was_inserted] = mAdjustClientsByArmHwNames.try_emplace(hwName, nh.serviceClient(std::format("{}_adjust", hwName))); + assert(was_inserted); + } mThrottleSub = nh.subscribe("arm_throttle_cmd", 1, &ArmTranslator::processThrottleCmd, this); mVelocitySub = nh.subscribe("arm_velocity_cmd", 1, &ArmTranslator::processVelocityCmd, this); mPositionSub = nh.subscribe("arm_position_cmd", 1, &ArmTranslator::processPositionCmd, this); - mArmHWJointDataSub = nh.subscribe("arm_hw_joint_data", 1, &ArmTranslator::processArmHWJointData, this); + mJointDataSub = nh.subscribe("arm_hw_joint_data", 1, &ArmTranslator::processJointState, this); mThrottlePub = std::make_unique(nh.advertise("arm_hw_throttle_cmd", 1)); mVelocityPub = std::make_unique(nh.advertise("arm_hw_velocity_cmd", 1)); mPositionPub = std::make_unique(nh.advertise("arm_hw_position_cmd", 1)); mJointDataPub = std::make_unique(nh.advertise("arm_joint_data", 1)); + + mDeOffsetTimer = nh.createTimer(ros::Duration{DE_OFFSET_TIMER_PERIOD}, &ArmTranslator::updateDeOffsets, this); } - // void ArmTranslator::clampValues(float& val1, float& val2, float minValue1, float maxValue1, float minValue2, float maxValue2) { - // val1 = (val1 - (-80)) / (maxValue1 - minValue1) * (); - // val2 if (val1 < minValue1) { - // float const ratio = minValue1 / val1; - // val1 *= ratio; - // val2 *= ratio; - // } - // if (maxValue1 < val1) { - // float const ratio = maxValue1 / val1; - // val1 *= ratio; - // val2 *= ratio; - // } - // if (val2 < minValue2) { - // float const ratio = minValue2 / val2; - // val1 *= ratio; - // val2 *= ratio; - // } - // if (maxValue2 < val2) { - // float const ratio = maxValue2 / val2; - // val1 *= ratio; - // val2 *= ratio; - // } - // } - - auto ArmTranslator::mapValue(float& val, float inputMinValue, float inputMaxValue, float outputMinValue, float outputMaxValue) -> void { - val = (val - inputMinValue) / (inputMaxValue - inputMinValue) * (outputMaxValue - outputMinValue) + outputMinValue; + auto findJointByName(std::vector const& names, std::string const& name) -> std::optional { + auto it = std::ranges::find(names, name); + return it == names.end() ? std::nullopt : std::make_optional(std::distance(names.begin(), it)); } auto ArmTranslator::processThrottleCmd(Throttle::ConstPtr const& msg) const -> void { - if (mRawArmNames != msg->names || mRawArmNames.size() != msg->throttles.size()) { - ROS_ERROR("Throttle requests for arm is ignored!"); + if (msg->names.size() != msg->throttles.size()) { + ROS_ERROR("Name count and value count mismatched!"); return; } Throttle throttle = *msg; - ROS_INFO("pitch throttle: %f roll throttle: %f", msg->throttles.at(mJointDEPitchIndex), msg->throttles.at(mJointDERollIndex)); - - auto [joint_de_0_throttle, joint_de_1_throttle] = transformPitchRollToMotorOutputs( - msg->throttles.at(mJointDEPitchIndex), - msg->throttles.at(mJointDERollIndex)); - - ROS_INFO("pre-mapped values: de_0 %f de_1 %f", joint_de_0_throttle, joint_de_1_throttle); - mapValue( - joint_de_0_throttle, - -80.0f, - 80.0f, - -1.0f, - 1.0f); + // If present, replace the entries for DE0 and DE1 with the pitch and roll values respectively + std::optional jointDePitchIndex = findJointByName(msg->names, "joint_de_pitch"), jointDeRollIndex = findJointByName(msg->names, "joint_de_roll"); + if (jointDePitchIndex && jointDeRollIndex) { - mapValue( - joint_de_1_throttle, - -80.0f, - 80.0f, - -1.0f, - 1.0f); + std::size_t pitchIndex = jointDePitchIndex.value(), rollIndex = jointDeRollIndex.value(); - throttle.names.at(mJointDEPitchIndex) = "joint_de_0"; - throttle.names.at(mJointDERollIndex) = "joint_de_1"; - throttle.throttles.at(mJointDEPitchIndex) = joint_de_0_throttle; - throttle.throttles.at(mJointDERollIndex) = joint_de_1_throttle; + Vector2 pitchRollThrottles{msg->throttles.at(pitchIndex), msg->throttles.at(rollIndex)}; + Vector2 motorThrottles = PITCH_ROLL_TO_0_1 * pitchRollThrottles; - ROS_INFO("post-mapped values: de_0 %f de_1 %f", joint_de_0_throttle, joint_de_1_throttle); + throttle.names[pitchIndex] = "joint_de_0"; + throttle.names[rollIndex] = "joint_de_1"; + throttle.throttles[pitchIndex] = motorThrottles[0].get(); + throttle.throttles[rollIndex] = motorThrottles[1].get(); + } mThrottlePub->publish(throttle); } - auto ArmTranslator::jointDEIsCalibrated() const -> bool { - return mJointDE0PosOffset.has_value() && mJointDE1PosOffset.has_value(); - } - - auto ArmTranslator::updatePositionOffsets() -> void { - if (!mCurrentRawJointDEPitch.has_value() || !mCurrentRawJointDERoll.has_value() || !mCurrentRawJointDE0Position.has_value() || !mCurrentRawJointDE1Position.has_value()) { + auto ArmTranslator::processVelocityCmd(Velocity::ConstPtr const& msg) -> void { + if (msg->names.size() != msg->velocities.size()) { + ROS_ERROR("Name count and value count mismatched!"); return; } - std::pair expected_motor_outputs = transformPitchRollToMotorOutputs(mCurrentRawJointDEPitch->get(), mCurrentRawJointDERoll->get()); - if (mCurrentRawJointDE0Position.has_value()) { - mJointDE0PosOffset = *mCurrentRawJointDE0Position - Radians{expected_motor_outputs.first}; - } - if (mCurrentRawJointDE1Position.has_value()) { - mJointDE1PosOffset = *mCurrentRawJointDE1Position - Radians{expected_motor_outputs.second}; - } - } + Velocity velocity = *msg; - auto ArmTranslator::processPitchRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void { - mCurrentRawJointDEPitch = Radians{msg->data}; - updatePositionOffsets(); - } + // TODO(quintin): Decrease code duplication + // If present, replace the entries for DE0 and DE1 with the pitch and roll values respectively + std::optional jointDePitchIndex = findJointByName(msg->names, "joint_de_pitch"), jointDeRollIndex = findJointByName(msg->names, "joint_de_roll"); + if (jointDePitchIndex && jointDeRollIndex) { + std::size_t pitchIndex = jointDePitchIndex.value(), rollIndex = jointDeRollIndex.value(); - auto ArmTranslator::processRollRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void { - mCurrentRawJointDERoll = Radians{msg->data}; - updatePositionOffsets(); - } + Vector2 pitchRollVelocities{msg->velocities.at(pitchIndex), msg->velocities.at(rollIndex)}; + Vector2 motorVelocities = PITCH_ROLL_TO_0_1 * pitchRollVelocities; - auto ArmTranslator::processVelocityCmd(Velocity::ConstPtr const& msg) -> void { - if (mRawArmNames != msg->names || mRawArmNames.size() != msg->velocities.size()) { - ROS_ERROR("Velocity requests for arm is ignored!"); - return; + velocity.names[pitchIndex] = "joint_de_0"; + velocity.names[rollIndex] = "joint_de_1"; + velocity.velocities[pitchIndex] = motorVelocities[0].get(); + velocity.velocities[rollIndex] = motorVelocities[1].get(); } - Velocity velocity = *msg; - - auto [joint_de_0_vel, joint_de_1_vel] = transformPitchRollToMotorOutputs( - msg->velocities.at(mJointDEPitchIndex), - msg->velocities.at(mJointDERollIndex)); - - mapValue( - joint_de_0_vel, - -800.0, - 800.0, - mMinRadPerSecDE1.get(), - mMaxRadPerSecDE1.get()); - - mapValue( - joint_de_1_vel, - -800.0, - 800.0, - mMinRadPerSecDE1.get(), - mMaxRadPerSecDE1.get()); - - velocity.names.at(mJointDEPitchIndex) = "joint_de_0"; - velocity.names.at(mJointDERollIndex) = "joint_de_1"; - velocity.velocities.at(mJointDEPitchIndex) = joint_de_0_vel; - velocity.velocities.at(mJointDERollIndex) = joint_de_1_vel; - - // joint a convert linear velocity (meters/s) to revolution/s - auto joint_a_vel = convertLinVel(msg->velocities.at(mJointAIndex), static_cast(mJointALinMult.get())); - velocity.velocities.at(mJointAIndex) = joint_a_vel; - ROS_INFO("joint a velocity after conversion: %f", joint_a_vel); - mVelocityPub->publish(velocity); } auto ArmTranslator::processPositionCmd(Position::ConstPtr const& msg) -> void { - ROS_INFO("msg: %f", msg->positions[0]); - if (mRawArmNames != msg->names || mRawArmNames.size() != msg->positions.size()) { - ROS_ERROR("Position requests for arm is ignored!"); - return; - } - - if (!jointDEIsCalibrated()) { - ROS_ERROR("Position requests for arm is ignored because jointDEIsNotCalibrated!"); + if (msg->names.size() != msg->positions.size()) { + ROS_ERROR("Name count and value count mismatched!"); return; } Position position = *msg; - auto [joint_de_0_raw_pos, joint_de_1_raw_pos] = transformPitchRollToMotorOutputs( - msg->positions.at(mJointDEPitchIndex), - msg->positions.at(mJointDERollIndex)); + // TODO(quintin): Decrease code duplication + // If present, replace the entries for DE0 and DE1 with the pitch and roll values respectively + std::optional jointDePitchIndex = findJointByName(msg->names, "joint_de_pitch"), jointDeRollIndex = findJointByName(msg->names, "joint_de_roll"); + if (jointDePitchIndex && jointDeRollIndex) { + std::size_t pitchIndex = jointDePitchIndex.value(), rollIndex = jointDeRollIndex.value(); - float joint_de_0_pos = joint_de_0_raw_pos + mJointDE0PosOffset->get(); - float joint_de_1_pos = joint_de_1_raw_pos + mJointDE1PosOffset->get(); + Vector2 pitchRoll{msg->positions.at(pitchIndex), msg->positions.at(rollIndex)}; + Vector2 motorPositions = PITCH_ROLL_TO_01_SCALE * PITCH_ROLL_TO_0_1 * pitchRoll; - position.names.at(mJointDEPitchIndex) = "joint_de_0"; - position.names.at(mJointDERollIndex) = "joint_de_1"; - position.positions.at(mJointDEPitchIndex) = joint_de_0_pos; - position.positions.at(mJointDERollIndex) = joint_de_1_pos; + position.names[pitchIndex] = "joint_de_0"; + position.names[rollIndex] = "joint_de_1"; + position.positions[pitchIndex] = motorPositions[0].get(); + position.positions[rollIndex] = motorPositions[1].get(); + } - // joint a convert linear position (meters) to radians - auto joint_a_pos = convertLinPos(msg->positions.at(mJointAIndex), mJointALinMult.get()); - position.positions.at(mJointAIndex) = joint_a_pos; - mPositionPub->publish(position); } - auto ArmTranslator::processArmHWJointData(sensor_msgs::JointState::ConstPtr const& msg) -> void { + auto wrapAngle(float angle) -> float { + constexpr float pi = std::numbers::pi_v; + constexpr float tau = 2 * pi; + return std::fmod(angle + pi, tau) - pi; + } + + auto ArmTranslator::processJointState(sensor_msgs::JointState::ConstPtr const& msg) -> void { if (mArmHWNames != msg->name || mArmHWNames.size() != msg->position.size() || mArmHWNames.size() != msg->velocity.size() || mArmHWNames.size() != msg->effort.size()) { ROS_ERROR("Forwarding joint data for arm is ignored!"); return; } - // Convert joint state of joint a from radians/revolutions to meters - auto jointALinVel = convertLinVel(static_cast(msg->velocity.at(mJointAIndex)), mJointALinMult.get()); - auto jointALinPos = convertLinPos(static_cast(msg->position.at(mJointAIndex)), mJointALinMult.get()); - - sensor_msgs::JointState jointState = *msg; - auto [jointDEPitchVel, jointDERollVel] = transformMotorOutputsToPitchRoll( - static_cast(msg->velocity.at(mJointDE0Index)), - static_cast(msg->velocity.at(mJointDE1Index))); - - [[maybe_unused]] auto [jointDEPitchPos, jointDERollPos] = transformMotorOutputsToPitchRoll( - static_cast(msg->position.at(mJointDE0Index)), - static_cast(msg->position.at(mJointDE1Index))); - - auto [jointDEPitchEff, jointDERollEff] = transformMotorOutputsToPitchRoll( - static_cast(msg->effort.at(mJointDE0Index)), - static_cast(msg->effort.at(mJointDE1Index))); - - mCurrentRawJointDE0Position = Radians{msg->position.at(mJointDE0Index)}; - mCurrentRawJointDE1Position = Radians{msg->position.at(mJointDE1Index)}; - - jointState.name.at(mJointDE0Index) = "joint_de_0"; - jointState.name.at(mJointDE1Index) = "joint_de_1"; - jointState.velocity.at(mJointDE0Index) = jointDEPitchVel; - jointState.velocity.at(mJointDE1Index) = jointDERollVel; - jointState.position.at(mJointDE0Index) = jointDEPitchVel; - jointState.position.at(mJointDE1Index) = jointDERollVel; - jointState.effort.at(mJointDE0Index) = jointDEPitchEff; - jointState.effort.at(mJointDE1Index) = jointDERollEff; - - jointState.velocity.at(mJointAIndex) = jointALinVel; - jointState.position.at(mJointAIndex) = jointALinPos; + std::optional jointDe0Index = findJointByName(msg->name, "joint_de_0"), jointDe1Index = findJointByName(msg->name, "joint_de_1"); + if (jointDe0Index && jointDe1Index) { + // The Moteus reports auxiliary motor positions in the range [0, tau) instead of [-pi, pi) + // Wrap to better align with IK conventions + auto pitchWrapped = wrapAngle(static_cast(msg->position.at(jointDe0Index.value()))); + auto rollWrapped = wrapAngle(static_cast(msg->position.at(jointDe1Index.value()))); + mJointDePitchRoll = {pitchWrapped, rollWrapped}; + jointState.name[jointDe0Index.value()] = "joint_de_pitch"; + jointState.name[jointDe1Index.value()] = "joint_de_roll"; + jointState.position[jointDe0Index.value()] = pitchWrapped; + jointState.position[jointDe1Index.value()] = rollWrapped; + } mJointDataPub->publish(jointState); } - auto ArmTranslator::adjustServiceCallback(AdjustMotor::Request& req, AdjustMotor::Response& res) -> bool { - - if (req.name == "joint_de_roll") { - mJointDERollAdjust = req.value; - } else if (req.name == "joint_de_pitch") { - mJointDEPitchAdjust = req.value; - } else if (req.name == "joint_a") { - AdjustMotor::Request controllerReq; - AdjustMotor::Response controllerRes = res; - controllerReq.value = convertLinPos(static_cast(req.value), mJointALinMult.get()); - - mAdjustClientsByArmHWNames[req.name].call(controllerReq, controllerRes); - res.success = controllerRes.success; - } else { - AdjustMotor::Request controllerReq = req; - AdjustMotor::Response controllerRes = res; - mAdjustClientsByArmHWNames[req.name].call(controllerReq, controllerRes); - res.success = controllerRes.success; - } + auto ArmTranslator::updateDeOffsets(ros::TimerEvent const&) -> void { + if (!mJointDePitchRoll) return; - if (mJointDEPitchAdjust && mJointDERollAdjust) { - // convert DE_roll and DE_pitch into DE_0 and DE_1 (outgoing message to arm_hw_bridge) - auto [joint_de_0_raw_value, joint_de_1_raw_value] = transformPitchRollToMotorOutputs( - mJointDEPitchAdjust.value(), - mJointDERollAdjust.value()); - mJointDEPitchAdjust = std::nullopt; - mJointDERollAdjust = std::nullopt; - - float joint_de_0_value = joint_de_0_raw_value + mJointDE0PosOffset->get(); - float joint_de_1_value = joint_de_1_raw_value + mJointDE1PosOffset->get(); - - AdjustMotor::Response controllerResDE0; - AdjustMotor::Request controllerReqDE0; - controllerReqDE0.name = "joint_de_0"; - controllerReqDE0.value = joint_de_0_value; - mAdjustClientsByArmHWNames[controllerReqDE0.name].call(controllerResDE0, controllerReqDE0); - - AdjustMotor::Response controllerResDE1; - AdjustMotor::Request controllerReqDE1; - controllerReqDE1.name = "joint_de_1"; - controllerReqDE1.value = joint_de_1_value; - mAdjustClientsByArmHWNames[controllerReqDE1.name].call(controllerReqDE1, controllerResDE1); - - res.success = controllerResDE0.success && controllerResDE1.success; - } else { - // adjust service was for de, but both de joints have not adjusted yet - res.success = false; + Vector2 motorPositions = PITCH_ROLL_TO_01_SCALE * PITCH_ROLL_TO_0_1 * mJointDePitchRoll.value(); + { + AdjustMotor adjust; + adjust.request.name = "joint_de_0"; + adjust.request.value = motorPositions[0].get(); + mAdjustClientsByArmHwNames["joint_de_0"].call(adjust); + } + { + AdjustMotor adjust; + adjust.request.name = "joint_de_1"; + adjust.request.value = motorPositions[1].get(); + mAdjustClientsByArmHwNames["joint_de_1"].call(adjust); } - return true; } - -} // namespace mrover \ No newline at end of file +} // namespace mrover diff --git a/src/esw/arm_translator_bridge/arm_translator.hpp b/src/esw/arm_translator_bridge/arm_translator.hpp index 14beae37e..cbab3a91a 100644 --- a/src/esw/arm_translator_bridge/arm_translator.hpp +++ b/src/esw/arm_translator_bridge/arm_translator.hpp @@ -1,12 +1,13 @@ #pragma once -#include "joint_de_translation.hpp" -#include "matrix_helper.hpp" - +#include +#include #include #include +#include #include +#include #include #include @@ -14,23 +15,33 @@ #include #include #include +#include #include #include +#include + #include -#include namespace mrover { + template + using Vector2 = Eigen::Matrix; + + template + using Matrix2 = Eigen::Matrix; + class ArmTranslator { public: ArmTranslator() = default; - explicit ArmTranslator(ros::NodeHandle& nh); + ArmTranslator(ArmTranslator const&) = delete; + ArmTranslator(ArmTranslator&&) = delete; - auto processPitchRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void; + auto operator=(ArmTranslator const&) -> ArmTranslator& = delete; + auto operator=(ArmTranslator&&) -> ArmTranslator& = delete; - auto processRollRawPositionData(std_msgs::Float32::ConstPtr const& msg) -> void; + explicit ArmTranslator(ros::NodeHandle& nh); auto processVelocityCmd(Velocity::ConstPtr const& msg) -> void; @@ -38,66 +49,28 @@ namespace mrover { auto processThrottleCmd(Throttle::ConstPtr const& msg) const -> void; - auto processArmHWJointData(sensor_msgs::JointState::ConstPtr const& msg) -> void; + auto processJointState(sensor_msgs::JointState::ConstPtr const& msg) -> void; - auto adjustServiceCallback(AdjustMotor::Request& req, AdjustMotor::Response& res) -> bool; + auto updateDeOffsets(ros::TimerEvent const&) -> void; private: - // static void clampValues(float& val1, float& val2, float minValue1, float maxValue1, float minValue2, float maxValue2); - - static void mapValue(float& val, float inputMinValue, float inputMaxValue, float outputMinValue, float outputMaxValue); - - [[nodiscard]] auto jointDEIsCalibrated() const -> bool; + std::vector const mArmHWNames{"joint_a", "joint_b", "joint_c", "joint_de_0", "joint_de_1", "allen_key", "gripper"}; - auto updatePositionOffsets() -> void; - - const std::vector mRawArmNames{"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; - const std::vector mArmHWNames{"joint_a", "joint_b", "joint_c", "joint_de_0", "joint_de_1", "allen_key", "gripper"}; std::unique_ptr mThrottlePub; std::unique_ptr mVelocityPub; std::unique_ptr mPositionPub; std::unique_ptr mJointDataPub; - size_t const mJointDEPitchIndex = std::find(mRawArmNames.begin(), mRawArmNames.end(), "joint_de_pitch") - mRawArmNames.begin(); - size_t const mJointDERollIndex = std::find(mRawArmNames.begin(), mRawArmNames.end(), "joint_de_roll") - mRawArmNames.begin(); - size_t const mJointDE0Index = std::find(mArmHWNames.begin(), mArmHWNames.end(), "joint_de_0") - mArmHWNames.begin(); - size_t const mJointDE1Index = std::find(mArmHWNames.begin(), mArmHWNames.end(), "joint_de_1") - mArmHWNames.begin(); - - size_t const mJointAIndex = std::find(mArmHWNames.begin(), mArmHWNames.end(), "joint_a") - mArmHWNames.begin(); - std::optional mJointDE0PosOffset = Radians{0}; - std::optional mJointDE1PosOffset = Radians{0}; - - Radians mJointDEPitchOffset; - Radians mJointDERollOffset; - - std::optional mCurrentRawJointDEPitch; - std::optional mCurrentRawJointDERoll; - std::optional mCurrentRawJointDE0Position; - std::optional mCurrentRawJointDE1Position; - RadiansPerSecond mMinRadPerSecDE0{}; - RadiansPerSecond mMinRadPerSecDE1{}; - RadiansPerSecond mMaxRadPerSecDE0{}; - RadiansPerSecond mMaxRadPerSecDE1{}; + ros::Timer mDeOffsetTimer; - RadiansPerMeter mJointALinMult{}; // TODO: need to be rev/meter for velocity.... - - ros::Subscriber mJointDEPitchPosSub; - ros::Subscriber mJointDERollPosSub; + std::optional> mJointDePitchRoll; ros::Subscriber mThrottleSub; ros::Subscriber mVelocitySub; ros::Subscriber mPositionSub; - ros::Subscriber mArmHWJointDataSub; - - // TODO:(owen) unique_ptr servers? unique_ptr clients? Both? Neither? The world may never know. (try to learn) - std::unordered_map mAdjustServersByRawArmNames; - // std::unordered_map > mCalibrateServer; - - std::unordered_map mAdjustClientsByArmHWNames; - // std::unique_ptr mCalibrateClient; + ros::Subscriber mJointDataSub; - std::optional mJointDEPitchAdjust; - std::optional mJointDERollAdjust; + std::unordered_map mAdjustClientsByArmHwNames; }; } // namespace mrover diff --git a/src/esw/arm_translator_bridge/joint_de_translation.hpp b/src/esw/arm_translator_bridge/joint_de_translation.hpp deleted file mode 100644 index 3108c321d..000000000 --- a/src/esw/arm_translator_bridge/joint_de_translation.hpp +++ /dev/null @@ -1,33 +0,0 @@ -#pragma once - -#include "matrix_helper.hpp" -#include - -namespace mrover { - - constexpr std::array, 2> CONVERT_PITCH_ROLL_TO_MOTORS_MATRIX = {{{{40, 40}}, - {{40, -40}}}}; - - constexpr std::array, 2> CONVERT_MOTORS_TO_PITCH_ROLL_MATRIX = inverseMatrix(CONVERT_PITCH_ROLL_TO_MOTORS_MATRIX); - - [[maybe_unused]] static auto transformMotorOutputsToPitchRoll(float motor_0, float motor_1) -> std::pair { - - std::array motorsVector = {motor_0, motor_1}; - - // Perform matrix multiplication - auto [pitch, roll] = multiplyMatrixByVector(motorsVector, CONVERT_MOTORS_TO_PITCH_ROLL_MATRIX); - - return std::make_pair(pitch, roll); - } - - // Function to transform coordinates - [[maybe_unused]] static auto transformPitchRollToMotorOutputs(float pitch, float roll) -> std::pair { - // Create the input vector - std::array pitchRollVector = {pitch, roll}; - - // Perform matrix multiplication - auto [m1, m2] = multiplyMatrixByVector(pitchRollVector, CONVERT_PITCH_ROLL_TO_MOTORS_MATRIX); - - return std::make_pair(m1, m2); - } -} // namespace mrover diff --git a/src/esw/arm_translator_bridge/matrix_helper.hpp b/src/esw/arm_translator_bridge/matrix_helper.hpp deleted file mode 100644 index 3b893861e..000000000 --- a/src/esw/arm_translator_bridge/matrix_helper.hpp +++ /dev/null @@ -1,24 +0,0 @@ -#pragma once - -#include - -namespace mrover { - - constexpr std::array, 2> inverseMatrix(std::array, 2> const& matrix) { - float determinant = matrix[0][0] * matrix[1][1] - matrix[0][1] * matrix[1][0]; - float invDet = 1.0f / determinant; - - std::array, 2> result = {{{matrix[1][1] * invDet, -matrix[0][1] * invDet}, - {-matrix[1][0] * invDet, matrix[0][0] * invDet}}}; - - return result; - } - - static std::array multiplyMatrixByVector(std::array const& vector, std::array, 2> const& matrix) { - std::array result = { - matrix[0][0] * vector[0] + matrix[0][1] * vector[1], - matrix[1][0] * vector[0] + matrix[1][1] * vector[1]}; - return result; - } - -} // namespace mrover diff --git a/src/esw/brushless_test_bridge/brushless_test_bridge.cpp b/src/esw/brushless_test_bridge/brushless_test_bridge.cpp index 74eabdcfd..b8b615121 100644 --- a/src/esw/brushless_test_bridge/brushless_test_bridge.cpp +++ b/src/esw/brushless_test_bridge/brushless_test_bridge.cpp @@ -1,3 +1,4 @@ +#include #include #include @@ -5,6 +6,27 @@ #include #include + +// void test_joint_de(ros::NodeHandle& nh) { + +// auto brushlessController_de0 = std::make_unique(nh, "jetson", "joint_de_0"); +// auto brushlessController_de1 = std::make_unique(nh, "jetson", "joint_de_1"); + +// brushlessController_de0->setStop(); +// brushlessController_de1->setStop(); + +// ros::Rate rate{20}; +// while (ros::ok()) { +// brushlessController_de0->setDesiredVelocity(mrover::RadiansPerSecond{60.0}); +// brushlessController_de1->setDesiredVelocity(mrover::RadiansPerSecond{60.0}); + +// ros::spinOnce(); +// rate.sleep(); +// } + + +// } + auto main(int argc, char** argv) -> int { // Initialize the ROS node ros::init(argc, argv, "brushless_test_bridge"); @@ -24,44 +46,64 @@ auto main(int argc, char** argv) -> int { // auto brushlessController_de0 = std::make_unique(nh, "jetson", "joint_de_0"); // auto brushlessController_de1 = std::make_unique(nh, "jetson", "joint_de_1"); - + // fake DE publisher: - auto DEPub = std::make_unique(nh.advertise("arm_velocity_cmd", 1)); - auto SAPub = std::make_unique(nh.advertise("sa_velocity_cmd", 1)); + // auto DEPub = std::make_unique(nh.advertise("arm_velocity_cmd", 1)); + // auto SAPub = std::make_unique(nh.advertise("sa_velocity_cmd", 1)); + auto dePub = nh.advertise("arm_position_cmd", 1); - mrover::Velocity armMsg; - mrover::Velocity saMsg; + mrover::Position armMsg; armMsg.names = {"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; - armMsg.velocities = {0, 0, 0, 20, 20, 0, 0}; + armMsg.positions = {0, 0, 0, 0, 0, 0, 0}; + + std::size_t index = 0; + auto timer = ros::Timer(nh.createTimer(ros::Duration{10}, [&](ros::TimerEvent const&) { + armMsg.positions[3] = std::array{-1, 1, 0, 0, 0, 0, -1}[index]; + armMsg.positions[4] = std::array{0, 0, 0, -3.14, 3.14, 0, 3.14}[index]; + index = (index + 1) % 7; + })); + + ros::Rate rate{20}; + while (ros::ok()) { + dePub.publish(armMsg); + ros::spinOnce(); + rate.sleep(); + } + + // mrover::Velocity armMsg; + // mrover::Velocity saMsg; + // armMsg.names = {"joint_a", "joint_b", "joint_c", "joint_de_pitch", "joint_de_roll", "allen_key", "gripper"}; + // armMsg.velocities = {0, 0, 0, 0, -10, 0, 0}; - saMsg.names = {"sa_x", "sa_y", "sa_z", "sampler", "sensor_actuator"}; - saMsg.velocities = {0, 0, 0.07,0, 0}; + // saMsg.names = {"sa_x", "sa_y", "sa_z", "sampler", "sensor_actuator"}; + // saMsg.velocities = {0, 0, 0.07,0, 0}; // brushlessController_de0->setStop(); // brushlessController_de1->setStop(); - ros::Rate rate{15}; - - int count = 0; - - while(ros::ok()){ - // publish DE velocity: - DEPub->publish(armMsg); - SAPub->publish(saMsg); - count++; + // ros::Rate rate{15}; + // + // int count = 0; + // + // + // while (ros::ok()) { + // // publish DE velocity: + // DEPub->publish(armMsg); + // // SAPub->publish(saMsg); + // count++; + // + // if (count > 100) { + // armMsg.velocities[3] *= -1; + // armMsg.velocities[4] *= -1; + // count = 0; + // } + // + // ros::spinOnce(); + // rate.sleep(); + // } - if(count > 100) { - armMsg.velocities[3] *= -1; - armMsg.velocities[4] *= -1; - count = 0; - } - - ros::spinOnce(); - rate.sleep(); - } return EXIT_SUCCESS; } - diff --git a/src/esw/can_device/can_device.hpp b/src/esw/can_device/can_device.hpp index 9c966deca..464d80bf2 100644 --- a/src/esw/can_device/can_device.hpp +++ b/src/esw/can_device/can_device.hpp @@ -11,7 +11,6 @@ #include -#define CANFD_FDF 0x04 #include namespace mrover { diff --git a/src/esw/drive_bridge/main.cpp b/src/esw/drive_bridge/main.cpp index 7a895dd21..9e836e462 100644 --- a/src/esw/drive_bridge/main.cpp +++ b/src/esw/drive_bridge/main.cpp @@ -5,45 +5,38 @@ #include #include +/* + * Converts from a Twist (linear and angular velocity) to the individual wheel velocities + */ + using namespace mrover; void moveDrive(geometry_msgs::Twist::ConstPtr const& msg); -std::unique_ptr driveManager; -std::vector driveNames{"front_left", "front_right", "middle_left", "middle_right", "back_left", "back_right"}; +ros::Publisher leftVelocityPub, rightVelocityPub; Meters WHEEL_DISTANCE_INNER; -Meters WHEEL_DISTANCE_OUTER; compound_unit> WHEEL_LINEAR_TO_ANGULAR; -RadiansPerSecond MAX_MOTOR_SPEED; auto main(int argc, char** argv) -> int { - // Initialize the ROS node ros::init(argc, argv, "drive_bridge"); ros::NodeHandle nh; - // Load rover dimensions and other parameters from the ROS parameter server auto roverWidth = requireParamAsUnit(nh, "rover/width"); - auto roverLength = requireParamAsUnit(nh, "rover/length"); WHEEL_DISTANCE_INNER = roverWidth / 2; - WHEEL_DISTANCE_OUTER = sqrt(((roverWidth / 2) * (roverWidth / 2)) + ((roverLength / 2) * (roverLength / 2))); auto ratioMotorToWheel = requireParamAsUnit(nh, "wheel/gear_ratio"); auto wheelRadius = requireParamAsUnit(nh, "wheel/radius"); - // TODO(quintin) is dividing by ratioMotorToWheel right? WHEEL_LINEAR_TO_ANGULAR = Radians{1} / wheelRadius * ratioMotorToWheel; - auto maxLinearSpeed = requireParamAsUnit(nh, "rover/max_speed"); - assert(maxLinearSpeed > 0_mps); - - MAX_MOTOR_SPEED = maxLinearSpeed * WHEEL_LINEAR_TO_ANGULAR; + auto leftGroup = std::make_unique(nh, "drive_left"); + auto rightGroup = std::make_unique(nh, "drive_right"); - driveManager = std::make_unique(nh, "drive"); + leftVelocityPub = nh.advertise("drive_left_velocity_cmd", 1); + rightVelocityPub = nh.advertise("drive_right_velocity_cmd", 1); - // Subscribe to the ROS topic for drive commands - ros::Subscriber moveDriveSubscriber = nh.subscribe("cmd_vel", 1, moveDrive); + auto twistSubscriber = nh.subscribe("cmd_vel", 1, moveDrive); - // Enter the ROS event loop ros::spin(); return 0; @@ -59,16 +52,17 @@ void moveDrive(geometry_msgs::Twist::ConstPtr const& msg) { RadiansPerSecond left = (forward - delta) * WHEEL_LINEAR_TO_ANGULAR; RadiansPerSecond right = (forward + delta) * WHEEL_LINEAR_TO_ANGULAR; - std::unordered_map driveCommandVelocities{ - {"front_left", left}, - {"front_right", right}, - {"middle_left", left}, - {"middle_right", right}, - {"back_left", left}, - {"back_right", right}, - }; - - for (auto [name, angularVelocity]: driveCommandVelocities) { - driveManager->getController(name).setDesiredVelocity(angularVelocity); + { + Velocity leftVelocity; + leftVelocity.names = {"front_left", "middle_left", "back_left"}; + leftVelocity.velocities.resize(leftVelocity.names.size(), left.get()); + leftVelocity.velocities.resize(leftVelocity.names.size(), left.get()); + leftVelocityPub.publish(leftVelocity); + } + { + Velocity rightVelocity; + rightVelocity.names = {"front_right", "middle_right", "back_right"}; + rightVelocity.velocities.resize(rightVelocity.names.size(), right.get()); + rightVelocityPub.publish(rightVelocity); } } diff --git a/src/esw/fw/bdcmc/.mxproject b/src/esw/fw/bdcmc/.mxproject index 39d7f8d4a..4f2334bec 100644 --- a/src/esw/fw/bdcmc/.mxproject +++ b/src/esw/fw/bdcmc/.mxproject @@ -1,25 +1,25 @@ [PreviousLibFiles] -LibFiles=Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_fdcan.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_def.h;Drivers/STM32G4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_bus.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_system.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_utils.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_crs.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ramfunc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dmamux.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_tim.h;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_fdcan.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ramfunc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_gpio.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_exti.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim_ex.c;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_fdcan.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_def.h;Drivers/STM32G4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_rcc_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_bus.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_rcc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_system.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_utils.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_crs.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ramfunc.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_gpio_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_gpio.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_exti.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_dma_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dma.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_dmamux.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pwr_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_pwr.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_cortex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_i2c.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_i2c_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_tim_ex.h;Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_ll_tim.h;Drivers/CMSIS/Device/ST/STM32G4xx/Include/stm32g431xx.h;Drivers/CMSIS/Device/ST/STM32G4xx/Include/stm32g4xx.h;Drivers/CMSIS/Device/ST/STM32G4xx/Include/system_stm32g4xx.h;Drivers/CMSIS/Device/ST/STM32G4xx/Source/Templates/system_stm32g4xx.c;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/cmsis_version.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/core_cm35p.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/core_armv8mbl.h;Drivers/CMSIS/Include/core_sc300.h;Drivers/CMSIS/Include/core_cm33.h;Drivers/CMSIS/Include/mpu_armv7.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/cmsis_armclang_ltm.h;Drivers/CMSIS/Include/cmsis_iccarm.h;Drivers/CMSIS/Include/tz_context.h;Drivers/CMSIS/Include/core_cm1.h;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_cm4.h;Drivers/CMSIS/Include/mpu_armv8.h;Drivers/CMSIS/Include/core_armv8mml.h;Drivers/CMSIS/Include/core_cm23.h;Drivers/CMSIS/Include/cmsis_compiler.h;Drivers/CMSIS/Include/core_armv81mml.h;Drivers/CMSIS/Include/cmsis_armclang.h; +LibFiles=Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_fdcan.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_def.h;Drivers\STM32G4xx_HAL_Driver\Inc\Legacy\stm32_hal_legacy.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_bus.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_system.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_utils.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_crs.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ramfunc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dmamux.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_tim.h;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_fdcan.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ramfunc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim_ex.c;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_fdcan.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_def.h;Drivers\STM32G4xx_HAL_Driver\Inc\Legacy\stm32_hal_legacy.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_rcc_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_bus.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_rcc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_system.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_utils.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_crs.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_flash_ramfunc.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_gpio_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_gpio.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_exti.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_dma_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dma.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_dmamux.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_pwr_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_pwr.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_cortex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_i2c.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_i2c_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_hal_tim_ex.h;Drivers\STM32G4xx_HAL_Driver\Inc\stm32g4xx_ll_tim.h;Drivers\CMSIS\Device\ST\STM32G4xx\Include\stm32g431xx.h;Drivers\CMSIS\Device\ST\STM32G4xx\Include\stm32g4xx.h;Drivers\CMSIS\Device\ST\STM32G4xx\Include\system_stm32g4xx.h;Drivers\CMSIS\Device\ST\STM32G4xx\Source\Templates\system_stm32g4xx.c;Drivers\CMSIS\Include\cmsis_armcc.h;Drivers\CMSIS\Include\cmsis_armclang.h;Drivers\CMSIS\Include\cmsis_armclang_ltm.h;Drivers\CMSIS\Include\cmsis_compiler.h;Drivers\CMSIS\Include\cmsis_gcc.h;Drivers\CMSIS\Include\cmsis_iccarm.h;Drivers\CMSIS\Include\cmsis_version.h;Drivers\CMSIS\Include\core_armv81mml.h;Drivers\CMSIS\Include\core_armv8mbl.h;Drivers\CMSIS\Include\core_armv8mml.h;Drivers\CMSIS\Include\core_cm0.h;Drivers\CMSIS\Include\core_cm0plus.h;Drivers\CMSIS\Include\core_cm1.h;Drivers\CMSIS\Include\core_cm23.h;Drivers\CMSIS\Include\core_cm3.h;Drivers\CMSIS\Include\core_cm33.h;Drivers\CMSIS\Include\core_cm35p.h;Drivers\CMSIS\Include\core_cm4.h;Drivers\CMSIS\Include\core_cm7.h;Drivers\CMSIS\Include\core_sc000.h;Drivers\CMSIS\Include\core_sc300.h;Drivers\CMSIS\Include\mpu_armv7.h;Drivers\CMSIS\Include\mpu_armv8.h;Drivers\CMSIS\Include\tz_context.h; [PreviousUsedCubeIDEFiles] -SourceFiles=Core/Src/main.c;Core/Src/stm32g4xx_it.c;Core/Src/stm32g4xx_hal_msp.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_fdcan.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ramfunc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_gpio.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_exti.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim_ex.c;Drivers/CMSIS/Device/ST/STM32G4xx/Source/Templates/system_stm32g4xx.c;Core/Src/system_stm32g4xx.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_fdcan.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ramfunc.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_gpio.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_exti.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_i2c_ex.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim.c;Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim_ex.c;Drivers/CMSIS/Device/ST/STM32G4xx/Source/Templates/system_stm32g4xx.c;Core/Src/system_stm32g4xx.c;;; -HeaderPath=Drivers/STM32G4xx_HAL_Driver/Inc;Drivers/STM32G4xx_HAL_Driver/Inc/Legacy;Drivers/CMSIS/Device/ST/STM32G4xx/Include;Drivers/CMSIS/Include;Core/Inc; +SourceFiles=Core\Src\main.c;Core\Src\stm32g4xx_it.c;Core\Src\stm32g4xx_hal_msp.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_fdcan.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ramfunc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim_ex.c;Drivers\CMSIS\Device\ST\STM32G4xx\Source\Templates\system_stm32g4xx.c;Core\Src\system_stm32g4xx.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_fdcan.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash_ramfunc.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_i2c_ex.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim.c;Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_tim_ex.c;Drivers\CMSIS\Device\ST\STM32G4xx\Source\Templates\system_stm32g4xx.c;Core\Src\system_stm32g4xx.c;;; +HeaderPath=Drivers\STM32G4xx_HAL_Driver\Inc;Drivers\STM32G4xx_HAL_Driver\Inc\Legacy;Drivers\CMSIS\Device\ST\STM32G4xx\Include;Drivers\CMSIS\Include;Core\Inc; CDefines=USE_HAL_DRIVER;STM32G431xx;USE_HAL_DRIVER;USE_HAL_DRIVER; [PreviousGenFiles] AdvancedFolderStructure=true HeaderFileListSize=3 -HeaderFiles#0=../Core/Inc/stm32g4xx_it.h -HeaderFiles#1=../Core/Inc/stm32g4xx_hal_conf.h -HeaderFiles#2=../Core/Inc/main.h +HeaderFiles#0=..\Core\Inc\stm32g4xx_it.h +HeaderFiles#1=..\Core\Inc\stm32g4xx_hal_conf.h +HeaderFiles#2=..\Core\Inc\main.h HeaderFolderListSize=1 -HeaderPath#0=../Core/Inc +HeaderPath#0=..\Core\Inc HeaderFiles=; SourceFileListSize=3 -SourceFiles#0=../Core/Src/stm32g4xx_it.c -SourceFiles#1=../Core/Src/stm32g4xx_hal_msp.c -SourceFiles#2=../Core/Src/main.c +SourceFiles#0=..\Core\Src\stm32g4xx_it.c +SourceFiles#1=..\Core\Src\stm32g4xx_hal_msp.c +SourceFiles#2=..\Core\Src\main.c SourceFolderListSize=1 -SourcePath#0=../Core/Src +SourcePath#0=..\Core\Src SourceFiles=; diff --git a/src/esw/fw/bdcmc/Core/Inc/common.hpp b/src/esw/fw/bdcmc/Core/Inc/common.hpp new file mode 100644 index 000000000..c51dcca6a --- /dev/null +++ b/src/esw/fw/bdcmc/Core/Inc/common.hpp @@ -0,0 +1,23 @@ +#pragma once + +#include + +namespace mrover { + + constexpr auto TAU_F = 2 * std::numbers::pi_v; + + constexpr auto CLOCK_FREQ = Hertz{140000000}; + + // Counts (ticks) per radian (NOT per rotation) + using CountsPerRad = compound_unit>; + + constexpr auto RELATIVE_CPR = CountsPerRad{3355 / TAU_F}; // Measured empirically from the devboard + constexpr auto ABSOLUTE_CPR = CountsPerRad{(1 << 14) / TAU_F}; // Corresponds to the AS5048B + + // NOTE: Change This For Each Motor Controller + constexpr static std::uint8_t DEVICE_ID = 0x21; // currently set for joint_b + + // Usually this is the Jetson + constexpr static std::uint8_t DESTINATION_DEVICE_ID = 0x10; + +} // namespace mrover diff --git a/src/esw/fw/bdcmc/Core/Inc/controller.hpp b/src/esw/fw/bdcmc/Core/Inc/controller.hpp index 104cd6ea5..4d8d6902d 100644 --- a/src/esw/fw/bdcmc/Core/Inc/controller.hpp +++ b/src/esw/fw/bdcmc/Core/Inc/controller.hpp @@ -11,6 +11,7 @@ #include #include +#include "common.hpp" #include "encoders.hpp" #include "hbridge.hpp" #include "testing.hpp" @@ -35,6 +36,8 @@ namespace mrover { bool m_watchdog_enabled{}; TIM_HandleTypeDef* m_encoder_timer{}; TIM_HandleTypeDef* m_encoder_elapsed_timer{}; + TIM_HandleTypeDef* m_throttle_timer{}; + TIM_HandleTypeDef* m_pidf_timer{}; I2C_HandleTypeDef* m_absolute_encoder_i2c{}; std::optional m_relative_encoder; std::optional m_absolute_encoder; @@ -45,9 +48,16 @@ namespace mrover { // "Desired" since it may be overridden. // For example if we are trying to drive into a limit switch it will be overriden to zero. Percent m_desired_output; + // Actual output after throttling. + // Changing the output quickly can result in back-EMF which can damage the board. + // This is a temporary fix until EHW adds TVS diodes. + Percent m_throttled_output; + using PercentPerSecond = compound_unit>; + PercentPerSecond m_throttle_rate{100}; std::optional m_uncalib_position; std::optional m_velocity; BDCMCErrorInfo m_error = BDCMCErrorInfo::DEFAULT_START_UP_NOT_CONFIGURED; + std::size_t m_missed_absolute_encoder_reads{0}; struct StateAfterConfig { Dimensionless gear_ratio; @@ -85,8 +95,8 @@ namespace mrover { m_uncalib_position = position; m_velocity = velocity; } else { - m_uncalib_position = std::nullopt; - m_velocity = std::nullopt; + m_uncalib_position.reset(); + m_velocity.reset(); } } @@ -114,14 +124,12 @@ namespace mrover { if (m_state_after_config) { // TODO: verify this is correct - bool limit_forward = m_desired_output > 0_percent && ( - std::ranges::any_of(m_limit_switches, &LimitSwitch::limit_forward) - //|| m_uncalib_position > m_state_after_config->max_position - ); - bool limit_backward = m_desired_output < 0_percent && ( - std::ranges::any_of(m_limit_switches, &LimitSwitch::limit_backward) - //|| m_uncalib_position < m_state_after_config->min_position - ); + bool limit_forward = m_desired_output > 0_percent && (std::ranges::any_of(m_limit_switches, &LimitSwitch::limit_forward) + //|| m_uncalib_position > m_state_after_config->max_position + ); + bool limit_backward = m_desired_output < 0_percent && (std::ranges::any_of(m_limit_switches, &LimitSwitch::limit_backward) + //|| m_uncalib_position < m_state_after_config->min_position + ); if (limit_forward || limit_backward) { m_error = BDCMCErrorInfo::OUTPUT_SET_TO_ZERO_SINCE_EXCEEDING_LIMITS; } else { @@ -129,7 +137,27 @@ namespace mrover { } } - m_motor_driver.write(output.value_or(0_percent)); + Percent output_after_limit = output.value_or(0_percent); + Percent delta = output_after_limit - m_throttled_output; + + Seconds dt = cycle_time(m_throttle_timer, CLOCK_FREQ); + + Percent applied_delta = m_throttle_rate * dt; + + if (signum(output_after_limit) != signum(m_throttled_output)) { + // If we are changing directions, go straight to zero + // This also includes when going to zero from a non-zero value (since signum(0) == 0), helpful for when you want to stop moving quickly on input release + m_throttled_output = 0_percent; + } + + if (abs(delta) < applied_delta) { + // We are very close to the desired output, just set it + m_throttled_output = output_after_limit; + } else { + m_throttled_output += applied_delta * signum(delta); + } + + m_motor_driver.write(m_throttled_output); } auto process_command(AdjustCommand const& message) -> void { @@ -142,24 +170,23 @@ namespace mrover { } auto process_command(ConfigCommand const& message) -> void { - // Initialize values StateAfterConfig config{.gear_ratio = message.gear_ratio}; if (message.enc_info.quad_present) { - Ratio multiplier = (message.enc_info.quad_is_forward_polarity ? 1 : -1) * message.enc_info.quad_ratio; - if (!m_relative_encoder) m_relative_encoder.emplace(m_encoder_timer, multiplier, m_encoder_elapsed_timer); + if (!m_relative_encoder) m_relative_encoder.emplace(m_encoder_timer, message.enc_info.quad_ratio, m_encoder_elapsed_timer); } if (message.enc_info.abs_present) { - Ratio multiplier = (message.enc_info.abs_is_forward_polarity ? 1 : -1) * message.enc_info.abs_ratio; - if (!m_absolute_encoder) m_absolute_encoder.emplace(AbsoluteEncoderReader::AS5048B_Bus{m_absolute_encoder_i2c}, message.enc_info.abs_offset, multiplier, m_encoder_elapsed_timer); + if (!m_absolute_encoder) m_absolute_encoder.emplace(AbsoluteEncoderReader::AS5048B_Bus{m_absolute_encoder_i2c}, message.enc_info.abs_offset, message.enc_info.abs_ratio, m_encoder_elapsed_timer); } m_motor_driver.change_max_pwm(message.max_pwm); + m_motor_driver.change_inverted(message.is_inverted); config.min_position = message.min_position; config.max_position = message.max_position; - // TODO: verify this is correct + // Boolean configs are stored as bitfields so we have to extract them carefully + for (std::size_t i = 0; i < m_limit_switches.size(); ++i) { if (GET_BIT_AT_INDEX(message.limit_switch_info.present, i)) { bool enabled = GET_BIT_AT_INDEX(message.limit_switch_info.enabled, i); @@ -181,7 +208,6 @@ namespace mrover { } auto process_command(IdleCommand const&) -> void { - // TODO - what is the expected behavior? just afk? if (!m_state_after_config) { m_error = BDCMCErrorInfo::RECEIVING_COMMANDS_WHEN_NOT_CONFIGURED; return; @@ -219,14 +245,13 @@ namespace mrover { mode.pidf.with_d(message.d); mode.pidf.with_ff(message.ff); mode.pidf.with_output_bound(-1.0, 1.0); - // TODO(quintin): Use timer for dt - m_desired_output = mode.pidf.calculate(input, target, Seconds{0.01}); + m_desired_output = mode.pidf.calculate(input, target, cycle_time(m_pidf_timer, CLOCK_FREQ)); m_error = BDCMCErrorInfo::NO_ERROR; - m_fdcan.broadcast(OutBoundMessage{DebugState{ - .f1 = m_velocity.value().get(), - .f2 = message.velocity.get(), - }}); + // m_fdcan.broadcast(OutBoundMessage{DebugState{ + // .f1 = m_velocity.value().get(), + // .f2 = message.velocity.get(), + // }}); } auto process_command(PositionCommand const& message, PositionMode& mode) -> void { @@ -250,8 +275,7 @@ namespace mrover { // mode.pidf.with_i(message.i); mode.pidf.with_d(message.d); mode.pidf.with_output_bound(-1.0, 1.0); - // TODO(quintin): Use timer for dt - m_desired_output = mode.pidf.calculate(input, target, Seconds{0.01}); + m_desired_output = mode.pidf.calculate(input, target, cycle_time(m_pidf_timer, CLOCK_FREQ)); m_error = BDCMCErrorInfo::NO_ERROR; } @@ -279,14 +303,22 @@ namespace mrover { public: Controller() = default; - Controller(TIM_HandleTypeDef* hbridge_output, Pin hbridge_forward_pin, Pin hbridge_backward_pin, FDCAN const& fdcan, TIM_HandleTypeDef* watchdog_timer, TIM_HandleTypeDef* encoder_tick_timer, TIM_HandleTypeDef* encoder_elapsed_timer, I2C_HandleTypeDef* absolute_encoder_i2c, std::array const& limit_switches) + Controller(TIM_HandleTypeDef* hbridge_output, Pin hbridge_forward_pin, Pin hbridge_backward_pin, + FDCAN const& fdcan, TIM_HandleTypeDef* watchdog_timer, + TIM_HandleTypeDef* encoder_tick_timer, + TIM_HandleTypeDef* encoder_elapsed_timer, TIM_HandleTypeDef* throttle_timer, TIM_HandleTypeDef* pid_timer, + I2C_HandleTypeDef* absolute_encoder_i2c, + std::array const& limit_switches) : m_fdcan{fdcan}, m_motor_driver{HBridge(hbridge_output, hbridge_forward_pin, hbridge_backward_pin)}, m_watchdog_timer{watchdog_timer}, m_encoder_timer{encoder_tick_timer}, m_encoder_elapsed_timer{encoder_elapsed_timer}, + m_throttle_timer{throttle_timer}, + m_pidf_timer{pid_timer}, m_absolute_encoder_i2c{absolute_encoder_i2c}, - m_limit_switches{limit_switches} {} + m_limit_switches{limit_switches} { + } template auto process_command(Command const& command) -> void { @@ -423,10 +455,17 @@ namespace mrover { update(); } + // Max hits before we remove the calibration state + constexpr static std::size_t MAX_MISSED_ABSOLUTE_ENCODER_READS = 32; + auto request_absolute_encoder_data() -> void { // Only read the encoder if we are configured if (m_absolute_encoder) { m_absolute_encoder->request_raw_angle(); + // TODO(quintin): No magic numbers + if (m_missed_absolute_encoder_reads++ > MAX_MISSED_ABSOLUTE_ENCODER_READS) { + m_state_after_calib.reset(); + } } } @@ -436,6 +475,9 @@ namespace mrover { } } + /** + * Called after a successful I2C transaction + */ auto update_absolute_encoder() -> void { if (!m_absolute_encoder) return; @@ -443,18 +485,20 @@ namespace mrover { auto const& [position, velocity] = reading.value(); if (!m_state_after_calib) m_state_after_calib.emplace(); + m_missed_absolute_encoder_reads = 0; + // TODO(quintin): This is pretty stupid m_state_after_calib->offset_position = -position; - m_fdcan.broadcast(OutBoundMessage{DebugState{ - .f1 = position.get(), - }}); + // m_fdcan.broadcast(OutBoundMessage{DebugState{ + // .f1 = position.get(), + // }}); m_uncalib_position.emplace(); // Reset to zero m_velocity = velocity; } else { - m_uncalib_position = std::nullopt; - m_velocity = std::nullopt; + m_uncalib_position.reset(); + m_velocity.reset(); } } }; diff --git a/src/esw/fw/bdcmc/Core/Inc/encoders.hpp b/src/esw/fw/bdcmc/Core/Inc/encoders.hpp index 275085eb2..fcb24e25d 100644 --- a/src/esw/fw/bdcmc/Core/Inc/encoders.hpp +++ b/src/esw/fw/bdcmc/Core/Inc/encoders.hpp @@ -8,19 +8,11 @@ #include #include +#include "common.hpp" #include "filtering.hpp" namespace mrover { - constexpr auto tau = 2 * std::numbers::pi_v; - - // Counts (ticks) per radian (NOT per rotation) - using CountsPerRad = compound_unit>; - - constexpr auto RELATIVE_CPR = CountsPerRad{3355 / tau}; // Measured empirically - constexpr auto ABSOLUTE_CPR = CountsPerRad{(1 << 14) / tau}; - auto const CLOCK_FREQ = Hertz{HAL_RCC_GetHCLKFreq()}; - struct EncoderReading { Radians position; RadiansPerSecond velocity; diff --git a/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp b/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp index c759ff1bf..e01f59fa4 100644 --- a/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp +++ b/src/esw/fw/bdcmc/Core/Inc/hbridge.hpp @@ -7,25 +7,28 @@ namespace mrover { - struct HBridge { + class HBridge { + Pin m_positive_pin{}; + Pin m_negative_pin{}; + TIM_HandleTypeDef* m_timer{}; + std::uint32_t m_channel = TIM_CHANNEL_1; + Percent m_max_pwm{}; + bool m_is_inverted = false; + + public: HBridge() = default; - explicit HBridge(TIM_HandleTypeDef* timer, Pin forward_pin, Pin reverse_pin); + explicit HBridge(TIM_HandleTypeDef* timer, Pin positive_pin, Pin negative_pin); - void write(Percent output) const; + auto write(Percent output) const -> void; - void change_max_pwm(Percent max_pwm); + auto set_direction_pins(Percent duty_cycle) const -> void; - private: - void set_direction_pins(Percent duty_cycle) const; + auto set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const -> void; - void set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const; + auto change_max_pwm(Percent max_pwm) -> void; - Pin m_forward_pins{}; - Pin m_reverse_pins{}; - TIM_HandleTypeDef* m_timer{}; - std::uint32_t m_channel = TIM_CHANNEL_1; - Percent m_max_pwm{}; + auto change_inverted(bool inverted) -> void; }; } // namespace mrover diff --git a/src/esw/fw/bdcmc/Core/Inc/main.h b/src/esw/fw/bdcmc/Core/Inc/main.h index 10cf7d765..0814ce08a 100644 --- a/src/esw/fw/bdcmc/Core/Inc/main.h +++ b/src/esw/fw/bdcmc/Core/Inc/main.h @@ -89,14 +89,8 @@ void HAL_PostInit(); #define MOTOR_0_DIR_GPIO_Port GPIOB #define MOTOR_1_DIR_Pin GPIO_PIN_6 #define MOTOR_1_DIR_GPIO_Port GPIOC -#define MOTOR_1_PWM_Pin GPIO_PIN_8 -#define MOTOR_1_PWM_GPIO_Port GPIOA #define CAN_STANDBY_Pin GPIO_PIN_15 #define CAN_STANDBY_GPIO_Port GPIOA -#define QUAD_0_A_Pin GPIO_PIN_6 -#define QUAD_0_A_GPIO_Port GPIOB -#define QUAD_0_B_Pin GPIO_PIN_7 -#define QUAD_0_B_GPIO_Port GPIOB /* USER CODE BEGIN Private defines */ diff --git a/src/esw/fw/bdcmc/Core/Inc/stm32g4xx_it.h b/src/esw/fw/bdcmc/Core/Inc/stm32g4xx_it.h index cc9b4bf35..df1ee310e 100644 --- a/src/esw/fw/bdcmc/Core/Inc/stm32g4xx_it.h +++ b/src/esw/fw/bdcmc/Core/Inc/stm32g4xx_it.h @@ -63,6 +63,7 @@ void TIM1_TRG_COM_TIM17_IRQHandler(void); void TIM2_IRQHandler(void); void I2C1_EV_IRQHandler(void); void I2C1_ER_IRQHandler(void); +void TIM6_DAC_IRQHandler(void); void TIM7_IRQHandler(void); /* USER CODE BEGIN EFP */ diff --git a/src/esw/fw/bdcmc/Core/Src/controller.cpp b/src/esw/fw/bdcmc/Core/Src/controller.cpp index fa8445833..248f0bccb 100644 --- a/src/esw/fw/bdcmc/Core/Src/controller.cpp +++ b/src/esw/fw/bdcmc/Core/Src/controller.cpp @@ -13,40 +13,35 @@ extern I2C_HandleTypeDef hi2c1; #define ABSOLUTE_I2C &hi2c1 /** - * For each timer, the update rate is determined by the .ioc file. + * For each repeating timer, the update rate is determined by the .ioc file. * * Specifically the ARR value. You can use the following equation: ARR = (MCU Clock Speed) / (Update Rate) / (Prescaler + 1) - 1 * For the STM32G4 we have a 140 MHz clock speed configured. * - * You must also set auto reload to true so the interurpt gets called on a cycle. + * You must also set auto reload to true so the interrupt gets called on a cycle. */ extern TIM_HandleTypeDef htim2; -extern TIM_HandleTypeDef htim4; extern TIM_HandleTypeDef htim3; extern TIM_HandleTypeDef htim6; extern TIM_HandleTypeDef htim7; +extern TIM_HandleTypeDef htim8; extern TIM_HandleTypeDef htim15; extern TIM_HandleTypeDef htim16; extern TIM_HandleTypeDef htim17; -#define QUADRATURE_TICK_TIMER_1 &htim3 // Special encoder timer which externally reads quadrature encoder ticks +#define QUADRATURE_TICK_TIMER_1 &htim3 // Special encoder timer which externally reads quadrature encoder ticks // #define QUADRATURE_TIMER_2 &htim4 -#define QUADRATURE_ELAPSED_TIMER_1 &htim17 // Measures time since the lsat quadrature tick reading -#define ABSOLUTE_ENCODER_TIMER &htim2 -// #define UPDATE_TIMER &htim6 -#define SEND_TIMER &htim7 // 20 Hz FDCAN repeating timer -#define PWM_TIMER_1 &htim15 // H-Bridge PWM -#define FDCAN_WATCHDOG_TIMER &htim16 // FDCAN watchdog timer that needs to be reset every time a message is received +#define QUADRATURE_ELAPSED_TIMER_1 &htim17 // Measures time since the lsat quadrature tick reading +#define ABSOLUTE_ENCODER_TIMER &htim2 // 20 Hz repeating timer to kick off I2C transactions with the absolute encoder +#define THROTTLE_LIMIT_TIMER &htim6 // Measures time since the last throttle command +#define SEND_TIMER &htim7 // 20 Hz FDCAN repeating timer +#define PIDF_TIMER &htim8 // Measures time since the last PIDF update, used for the "D" term +#define PWM_TIMER_1 &htim15 // H-Bridge PWM +#define FDCAN_WATCHDOG_TIMER &htim16 // FDCAN watchdog timer that needs to be reset every time a message is received namespace mrover { - // NOTE: Change This For Each Motor Controller - constexpr static std::uint8_t DEVICE_ID = 0x21; // currently set for joint_b - - // Usually this is the Jetson - constexpr static std::uint8_t DESTINATION_DEVICE_ID = 0x10; - FDCAN fdcan_bus; Controller controller; @@ -60,6 +55,8 @@ namespace mrover { FDCAN_WATCHDOG_TIMER, QUADRATURE_TICK_TIMER_1, QUADRATURE_ELAPSED_TIMER_1, + THROTTLE_LIMIT_TIMER, + PIDF_TIMER, ABSOLUTE_I2C, { LimitSwitch{Pin{LIMIT_0_0_GPIO_Port, LIMIT_0_0_Pin}}, @@ -71,7 +68,8 @@ namespace mrover { // TODO: these should probably be in the controller / encoders themselves // Necessary for the timer interrupt to work - // check(HAL_TIM_Base_Start_IT(UPDATE_TIMER) == HAL_OK, Error_Handler); + check(HAL_TIM_Base_Start(THROTTLE_LIMIT_TIMER) == HAL_OK, Error_Handler); + check(HAL_TIM_Base_Start(PIDF_TIMER) == HAL_OK, Error_Handler); check(HAL_TIM_Base_Start_IT(SEND_TIMER) == HAL_OK, Error_Handler); check(HAL_TIM_Base_Start_IT(ABSOLUTE_ENCODER_TIMER) == HAL_OK, Error_Handler); } @@ -155,7 +153,6 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef* htim) { } else if (htim == ABSOLUTE_ENCODER_TIMER) { mrover::request_absolute_encoder_data_callback(); } - // TODO: check for slow update timer and call on controller to send out i2c frame } void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef* htim) { @@ -176,13 +173,13 @@ void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef* hfdcan, uint32_t RxFifo0ITs) } } -// TODO: implement +// TODO(quintin): Error handling void HAL_FDCAN_ErrorCallback(FDCAN_HandleTypeDef* hfdcan) {} void HAL_FDCAN_ErrorStatusCallback(FDCAN_HandleTypeDef* hfdcan, uint32_t ErrorStatusITs) {} -// TODO DMA receive callback, this should eventually call a function on the controller with most up to date info +// TODO(quintin): Do we need these two callbacks? void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef* hi2c) {} diff --git a/src/esw/fw/bdcmc/Core/Src/encoders/absolute_encoder.cpp b/src/esw/fw/bdcmc/Core/Src/encoders/absolute_encoder.cpp index e6bbece34..404fec1a0 100644 --- a/src/esw/fw/bdcmc/Core/Src/encoders/absolute_encoder.cpp +++ b/src/esw/fw/bdcmc/Core/Src/encoders/absolute_encoder.cpp @@ -52,22 +52,27 @@ namespace mrover { return angle; } - auto wrapAngle(Radians angle) -> Radians { - constexpr Radians pi{std::numbers::pi}; - return Radians{fmod(angle + pi, tau) - pi}; + /** + * \return Wrapped angle in the range [-𝜏/2, 𝜏/2), same as [-π, π) + */ + auto wrap_angle(Radians angle) -> Radians { + constexpr Radians PI_F{std::numbers::pi}; + return fmod(angle + PI_F, TAU_F) - PI_F; } [[nodiscard]] auto AbsoluteEncoderReader::read() -> std::optional { if (std::optional count = try_read_buffer()) { - std::uint32_t elapsed_count = std::exchange(__HAL_TIM_GetCounter(m_elapsed_timer), 0); - Seconds elapsed_time = 1 / CLOCK_FREQ * elapsed_count; + Seconds elapsed_time = cycle_time(m_elapsed_timer, CLOCK_FREQ); - m_position = wrapAngle(m_multiplier * Ticks{count.value()} / ABSOLUTE_CPR + m_offset); - m_velocity_filter.add_reading((m_position - m_position_prev) / elapsed_time); + // Absolute encoder returns [0, COUNTS_PER_REVOLUTION) + // We need to convert this to [-𝜏/2, 𝜏/2) + // Angles always need to be wrapped after addition/subtraction + m_position = wrap_angle(m_multiplier * Ticks{count.value()} / ABSOLUTE_CPR + m_offset); + m_velocity_filter.add_reading(wrap_angle(m_position - m_position_prev) / elapsed_time); m_position_prev = m_position; } return std::make_optional(m_position, m_velocity_filter.get_filtered()); } -} // namespace mrover \ No newline at end of file +} // namespace mrover diff --git a/src/esw/fw/bdcmc/Core/Src/encoders/quadrature_encoder.cpp b/src/esw/fw/bdcmc/Core/Src/encoders/quadrature_encoder.cpp index 31cd7a42f..635f5593d 100644 --- a/src/esw/fw/bdcmc/Core/Src/encoders/quadrature_encoder.cpp +++ b/src/esw/fw/bdcmc/Core/Src/encoders/quadrature_encoder.cpp @@ -30,14 +30,14 @@ namespace mrover { std::uint32_t now = __HAL_TIM_GetCounter(timer); std::uint32_t max_value = __HAL_TIM_GetAutoreload(timer); - // adapted from: https://electronics.stackexchange.com/questions/605278/how-to-increase-stm32-timer-encoder-mode-counter-value - // handle when timer wraps around - std::int64_t c64 = static_cast(now) - max_value / 2; // remove half period to determine (+/-) sign of the wrap + // Adapted from: https://electronics.stackexchange.com/questions/605278/how-to-increase-stm32-timer-encoder-mode-counter-value + // Handles when the timer wraps around + std::int64_t c64 = static_cast(now) - max_value / 2; // Remove half period to determine (+/-) sign of the wrap std::int64_t dif = c64 - store; // prev + (current - prev) = current - // wrap difference from -HALF_PERIOD to HALF_PERIOD. modulo prevents differences after the wrap from having an incorrect result + // Wrap difference from -HALF_PERIOD to HALF_PERIOD. The modulo prevents differences after the wrap from having an incorrect result std::int64_t mod_dif = (dif + max_value / 2) % max_value - max_value / 2; - if (dif < -max_value / 2) mod_dif += max_value; // account for mod of negative number behavior in C + if (dif < -max_value / 2) mod_dif += max_value; // Account for the behavior of the modulo operator with negative numbers in C++ std::int64_t unwrapped = store + mod_dif; store = unwrapped; @@ -51,18 +51,13 @@ namespace mrover { } auto QuadratureEncoderReader::update() -> void { - std::uint32_t elapsed_count = std::exchange(__HAL_TIM_GetCounter(m_elapsed_timer), 0); + Seconds elapsed_time = cycle_time(m_elapsed_timer, CLOCK_FREQ); std::int64_t delta_ticks = count_delta(m_counts_unwrapped_prev, m_tick_timer); - - // if (delta_ticks == 0 || elapsed_count == 0) return; - Radians delta_angle = m_multiplier * Ticks{delta_ticks} / RELATIVE_CPR; - Seconds elapsed_time = 1 / CLOCK_FREQ * elapsed_count; m_position += delta_angle; // m_velocity = delta_angle / elapsed_time; m_velocity_filter.add_reading(delta_angle / elapsed_time); } - } // namespace mrover diff --git a/src/esw/fw/bdcmc/Core/Src/hbridge.cpp b/src/esw/fw/bdcmc/Core/Src/hbridge.cpp index 2ca1e595a..3e5f48e2c 100644 --- a/src/esw/fw/bdcmc/Core/Src/hbridge.cpp +++ b/src/esw/fw/bdcmc/Core/Src/hbridge.cpp @@ -5,9 +5,9 @@ namespace mrover { - HBridge::HBridge(TIM_HandleTypeDef* timer, Pin forward_pin, Pin reverse_pin) - : m_forward_pins{forward_pin}, - m_reverse_pins{reverse_pin}, + HBridge::HBridge(TIM_HandleTypeDef* timer, Pin positive_pin, Pin negative_pin) + : m_positive_pin{positive_pin}, + m_negative_pin{negative_pin}, m_timer{timer}, m_max_pwm{0_percent} { @@ -16,18 +16,22 @@ namespace mrover { HAL_TIM_PWM_Start(m_timer, m_channel); } - void HBridge::write(Percent output) const { + auto HBridge::write(Percent output) const -> void { // Set direction pins/duty cycle set_direction_pins(output); set_duty_cycle(output, m_max_pwm); } - void HBridge::set_direction_pins(Percent duty_cycle) const { - m_forward_pins.write(duty_cycle < 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET); - m_reverse_pins.write(duty_cycle > 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET); + auto HBridge::set_direction_pins(Percent duty_cycle) const -> void { + // TODO(quintin): Guthrie says only one of these pins is actually used? + GPIO_PinState positive_state = duty_cycle > 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET; + GPIO_PinState negative_state = duty_cycle < 0_percent ? GPIO_PIN_SET : GPIO_PIN_RESET; + if (m_is_inverted) std::swap(positive_state, negative_state); + m_positive_pin.write(positive_state); + m_negative_pin.write(negative_state); } - void HBridge::set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const { + auto HBridge::set_duty_cycle(Percent duty_cycle, Percent max_duty_cycle) const -> void { // Clamp absolute value of the duty cycle to the supported range duty_cycle = std::clamp(abs(duty_cycle), 0_percent, max_duty_cycle); @@ -39,8 +43,12 @@ namespace mrover { // TODO(quintin) we should error if the registers are null pointers } - void HBridge::change_max_pwm(Percent max_pwm) { + auto HBridge::change_max_pwm(Percent max_pwm) -> void { m_max_pwm = max_pwm; } + auto HBridge::change_inverted(bool inverted) -> void { + m_is_inverted = inverted; + } + } // namespace mrover \ No newline at end of file diff --git a/src/esw/fw/bdcmc/Core/Src/main.c b/src/esw/fw/bdcmc/Core/Src/main.c index f97d32762..f0f572550 100644 --- a/src/esw/fw/bdcmc/Core/Src/main.c +++ b/src/esw/fw/bdcmc/Core/Src/main.c @@ -47,11 +47,11 @@ I2C_HandleTypeDef hi2c1; DMA_HandleTypeDef hdma_i2c1_rx; DMA_HandleTypeDef hdma_i2c1_tx; -TIM_HandleTypeDef htim1; TIM_HandleTypeDef htim2; TIM_HandleTypeDef htim3; -TIM_HandleTypeDef htim4; +TIM_HandleTypeDef htim6; TIM_HandleTypeDef htim7; +TIM_HandleTypeDef htim8; TIM_HandleTypeDef htim15; TIM_HandleTypeDef htim16; TIM_HandleTypeDef htim17; @@ -67,13 +67,13 @@ static void MX_DMA_Init(void); static void MX_FDCAN1_Init(void); static void MX_I2C1_Init(void); static void MX_TIM15_Init(void); -static void MX_TIM4_Init(void); static void MX_TIM3_Init(void); static void MX_TIM7_Init(void); static void MX_TIM16_Init(void); static void MX_TIM2_Init(void); -static void MX_TIM1_Init(void); static void MX_TIM17_Init(void); +static void MX_TIM6_Init(void); +static void MX_TIM8_Init(void); /* USER CODE BEGIN PFP */ void HAL_PostInit(); /* USER CODE END PFP */ @@ -89,7 +89,6 @@ void HAL_PostInit(); */ int main(void) { - /* USER CODE BEGIN 1 */ /* USER CODE END 1 */ @@ -144,13 +143,13 @@ int main(void) MX_FDCAN1_Init(); MX_I2C1_Init(); MX_TIM15_Init(); - MX_TIM4_Init(); MX_TIM3_Init(); MX_TIM7_Init(); MX_TIM16_Init(); MX_TIM2_Init(); - MX_TIM1_Init(); MX_TIM17_Init(); + MX_TIM6_Init(); + MX_TIM8_Init(); /* USER CODE BEGIN 2 */ HAL_PostInit(); @@ -245,7 +244,7 @@ static void MX_FDCAN1_Init(void) hfdcan1.Init.DataTimeSeg1 = 14; hfdcan1.Init.DataTimeSeg2 = 13; hfdcan1.Init.StdFiltersNbr = 0; - hfdcan1.Init.ExtFiltersNbr = 0; + hfdcan1.Init.ExtFiltersNbr = 1; hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION; if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) { @@ -273,7 +272,7 @@ static void MX_I2C1_Init(void) /* USER CODE END I2C1_Init 1 */ hi2c1.Instance = I2C1; - hi2c1.Init.Timing = 0x20B0CCFF; + hi2c1.Init.Timing = 0x00D04BFF; hi2c1.Init.OwnAddress1 = 0; hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; @@ -305,78 +304,6 @@ static void MX_I2C1_Init(void) } -/** - * @brief TIM1 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM1_Init(void) -{ - - /* USER CODE BEGIN TIM1_Init 0 */ - - /* USER CODE END TIM1_Init 0 */ - - TIM_MasterConfigTypeDef sMasterConfig = {0}; - TIM_OC_InitTypeDef sConfigOC = {0}; - TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0}; - - /* USER CODE BEGIN TIM1_Init 1 */ - - /* USER CODE END TIM1_Init 1 */ - htim1.Instance = TIM1; - htim1.Init.Prescaler = 0; - htim1.Init.CounterMode = TIM_COUNTERMODE_UP; - htim1.Init.Period = 65535; - htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim1.Init.RepetitionCounter = 0; - htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_OC_Init(&htim1) != HAL_OK) - { - Error_Handler(); - } - sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET; - sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK) - { - Error_Handler(); - } - sConfigOC.OCMode = TIM_OCMODE_TIMING; - sConfigOC.Pulse = 0; - sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; - sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; - sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; - sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; - if (HAL_TIM_OC_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK) - { - Error_Handler(); - } - sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE; - sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE; - sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; - sBreakDeadTimeConfig.DeadTime = 0; - sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; - sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH; - sBreakDeadTimeConfig.BreakFilter = 0; - sBreakDeadTimeConfig.BreakAFMode = TIM_BREAK_AFMODE_INPUT; - sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE; - sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH; - sBreakDeadTimeConfig.Break2Filter = 0; - sBreakDeadTimeConfig.Break2AFMode = TIM_BREAK_AFMODE_INPUT; - sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; - if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK) - { - Error_Handler(); - } - /* USER CODE BEGIN TIM1_Init 2 */ - - /* USER CODE END TIM1_Init 2 */ - HAL_TIM_MspPostInit(&htim1); - -} - /** * @brief TIM2 Initialization Function * @param None @@ -472,51 +399,40 @@ static void MX_TIM3_Init(void) } /** - * @brief TIM4 Initialization Function + * @brief TIM6 Initialization Function * @param None * @retval None */ -static void MX_TIM4_Init(void) +static void MX_TIM6_Init(void) { - /* USER CODE BEGIN TIM4_Init 0 */ + /* USER CODE BEGIN TIM6_Init 0 */ - /* USER CODE END TIM4_Init 0 */ + /* USER CODE END TIM6_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = {0}; TIM_MasterConfigTypeDef sMasterConfig = {0}; - /* USER CODE BEGIN TIM4_Init 1 */ + /* USER CODE BEGIN TIM6_Init 1 */ - /* USER CODE END TIM4_Init 1 */ - htim4.Instance = TIM4; - htim4.Init.Prescaler = 0; - htim4.Init.CounterMode = TIM_COUNTERMODE_UP; - htim4.Init.Period = 65535; - htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - sConfig.EncoderMode = TIM_ENCODERMODE_TI1; - sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; - sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; - sConfig.IC1Prescaler = TIM_ICPSC_DIV1; - sConfig.IC1Filter = 0; - sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; - sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; - sConfig.IC2Prescaler = TIM_ICPSC_DIV1; - sConfig.IC2Filter = 0; - if (HAL_TIM_Encoder_Init(&htim4, &sConfig) != HAL_OK) + /* USER CODE END TIM6_Init 1 */ + htim6.Instance = TIM6; + htim6.Init.Prescaler = 0; + htim6.Init.CounterMode = TIM_COUNTERMODE_UP; + htim6.Init.Period = 65535; + htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) { Error_Handler(); } - /* USER CODE BEGIN TIM4_Init 2 */ + /* USER CODE BEGIN TIM6_Init 2 */ - /* USER CODE END TIM4_Init 2 */ + /* USER CODE END TIM6_Init 2 */ } @@ -558,6 +474,53 @@ static void MX_TIM7_Init(void) } +/** + * @brief TIM8 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM8_Init(void) +{ + + /* USER CODE BEGIN TIM8_Init 0 */ + + /* USER CODE END TIM8_Init 0 */ + + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; + + /* USER CODE BEGIN TIM8_Init 1 */ + + /* USER CODE END TIM8_Init 1 */ + htim8.Instance = TIM8; + htim8.Init.Prescaler = 0; + htim8.Init.CounterMode = TIM_COUNTERMODE_UP; + htim8.Init.Period = 65535; + htim8.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim8.Init.RepetitionCounter = 0; + htim8.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_Base_Init(&htim8) != HAL_OK) + { + Error_Handler(); + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + if (HAL_TIM_ConfigClockSource(&htim8, &sClockSourceConfig) != HAL_OK) + { + Error_Handler(); + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim8, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN TIM8_Init 2 */ + + /* USER CODE END TIM8_Init 2 */ + +} + /** * @brief TIM15 Initialization Function * @param None @@ -767,13 +730,13 @@ static void MX_GPIO_Init(void) /*Configure GPIO pins : LIMIT_0_0_Pin LIMIT_0_1_Pin LIMIT_0_2_Pin LIMIT_1_0_Pin */ GPIO_InitStruct.Pin = LIMIT_0_0_Pin|LIMIT_0_1_Pin|LIMIT_0_2_Pin|LIMIT_1_0_Pin; GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Pull = GPIO_PULLUP; HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); /*Configure GPIO pin : LIMIT_0_3_Pin */ GPIO_InitStruct.Pin = LIMIT_0_3_Pin; GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Pull = GPIO_PULLUP; HAL_GPIO_Init(LIMIT_0_3_GPIO_Port, &GPIO_InitStruct); /*Configure GPIO pins : DEBUG_LED_0_Pin DEBUG_LED_1_Pin DEBUG_LED_2_Pin CAN_STANDBY_Pin */ @@ -786,7 +749,7 @@ static void MX_GPIO_Init(void) /*Configure GPIO pins : LIMIT_1_1_Pin LIMIT_1_2_Pin LIMIT_1_3_Pin */ GPIO_InitStruct.Pin = LIMIT_1_1_Pin|LIMIT_1_2_Pin|LIMIT_1_3_Pin; GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Pull = GPIO_PULLUP; HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); /*Configure GPIO pin : MOTOR_0_DIR_Pin */ diff --git a/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c b/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c index 58f0e8501..eb37487cb 100644 --- a/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c +++ b/src/esw/fw/bdcmc/Core/Src/stm32g4xx_hal_msp.c @@ -20,6 +20,7 @@ /* Includes ------------------------------------------------------------------*/ #include "main.h" + /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ @@ -62,12 +63,11 @@ extern DMA_HandleTypeDef hdma_i2c1_tx; /* USER CODE END 0 */ void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); - /** + /** * Initializes the Global MSP. */ void HAL_MspInit(void) { - /* USER CODE BEGIN MspInit 0 */ /* USER CODE END MspInit 0 */ @@ -204,6 +204,10 @@ void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c) GPIO_InitStruct.Alternate = GPIO_AF4_I2C1; HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + __HAL_SYSCFG_FASTMODEPLUS_ENABLE(SYSCFG_FASTMODEPLUS_PB8); + + __HAL_SYSCFG_FASTMODEPLUS_ENABLE(SYSCFG_FASTMODEPLUS_PB9); + /* Peripheral clock enable */ __HAL_RCC_I2C1_CLK_ENABLE(); @@ -292,33 +296,6 @@ void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c) } -/** -* @brief TIM_OC MSP Initialization -* This function configures the hardware resources used in this example -* @param htim_oc: TIM_OC handle pointer -* @retval None -*/ -void HAL_TIM_OC_MspInit(TIM_HandleTypeDef* htim_oc) -{ - if(htim_oc->Instance==TIM1) - { - /* USER CODE BEGIN TIM1_MspInit 0 */ - - /* USER CODE END TIM1_MspInit 0 */ - /* Peripheral clock enable */ - __HAL_RCC_TIM1_CLK_ENABLE(); - /* TIM1 interrupt Init */ - HAL_NVIC_SetPriority(TIM1_UP_TIM16_IRQn, 1, 0); - HAL_NVIC_EnableIRQ(TIM1_UP_TIM16_IRQn); - HAL_NVIC_SetPriority(TIM1_TRG_COM_TIM17_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(TIM1_TRG_COM_TIM17_IRQn); - /* USER CODE BEGIN TIM1_MspInit 1 */ - - /* USER CODE END TIM1_MspInit 1 */ - } - -} - /** * @brief TIM_Base MSP Initialization * This function configures the hardware resources used in this example @@ -341,6 +318,20 @@ void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base) /* USER CODE END TIM2_MspInit 1 */ } + else if(htim_base->Instance==TIM6) + { + /* USER CODE BEGIN TIM6_MspInit 0 */ + + /* USER CODE END TIM6_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM6_CLK_ENABLE(); + /* TIM6 interrupt Init */ + HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn); + /* USER CODE BEGIN TIM6_MspInit 1 */ + + /* USER CODE END TIM6_MspInit 1 */ + } else if(htim_base->Instance==TIM7) { /* USER CODE BEGIN TIM7_MspInit 0 */ @@ -355,6 +346,17 @@ void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base) /* USER CODE END TIM7_MspInit 1 */ } + else if(htim_base->Instance==TIM8) + { + /* USER CODE BEGIN TIM8_MspInit 0 */ + + /* USER CODE END TIM8_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM8_CLK_ENABLE(); + /* USER CODE BEGIN TIM8_MspInit 1 */ + + /* USER CODE END TIM8_MspInit 1 */ + } else if(htim_base->Instance==TIM16) { /* USER CODE BEGIN TIM16_MspInit 0 */ @@ -419,30 +421,6 @@ void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* htim_encoder) /* USER CODE END TIM3_MspInit 1 */ } - else if(htim_encoder->Instance==TIM4) - { - /* USER CODE BEGIN TIM4_MspInit 0 */ - - /* USER CODE END TIM4_MspInit 0 */ - /* Peripheral clock enable */ - __HAL_RCC_TIM4_CLK_ENABLE(); - - __HAL_RCC_GPIOB_CLK_ENABLE(); - /**TIM4 GPIO Configuration - PB6 ------> TIM4_CH1 - PB7 ------> TIM4_CH2 - */ - GPIO_InitStruct.Pin = QUAD_0_A_Pin|QUAD_0_B_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct.Alternate = GPIO_AF2_TIM4; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - /* USER CODE BEGIN TIM4_MspInit 1 */ - - /* USER CODE END TIM4_MspInit 1 */ - } } @@ -471,27 +449,7 @@ void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm) void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) { GPIO_InitTypeDef GPIO_InitStruct = {0}; - if(htim->Instance==TIM1) - { - /* USER CODE BEGIN TIM1_MspPostInit 0 */ - - /* USER CODE END TIM1_MspPostInit 0 */ - __HAL_RCC_GPIOA_CLK_ENABLE(); - /**TIM1 GPIO Configuration - PA8 ------> TIM1_CH1 - */ - GPIO_InitStruct.Pin = MOTOR_1_PWM_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct.Alternate = GPIO_AF6_TIM1; - HAL_GPIO_Init(MOTOR_1_PWM_GPIO_Port, &GPIO_InitStruct); - - /* USER CODE BEGIN TIM1_MspPostInit 1 */ - - /* USER CODE END TIM1_MspPostInit 1 */ - } - else if(htim->Instance==TIM15) + if(htim->Instance==TIM15) { /* USER CODE BEGIN TIM15_MspPostInit 0 */ @@ -514,46 +472,6 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) } } -/** -* @brief TIM_OC MSP De-Initialization -* This function freeze the hardware resources used in this example -* @param htim_oc: TIM_OC handle pointer -* @retval None -*/ -void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef* htim_oc) -{ - if(htim_oc->Instance==TIM1) - { - /* USER CODE BEGIN TIM1_MspDeInit 0 */ - - /* USER CODE END TIM1_MspDeInit 0 */ - /* Peripheral clock disable */ - __HAL_RCC_TIM1_CLK_DISABLE(); - - /* TIM1 interrupt DeInit */ - /* USER CODE BEGIN TIM1:TIM1_UP_TIM16_IRQn disable */ - /** - * Uncomment the line below to disable the "TIM1_UP_TIM16_IRQn" interrupt - * Be aware, disabling shared interrupt may affect other IPs - */ - /* HAL_NVIC_DisableIRQ(TIM1_UP_TIM16_IRQn); */ - /* USER CODE END TIM1:TIM1_UP_TIM16_IRQn disable */ - - /* USER CODE BEGIN TIM1:TIM1_TRG_COM_TIM17_IRQn disable */ - /** - * Uncomment the line below to disable the "TIM1_TRG_COM_TIM17_IRQn" interrupt - * Be aware, disabling shared interrupt may affect other IPs - */ - /* HAL_NVIC_DisableIRQ(TIM1_TRG_COM_TIM17_IRQn); */ - /* USER CODE END TIM1:TIM1_TRG_COM_TIM17_IRQn disable */ - - /* USER CODE BEGIN TIM1_MspDeInit 1 */ - - /* USER CODE END TIM1_MspDeInit 1 */ - } - -} - /** * @brief TIM_Base MSP De-Initialization * This function freeze the hardware resources used in this example @@ -576,6 +494,20 @@ void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base) /* USER CODE END TIM2_MspDeInit 1 */ } + else if(htim_base->Instance==TIM6) + { + /* USER CODE BEGIN TIM6_MspDeInit 0 */ + + /* USER CODE END TIM6_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM6_CLK_DISABLE(); + + /* TIM6 interrupt DeInit */ + HAL_NVIC_DisableIRQ(TIM6_DAC_IRQn); + /* USER CODE BEGIN TIM6_MspDeInit 1 */ + + /* USER CODE END TIM6_MspDeInit 1 */ + } else if(htim_base->Instance==TIM7) { /* USER CODE BEGIN TIM7_MspDeInit 0 */ @@ -590,6 +522,17 @@ void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base) /* USER CODE END TIM7_MspDeInit 1 */ } + else if(htim_base->Instance==TIM8) + { + /* USER CODE BEGIN TIM8_MspDeInit 0 */ + + /* USER CODE END TIM8_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM8_CLK_DISABLE(); + /* USER CODE BEGIN TIM8_MspDeInit 1 */ + + /* USER CODE END TIM8_MspDeInit 1 */ + } else if(htim_base->Instance==TIM16) { /* USER CODE BEGIN TIM16_MspDeInit 0 */ @@ -599,14 +542,7 @@ void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base) __HAL_RCC_TIM16_CLK_DISABLE(); /* TIM16 interrupt DeInit */ - /* USER CODE BEGIN TIM16:TIM1_UP_TIM16_IRQn disable */ - /** - * Uncomment the line below to disable the "TIM1_UP_TIM16_IRQn" interrupt - * Be aware, disabling shared interrupt may affect other IPs - */ - /* HAL_NVIC_DisableIRQ(TIM1_UP_TIM16_IRQn); */ - /* USER CODE END TIM16:TIM1_UP_TIM16_IRQn disable */ - + HAL_NVIC_DisableIRQ(TIM1_UP_TIM16_IRQn); /* USER CODE BEGIN TIM16_MspDeInit 1 */ /* USER CODE END TIM16_MspDeInit 1 */ @@ -620,14 +556,7 @@ void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base) __HAL_RCC_TIM17_CLK_DISABLE(); /* TIM17 interrupt DeInit */ - /* USER CODE BEGIN TIM17:TIM1_TRG_COM_TIM17_IRQn disable */ - /** - * Uncomment the line below to disable the "TIM1_TRG_COM_TIM17_IRQn" interrupt - * Be aware, disabling shared interrupt may affect other IPs - */ - /* HAL_NVIC_DisableIRQ(TIM1_TRG_COM_TIM17_IRQn); */ - /* USER CODE END TIM17:TIM1_TRG_COM_TIM17_IRQn disable */ - + HAL_NVIC_DisableIRQ(TIM1_TRG_COM_TIM17_IRQn); /* USER CODE BEGIN TIM17_MspDeInit 1 */ /* USER CODE END TIM17_MspDeInit 1 */ @@ -661,24 +590,6 @@ void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* htim_encoder) /* USER CODE END TIM3_MspDeInit 1 */ } - else if(htim_encoder->Instance==TIM4) - { - /* USER CODE BEGIN TIM4_MspDeInit 0 */ - - /* USER CODE END TIM4_MspDeInit 0 */ - /* Peripheral clock disable */ - __HAL_RCC_TIM4_CLK_DISABLE(); - - /**TIM4 GPIO Configuration - PB6 ------> TIM4_CH1 - PB7 ------> TIM4_CH2 - */ - HAL_GPIO_DeInit(GPIOB, QUAD_0_A_Pin|QUAD_0_B_Pin); - - /* USER CODE BEGIN TIM4_MspDeInit 1 */ - - /* USER CODE END TIM4_MspDeInit 1 */ - } } diff --git a/src/esw/fw/bdcmc/Core/Src/stm32g4xx_it.c b/src/esw/fw/bdcmc/Core/Src/stm32g4xx_it.c index 1fafa705a..eabb9dc4f 100644 --- a/src/esw/fw/bdcmc/Core/Src/stm32g4xx_it.c +++ b/src/esw/fw/bdcmc/Core/Src/stm32g4xx_it.c @@ -59,8 +59,8 @@ extern FDCAN_HandleTypeDef hfdcan1; extern DMA_HandleTypeDef hdma_i2c1_rx; extern DMA_HandleTypeDef hdma_i2c1_tx; extern I2C_HandleTypeDef hi2c1; -extern TIM_HandleTypeDef htim1; extern TIM_HandleTypeDef htim2; +extern TIM_HandleTypeDef htim6; extern TIM_HandleTypeDef htim7; extern TIM_HandleTypeDef htim16; extern TIM_HandleTypeDef htim17; @@ -256,7 +256,6 @@ void TIM1_UP_TIM16_IRQHandler(void) /* USER CODE BEGIN TIM1_UP_TIM16_IRQn 0 */ /* USER CODE END TIM1_UP_TIM16_IRQn 0 */ - HAL_TIM_IRQHandler(&htim1); HAL_TIM_IRQHandler(&htim16); /* USER CODE BEGIN TIM1_UP_TIM16_IRQn 1 */ @@ -271,7 +270,6 @@ void TIM1_TRG_COM_TIM17_IRQHandler(void) /* USER CODE BEGIN TIM1_TRG_COM_TIM17_IRQn 0 */ /* USER CODE END TIM1_TRG_COM_TIM17_IRQn 0 */ - HAL_TIM_IRQHandler(&htim1); HAL_TIM_IRQHandler(&htim17); /* USER CODE BEGIN TIM1_TRG_COM_TIM17_IRQn 1 */ @@ -320,6 +318,20 @@ void I2C1_ER_IRQHandler(void) /* USER CODE END I2C1_ER_IRQn 1 */ } +/** + * @brief This function handles TIM6 global interrupt, DAC1 and DAC3 channel underrun error interrupts. + */ +void TIM6_DAC_IRQHandler(void) +{ + /* USER CODE BEGIN TIM6_DAC_IRQn 0 */ + + /* USER CODE END TIM6_DAC_IRQn 0 */ + HAL_TIM_IRQHandler(&htim6); + /* USER CODE BEGIN TIM6_DAC_IRQn 1 */ + + /* USER CODE END TIM6_DAC_IRQn 1 */ +} + /** * @brief This function handles TIM7 global interrupt. */ diff --git a/src/esw/fw/bdcmc/bdcmc.ioc b/src/esw/fw/bdcmc/bdcmc.ioc index 8cc6a75ca..df4ab75e2 100644 --- a/src/esw/fw/bdcmc/bdcmc.ioc +++ b/src/esw/fw/bdcmc/bdcmc.ioc @@ -47,22 +47,24 @@ FDCAN1.DataPrescaler=1 FDCAN1.DataSyncJumpWidth=13 FDCAN1.DataTimeSeg1=14 FDCAN1.DataTimeSeg2=13 +FDCAN1.ExtFiltersNbr=1 FDCAN1.FrameFormat=FDCAN_FRAME_FD_NO_BRS -FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,NominalSyncJumpWidth,DataPrescaler,DataSyncJumpWidth,DataTimeSeg1,DataTimeSeg2,NominalPrescaler,NominalTimeSeg1,NominalTimeSeg2,Mode,AutoRetransmission +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,NominalSyncJumpWidth,DataPrescaler,DataSyncJumpWidth,DataTimeSeg1,DataTimeSeg2,NominalPrescaler,NominalTimeSeg1,NominalTimeSeg2,Mode,AutoRetransmission,ExtFiltersNbr FDCAN1.Mode=FDCAN_MODE_NORMAL FDCAN1.NominalPrescaler=1 FDCAN1.NominalSyncJumpWidth=19 FDCAN1.NominalTimeSeg1=120 FDCAN1.NominalTimeSeg2=19 File.Version=6 -I2C1.IPParameters=Timing -I2C1.Timing=0x20B0CCFF +I2C1.I2C_Speed_Mode=I2C_Fast +I2C1.IPParameters=Timing,I2C_Speed_Mode +I2C1.Timing=0x00D04BFF KeepUserPlacement=false Mcu.CPN=STM32G431CBU3 Mcu.Family=STM32G4 Mcu.IP0=DMA Mcu.IP1=FDCAN1 -Mcu.IP10=TIM7 +Mcu.IP10=TIM8 Mcu.IP11=TIM15 Mcu.IP12=TIM16 Mcu.IP13=TIM17 @@ -70,10 +72,10 @@ Mcu.IP2=I2C1 Mcu.IP3=NVIC Mcu.IP4=RCC Mcu.IP5=SYS -Mcu.IP6=TIM1 -Mcu.IP7=TIM2 -Mcu.IP8=TIM3 -Mcu.IP9=TIM4 +Mcu.IP6=TIM2 +Mcu.IP7=TIM3 +Mcu.IP8=TIM6 +Mcu.IP9=TIM7 Mcu.IPNb=14 Mcu.Name=STM32G431C(6-8-B)Ux Mcu.Package=UFQFPN48 @@ -85,37 +87,36 @@ Mcu.Pin12=PB2 Mcu.Pin13=PB14 Mcu.Pin14=PB15 Mcu.Pin15=PC6 -Mcu.Pin16=PA8 -Mcu.Pin17=PA11 -Mcu.Pin18=PA12 -Mcu.Pin19=PA13 +Mcu.Pin16=PA11 +Mcu.Pin17=PA12 +Mcu.Pin18=PA13 +Mcu.Pin19=PA14 Mcu.Pin2=PC15-OSC32_OUT -Mcu.Pin20=PA14 -Mcu.Pin21=PA15 -Mcu.Pin22=PB6 -Mcu.Pin23=PB7 -Mcu.Pin24=PB8-BOOT0 -Mcu.Pin25=PB9 -Mcu.Pin26=VP_SYS_VS_Systick -Mcu.Pin27=VP_SYS_VS_DBSignals -Mcu.Pin28=VP_TIM2_VS_ClockSourceINT -Mcu.Pin29=VP_TIM7_VS_ClockSourceINT +Mcu.Pin20=PA15 +Mcu.Pin21=PB8-BOOT0 +Mcu.Pin22=PB9 +Mcu.Pin23=VP_SYS_VS_Systick +Mcu.Pin24=VP_SYS_VS_DBSignals +Mcu.Pin25=VP_TIM2_VS_ClockSourceINT +Mcu.Pin26=VP_TIM6_VS_ClockSourceINT +Mcu.Pin27=VP_TIM7_VS_ClockSourceINT +Mcu.Pin28=VP_TIM8_VS_ClockSourceINT +Mcu.Pin29=VP_TIM16_VS_ClockSourceINT Mcu.Pin3=PF0-OSC_IN -Mcu.Pin30=VP_TIM16_VS_ClockSourceINT -Mcu.Pin31=VP_TIM17_VS_ClockSourceINT -Mcu.Pin32=VP_TIM17_VS_no_output1 +Mcu.Pin30=VP_TIM17_VS_ClockSourceINT +Mcu.Pin31=VP_TIM17_VS_no_output1 Mcu.Pin4=PA1 Mcu.Pin5=PA2 Mcu.Pin6=PA3 Mcu.Pin7=PA4 Mcu.Pin8=PA6 Mcu.Pin9=PC4 -Mcu.PinsNb=33 +Mcu.PinsNb=32 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32G431CBUx -MxCube.Version=6.11.0 -MxDb.Version=DB.6.0.110 +MxCube.Version=6.10.0 +MxDb.Version=DB.6.0.100 NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.DMA1_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true NVIC.DMA1_Channel2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true @@ -134,6 +135,7 @@ NVIC.SysTick_IRQn=true\:0\:0\:true\:false\:true\:false\:true\:false NVIC.TIM1_TRG_COM_TIM17_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true NVIC.TIM1_UP_TIM16_IRQn=true\:1\:0\:true\:false\:true\:true\:true\:true NVIC.TIM2_IRQn=true\:1\:0\:true\:false\:true\:true\:true\:true +NVIC.TIM6_DAC_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true NVIC.TIM7_IRQn=true\:1\:0\:true\:false\:true\:true\:true\:true NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false PA1.GPIOParameters=GPIO_Label @@ -171,15 +173,14 @@ PA4.Signal=S_TIM3_CH2 PA6.GPIOParameters=GPIO_Label PA6.GPIO_Label=QUAD 1 A PA6.Signal=S_TIM3_CH1 -PA8.GPIOParameters=GPIO_Label -PA8.GPIO_Label=MOTOR 1 PWM -PA8.Signal=S_TIM1_CH1 -PB0.GPIOParameters=GPIO_Label +PB0.GPIOParameters=GPIO_PuPd,GPIO_Label PB0.GPIO_Label=LIMIT 1-1 +PB0.GPIO_PuPd=GPIO_PULLUP PB0.Locked=true PB0.Signal=GPIO_Input -PB1.GPIOParameters=GPIO_Label +PB1.GPIOParameters=GPIO_PuPd,GPIO_Label PB1.GPIO_Label=LIMIT 1-2 +PB1.GPIO_PuPd=GPIO_PULLUP PB1.Locked=true PB1.Signal=GPIO_Input PB14.GPIOParameters=GPIO_Label @@ -190,49 +191,51 @@ PB15.GPIOParameters=GPIO_Label PB15.GPIO_Label=MOTOR 0 DIR PB15.Locked=true PB15.Signal=GPIO_Output -PB2.GPIOParameters=GPIO_Label +PB2.GPIOParameters=GPIO_PuPd,GPIO_Label PB2.GPIO_Label=LIMIT 1-3 +PB2.GPIO_PuPd=GPIO_PULLUP PB2.Locked=true PB2.Signal=GPIO_Input -PB6.GPIOParameters=GPIO_Label -PB6.GPIO_Label=QUAD 0 A -PB6.Signal=S_TIM4_CH1 -PB7.GPIOParameters=GPIO_Label -PB7.GPIO_Label=QUAD 0 B -PB7.Signal=S_TIM4_CH2 -PB8-BOOT0.GPIOParameters=GPIO_Speed,GPIO_Pu +PB8-BOOT0.GPIOParameters=GPIO_Speed,GPIO_FM8,GPIO_Pu +PB8-BOOT0.GPIO_FM8=SYSCFG_FASTMODEPLUS_PB8 PB8-BOOT0.GPIO_Pu=GPIO_NOPULL PB8-BOOT0.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH PB8-BOOT0.Locked=true PB8-BOOT0.Mode=I2C PB8-BOOT0.Signal=I2C1_SCL -PB9.GPIOParameters=GPIO_Speed,GPIO_Pu +PB9.GPIOParameters=GPIO_Speed,GPIO_Pu,GPIO_FM9 +PB9.GPIO_FM9=SYSCFG_FASTMODEPLUS_PB9 PB9.GPIO_Pu=GPIO_NOPULL PB9.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH PB9.Mode=I2C PB9.Signal=I2C1_SDA -PC13.GPIOParameters=GPIO_Label +PC13.GPIOParameters=GPIO_PuPd,GPIO_Label PC13.GPIO_Label=LIMIT 0-0 +PC13.GPIO_PuPd=GPIO_PULLUP PC13.Locked=true PC13.Signal=GPIO_Input -PC14-OSC32_IN.GPIOParameters=GPIO_Label +PC14-OSC32_IN.GPIOParameters=GPIO_PuPd,GPIO_Label PC14-OSC32_IN.GPIO_Label=LIMIT 0-1 +PC14-OSC32_IN.GPIO_PuPd=GPIO_PULLUP PC14-OSC32_IN.Locked=true PC14-OSC32_IN.Signal=GPIO_Input -PC15-OSC32_OUT.GPIOParameters=GPIO_Label +PC15-OSC32_OUT.GPIOParameters=GPIO_PuPd,GPIO_Label PC15-OSC32_OUT.GPIO_Label=LIMIT 0-2 +PC15-OSC32_OUT.GPIO_PuPd=GPIO_PULLUP PC15-OSC32_OUT.Locked=true PC15-OSC32_OUT.Signal=GPIO_Input -PC4.GPIOParameters=GPIO_Label +PC4.GPIOParameters=GPIO_PuPd,GPIO_Label PC4.GPIO_Label=LIMIT 1-0 +PC4.GPIO_PuPd=GPIO_PULLUP PC4.Locked=true PC4.Signal=GPIO_Input PC6.GPIOParameters=GPIO_Label PC6.GPIO_Label=MOTOR 1 DIR PC6.Locked=true PC6.Signal=GPIO_Output -PF0-OSC_IN.GPIOParameters=GPIO_Label +PF0-OSC_IN.GPIOParameters=GPIO_PuPd,GPIO_Label PF0-OSC_IN.GPIO_Label=LIMIT 0-3 +PF0-OSC_IN.GPIO_PuPd=GPIO_PULLUP PF0-OSC_IN.Locked=true PF0-OSC_IN.Signal=GPIO_Input PinOutPanel.RotationAngle=0 @@ -266,7 +269,7 @@ ProjectManager.ToolChainLocation= ProjectManager.UAScriptAfterPath= ProjectManager.UAScriptBeforePath= ProjectManager.UnderRoot=true -ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_FDCAN1_Init-FDCAN1-false-HAL-true,5-MX_I2C1_Init-I2C1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,7-MX_TIM4_Init-TIM4-false-HAL-true,8-MX_TIM3_Init-TIM3-false-HAL-true,9-MX_TIM7_Init-TIM7-false-HAL-true,10-MX_TIM16_Init-TIM16-false-HAL-true,11-MX_TIM2_Init-TIM2-false-HAL-true,12-MX_TIM1_Init-TIM1-false-HAL-true,13-MX_TIM17_Init-TIM17-false-HAL-true +ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_FDCAN1_Init-FDCAN1-false-HAL-true,5-MX_I2C1_Init-I2C1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,7-MX_TIM3_Init-TIM3-false-HAL-true,8-MX_TIM7_Init-TIM7-false-HAL-true,9-MX_TIM16_Init-TIM16-false-HAL-true,10-MX_TIM2_Init-TIM2-false-HAL-true,11-MX_TIM17_Init-TIM17-false-HAL-true,12-MX_TIM6_Init-TIM6-false-HAL-true,13-MX_TIM8_Init-TIM8-false-HAL-true RCC.ADC12Freq_Value=140000000 RCC.AHBFreq_Value=140000000 RCC.APB1Freq_Value=140000000 @@ -313,18 +316,10 @@ RCC.VCOInputFreq_Value=8000000 RCC.VCOOutputFreq_Value=280000000 SH.S_TIM15_CH1.0=TIM15_CH1,PWM Generation1 CH1 SH.S_TIM15_CH1.ConfNb=1 -SH.S_TIM1_CH1.0=TIM1_CH1,Output Compare1 CH1 -SH.S_TIM1_CH1.ConfNb=1 SH.S_TIM3_CH1.0=TIM3_CH1,Encoder_Interface SH.S_TIM3_CH1.ConfNb=1 SH.S_TIM3_CH2.0=TIM3_CH2,Encoder_Interface SH.S_TIM3_CH2.ConfNb=1 -SH.S_TIM4_CH1.0=TIM4_CH1,Encoder_Interface -SH.S_TIM4_CH1.ConfNb=1 -SH.S_TIM4_CH2.0=TIM4_CH2,Encoder_Interface -SH.S_TIM4_CH2.ConfNb=1 -TIM1.Channel-Output\ Compare1\ CH1=TIM_CHANNEL_1 -TIM1.IPParameters=Channel-Output Compare1 CH1 TIM15.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 TIM15.IPParameters=Prescaler,PeriodNoDither,Channel-PWM Generation1 CH1 TIM15.PeriodNoDither=99 @@ -354,7 +349,11 @@ VP_TIM17_VS_no_output1.Mode=Output Compare1 No Output VP_TIM17_VS_no_output1.Signal=TIM17_VS_no_output1 VP_TIM2_VS_ClockSourceINT.Mode=Internal VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT +VP_TIM6_VS_ClockSourceINT.Mode=Enable_Timer +VP_TIM6_VS_ClockSourceINT.Signal=TIM6_VS_ClockSourceINT VP_TIM7_VS_ClockSourceINT.Mode=Enable_Timer VP_TIM7_VS_ClockSourceINT.Signal=TIM7_VS_ClockSourceINT +VP_TIM8_VS_ClockSourceINT.Mode=Internal +VP_TIM8_VS_ClockSourceINT.Signal=TIM8_VS_ClockSourceINT board=custom isbadioc=false diff --git a/src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino b/src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino index da8cbf0b0..b6b227b0b 100644 --- a/src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino +++ b/src/esw/fw/dirt_sensor/dirt_sensor_ros/dirt_sensor_ros.ino @@ -1,5 +1,5 @@ -#include #include +#include #include #include @@ -14,11 +14,11 @@ ros::Publisher humidity_pub("sa_humidity_data", &humidity_data); DFRobot_SHT20 sht20(&Wire, SHT20_I2C_ADDR); void setup(){ - + nh.getHardware()->setBaud(57600); // Have to set this parameter nh.initNode(); nh.advertise(temperature_pub); nh.advertise(humidity_pub); - + //Serial.begin(9600); sht20.initSHT20(); delay(100); } @@ -27,6 +27,12 @@ void loop(){ float temp = sht20.readTemperature(); float humidity = sht20.readHumidity() / 100.0; +/* + Serial.print(temp); + Serial.print(" "); + Serial.print(humidity); + Serial.print("\n"); + */ temperature_data.temperature = temp; temperature_pub.publish(&temperature_data); diff --git a/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp b/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp index 151f77556..39e9ccd85 100644 --- a/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp +++ b/src/esw/fw/pdlb/Core/Inc/diag_temp_sensor.hpp @@ -9,6 +9,8 @@ #include #include +// TMP6431DECR + namespace mrover { class DiagTempSensor { diff --git a/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp b/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp index 8c7bcd597..f3f2a4c95 100644 --- a/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp +++ b/src/esw/fw/pdlb/Core/Src/diag_temp_sensor.cpp @@ -5,6 +5,8 @@ #include +// TMP6431DECR + namespace mrover { constexpr static float DIAG_TEMP_COEFFICIENT = 0.0064f; @@ -23,6 +25,7 @@ namespace mrover { void DiagTempSensor::update_temp() { uint16_t adc_val = m_adc_sensor->get_raw_channel_value(m_channel); float measured_volts = (adc_val * 3.3f) / 4096.0f; + m_temp = (THRM_A4 * powf(measured_volts,4)) + (THRM_A3 * powf(measured_volts,3)) + (THRM_A2 * powf(measured_volts,2)) + (THRM_A1 * measured_volts) + THRM_A0; } diff --git a/src/esw/fw/pdlb/Core/Src/main.c b/src/esw/fw/pdlb/Core/Src/main.c index 10d641360..98a6fe28c 100644 --- a/src/esw/fw/pdlb/Core/Src/main.c +++ b/src/esw/fw/pdlb/Core/Src/main.c @@ -205,6 +205,7 @@ int main(void) /* Start scheduler */ osKernelStart(); + /* We should never get here as control is now taken by the scheduler */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ @@ -317,7 +318,7 @@ static void MX_ADC1_Init(void) */ sConfig.Channel = ADC_CHANNEL_1; sConfig.Rank = ADC_REGULAR_RANK_1; - sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5; + sConfig.SamplingTime = ADC_SAMPLETIME_12CYCLES_5; sConfig.SingleDiff = ADC_SINGLE_ENDED; sConfig.OffsetNumber = ADC_OFFSET_NONE; sConfig.Offset = 0; @@ -457,7 +458,7 @@ static void MX_ADC2_Init(void) */ sConfig.Channel = ADC_CHANNEL_10; sConfig.Rank = ADC_REGULAR_RANK_1; - sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5; + sConfig.SamplingTime = ADC_SAMPLETIME_640CYCLES_5; sConfig.SingleDiff = ADC_SINGLE_ENDED; sConfig.OffsetNumber = ADC_OFFSET_NONE; sConfig.Offset = 0; @@ -511,7 +512,7 @@ static void MX_FDCAN1_Init(void) hfdcan1.Init.DataTimeSeg1 = 14; hfdcan1.Init.DataTimeSeg2 = 13; hfdcan1.Init.StdFiltersNbr = 0; - hfdcan1.Init.ExtFiltersNbr = 0; + hfdcan1.Init.ExtFiltersNbr = 1; hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION; if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) { @@ -624,7 +625,7 @@ void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs) void SendCurrentTemperature(void* argument) { for(;;) { - uint32_t tick = osKernelGetTickCount() + osKernelGetTickFreq(); // 1 Hz + uint32_t tick = osKernelGetTickCount() + (osKernelGetTickFreq() / 10.0); // 10 Hz update_and_send_current_temp(); osDelayUntil(tick); diff --git a/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c b/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c index e8a63291c..4685060eb 100644 --- a/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c +++ b/src/esw/fw/pdlb/Core/Src/stm32g4xx_hal_msp.c @@ -20,6 +20,7 @@ /* Includes ------------------------------------------------------------------*/ #include "main.h" + /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ @@ -152,8 +153,8 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY; hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE; hdma_adc1.Init.MemInc = DMA_MINC_ENABLE; - hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; hdma_adc1.Init.Mode = DMA_NORMAL; hdma_adc1.Init.Priority = DMA_PRIORITY_LOW; if (HAL_DMA_Init(&hdma_adc1) != HAL_OK) @@ -211,8 +212,8 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) hdma_adc2.Init.Direction = DMA_PERIPH_TO_MEMORY; hdma_adc2.Init.PeriphInc = DMA_PINC_DISABLE; hdma_adc2.Init.MemInc = DMA_MINC_ENABLE; - hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; hdma_adc2.Init.Mode = DMA_NORMAL; hdma_adc2.Init.Priority = DMA_PRIORITY_LOW; if (HAL_DMA_Init(&hdma_adc2) != HAL_OK) diff --git a/src/esw/fw/pdlb/pdlb.ioc b/src/esw/fw/pdlb/pdlb.ioc index 7d0bf72af..90d1e4a67 100644 --- a/src/esw/fw/pdlb/pdlb.ioc +++ b/src/esw/fw/pdlb/pdlb.ioc @@ -33,16 +33,16 @@ ADC1.Rank-6\#ChannelRegularConversion=7 ADC1.Rank-7\#ChannelRegularConversion=8 ADC1.Rank-8\#ChannelRegularConversion=9 ADC1.Rank-9\#ChannelRegularConversion=10 -ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-7\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-8\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC1.SamplingTime-9\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 +ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-7\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-8\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-9\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 ADC1.master=1 ADC2.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_10 ADC2.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_15 @@ -54,18 +54,18 @@ ADC2.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE ADC2.OffsetNumber-1\#ChannelRegularConversion=ADC_OFFSET_NONE ADC2.Rank-0\#ChannelRegularConversion=1 ADC2.Rank-1\#ChannelRegularConversion=2 -ADC2.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 -ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5 +ADC2.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_640CYCLES_5 +ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_640CYCLES_5 CAD.formats= CAD.pinconfig= CAD.provider= Dma.ADC1.0.Direction=DMA_PERIPH_TO_MEMORY Dma.ADC1.0.EventEnable=DISABLE Dma.ADC1.0.Instance=DMA1_Channel1 -Dma.ADC1.0.MemDataAlignment=DMA_MDATAALIGN_HALFWORD +Dma.ADC1.0.MemDataAlignment=DMA_MDATAALIGN_WORD Dma.ADC1.0.MemInc=DMA_MINC_ENABLE Dma.ADC1.0.Mode=DMA_NORMAL -Dma.ADC1.0.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD +Dma.ADC1.0.PeriphDataAlignment=DMA_PDATAALIGN_WORD Dma.ADC1.0.PeriphInc=DMA_PINC_DISABLE Dma.ADC1.0.Polarity=HAL_DMAMUX_REQ_GEN_RISING Dma.ADC1.0.Priority=DMA_PRIORITY_LOW @@ -79,10 +79,10 @@ Dma.ADC1.0.SyncSignalID=NONE Dma.ADC2.1.Direction=DMA_PERIPH_TO_MEMORY Dma.ADC2.1.EventEnable=DISABLE Dma.ADC2.1.Instance=DMA1_Channel2 -Dma.ADC2.1.MemDataAlignment=DMA_MDATAALIGN_HALFWORD +Dma.ADC2.1.MemDataAlignment=DMA_MDATAALIGN_WORD Dma.ADC2.1.MemInc=DMA_MINC_ENABLE Dma.ADC2.1.Mode=DMA_NORMAL -Dma.ADC2.1.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD +Dma.ADC2.1.PeriphDataAlignment=DMA_PDATAALIGN_WORD Dma.ADC2.1.PeriphInc=DMA_PINC_DISABLE Dma.ADC2.1.Polarity=HAL_DMAMUX_REQ_GEN_RISING Dma.ADC2.1.Priority=DMA_PRIORITY_LOW @@ -104,8 +104,9 @@ FDCAN1.DataPrescaler=5 FDCAN1.DataSyncJumpWidth=13 FDCAN1.DataTimeSeg1=14 FDCAN1.DataTimeSeg2=13 +FDCAN1.ExtFiltersNbr=1 FDCAN1.FrameFormat=FDCAN_FRAME_FD_NO_BRS -FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,DataSyncJumpWidth,NominalSyncJumpWidth,NominalTimeSeg1,NominalTimeSeg2,NominalPrescaler,DataTimeSeg1,DataTimeSeg2,TransmitPause,AutoRetransmission,DataPrescaler +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,DataSyncJumpWidth,NominalSyncJumpWidth,NominalTimeSeg1,NominalTimeSeg2,NominalPrescaler,DataTimeSeg1,DataTimeSeg2,TransmitPause,AutoRetransmission,DataPrescaler,ExtFiltersNbr FDCAN1.NominalPrescaler=1 FDCAN1.NominalSyncJumpWidth=19 FDCAN1.NominalTimeSeg1=120 @@ -157,8 +158,8 @@ Mcu.PinsNb=24 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32G431CBUx -MxCube.Version=6.8.1 -MxDb.Version=DB.6.0.81 +MxCube.Version=6.10.0 +MxDb.Version=DB.6.0.100 NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false NVIC.DMA1_Channel1_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true NVIC.DMA1_Channel2_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true @@ -276,7 +277,7 @@ ProjectManager.FreePins=false ProjectManager.HalAssertFull=false ProjectManager.HeapSize=0x200 ProjectManager.KeepUserCode=true -ProjectManager.LastFirmware=true +ProjectManager.LastFirmware=false ProjectManager.LibraryCopy=1 ProjectManager.MainLocation=Core/Src ProjectManager.NoMain=false diff --git a/src/esw/fw/science/.cproject b/src/esw/fw/science/.cproject index 6902faf68..5dbf61419 100644 --- a/src/esw/fw/science/.cproject +++ b/src/esw/fw/science/.cproject @@ -37,7 +37,7 @@