├── .clang-format ├── LICENSE ├── README.md ├── README_CN.md ├── odrive_demo_bringup ├── CMakeLists.txt ├── config │ ├── diffbot_controllers.yaml │ ├── odrive_multi_interface_forward_controllers.yaml │ └── rrbot_controllers.yaml ├── launch │ ├── odrive_diffbot.launch.py │ ├── odrive_multi_interface.launch.py │ └── odrive_rrbot.launch.py └── package.xml ├── odrive_demo_description ├── CMakeLists.txt ├── package.xml └── urdf │ ├── odrive.ros2_control.xacro │ ├── odrive.urdf.xacro │ ├── odrive_diffbot.urdf.xacro │ └── odrive_rrbot.urdf.xacro ├── odrive_hardware_interface ├── CMakeLists.txt ├── include │ └── odrive_hardware_interface │ │ ├── odrive_endpoints.hpp │ │ ├── odrive_hardware_interface.hpp │ │ ├── odrive_usb.hpp │ │ └── visibility_control.hpp ├── odrive_hardware_interface.xml ├── package.xml └── src │ ├── odrive_hardware_interface.cpp │ └── odrive_usb.cpp └── odrive_ros2_control ├── CMakeLists.txt └── package.xml /.clang-format: -------------------------------------------------------------------------------- 1 | --- 2 | Language: Cpp 3 | BasedOnStyle: Google 4 | 5 | AccessModifierOffset: -2 6 | AlignAfterOpenBracket: AlwaysBreak 7 | BraceWrapping: 8 | AfterClass: true 9 | AfterFunction: true 10 | AfterNamespace: true 11 | AfterStruct: true 12 | AfterEnum: true 13 | BreakBeforeBraces: Custom 14 | ColumnLimit: 100 15 | ConstructorInitializerIndentWidth: 0 16 | ContinuationIndentWidth: 2 17 | DerivePointerAlignment: false 18 | PointerAlignment: Middle 19 | ReflowComments: false 20 | ... -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Apache License 2 | Version 2.0, January 2004 3 | http://www.apache.org/licenses/ 4 | 5 | TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 6 | 7 | 1. Definitions. 8 | 9 | "License" shall mean the terms and conditions for use, reproduction, 10 | and distribution as defined by Sections 1 through 9 of this document. 11 | 12 | "Licensor" shall mean the copyright owner or entity authorized by 13 | the copyright owner that is granting the License. 14 | 15 | "Legal Entity" shall mean the union of the acting entity and all 16 | other entities that control, are controlled by, or are under common 17 | control with that entity. For the purposes of this definition, 18 | "control" means (i) the power, direct or indirect, to cause the 19 | direction or management of such entity, whether by contract or 20 | otherwise, or (ii) ownership of fifty percent (50%) or more of the 21 | outstanding shares, or (iii) beneficial ownership of such entity. 22 | 23 | "You" (or "Your") shall mean an individual or Legal Entity 24 | exercising permissions granted by this License. 25 | 26 | "Source" form shall mean the preferred form for making modifications, 27 | including but not limited to software source code, documentation 28 | source, and configuration files. 29 | 30 | "Object" form shall mean any form resulting from mechanical 31 | transformation or translation of a Source form, including but 32 | not limited to compiled object code, generated documentation, 33 | and conversions to other media types. 34 | 35 | "Work" shall mean the work of authorship, whether in Source or 36 | Object form, made available under the License, as indicated by a 37 | copyright notice that is included in or attached to the work 38 | (an example is provided in the Appendix below). 39 | 40 | "Derivative Works" shall mean any work, whether in Source or Object 41 | form, that is based on (or derived from) the Work and for which the 42 | editorial revisions, annotations, elaborations, or other modifications 43 | represent, as a whole, an original work of authorship. For the purposes 44 | of this License, Derivative Works shall not include works that remain 45 | separable from, or merely link (or bind by name) to the interfaces of, 46 | the Work and Derivative Works thereof. 47 | 48 | "Contribution" shall mean any work of authorship, including 49 | the original version of the Work and any modifications or additions 50 | to that Work or Derivative Works thereof, that is intentionally 51 | submitted to Licensor for inclusion in the Work by the copyright owner 52 | or by an individual or Legal Entity authorized to submit on behalf of 53 | the copyright owner. For the purposes of this definition, "submitted" 54 | means any form of electronic, verbal, or written communication sent 55 | to the Licensor or its representatives, including but not limited to 56 | communication on electronic mailing lists, source code control systems, 57 | and issue tracking systems that are managed by, or on behalf of, the 58 | Licensor for the purpose of discussing and improving the Work, but 59 | excluding communication that is conspicuously marked or otherwise 60 | designated in writing by the copyright owner as "Not a Contribution." 61 | 62 | "Contributor" shall mean Licensor and any individual or Legal Entity 63 | on behalf of whom a Contribution has been received by Licensor and 64 | subsequently incorporated within the Work. 65 | 66 | 2. Grant of Copyright License. Subject to the terms and conditions of 67 | this License, each Contributor hereby grants to You a perpetual, 68 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 69 | copyright license to reproduce, prepare Derivative Works of, 70 | publicly display, publicly perform, sublicense, and distribute the 71 | Work and such Derivative Works in Source or Object form. 72 | 73 | 3. Grant of Patent License. Subject to the terms and conditions of 74 | this License, each Contributor hereby grants to You a perpetual, 75 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 76 | (except as stated in this section) patent license to make, have made, 77 | use, offer to sell, sell, import, and otherwise transfer the Work, 78 | where such license applies only to those patent claims licensable 79 | by such Contributor that are necessarily infringed by their 80 | Contribution(s) alone or by combination of their Contribution(s) 81 | with the Work to which such Contribution(s) was submitted. If You 82 | institute patent litigation against any entity (including a 83 | cross-claim or counterclaim in a lawsuit) alleging that the Work 84 | or a Contribution incorporated within the Work constitutes direct 85 | or contributory patent infringement, then any patent licenses 86 | granted to You under this License for that Work shall terminate 87 | as of the date such litigation is filed. 88 | 89 | 4. Redistribution. You may reproduce and distribute copies of the 90 | Work or Derivative Works thereof in any medium, with or without 91 | modifications, and in Source or Object form, provided that You 92 | meet the following conditions: 93 | 94 | (a) You must give any other recipients of the Work or 95 | Derivative Works a copy of this License; and 96 | 97 | (b) You must cause any modified files to carry prominent notices 98 | stating that You changed the files; and 99 | 100 | (c) You must retain, in the Source form of any Derivative Works 101 | that You distribute, all copyright, patent, trademark, and 102 | attribution notices from the Source form of the Work, 103 | excluding those notices that do not pertain to any part of 104 | the Derivative Works; and 105 | 106 | (d) If the Work includes a "NOTICE" text file as part of its 107 | distribution, then any Derivative Works that You distribute must 108 | include a readable copy of the attribution notices contained 109 | within such NOTICE file, excluding those notices that do not 110 | pertain to any part of the Derivative Works, in at least one 111 | of the following places: within a NOTICE text file distributed 112 | as part of the Derivative Works; within the Source form or 113 | documentation, if provided along with the Derivative Works; or, 114 | within a display generated by the Derivative Works, if and 115 | wherever such third-party notices normally appear. The contents 116 | of the NOTICE file are for informational purposes only and 117 | do not modify the License. You may add Your own attribution 118 | notices within Derivative Works that You distribute, alongside 119 | or as an addendum to the NOTICE text from the Work, provided 120 | that such additional attribution notices cannot be construed 121 | as modifying the License. 122 | 123 | You may add Your own copyright statement to Your modifications and 124 | may provide additional or different license terms and conditions 125 | for use, reproduction, or distribution of Your modifications, or 126 | for any such Derivative Works as a whole, provided Your use, 127 | reproduction, and distribution of the Work otherwise complies with 128 | the conditions stated in this License. 129 | 130 | 5. Submission of Contributions. Unless You explicitly state otherwise, 131 | any Contribution intentionally submitted for inclusion in the Work 132 | by You to the Licensor shall be under the terms and conditions of 133 | this License, without any additional terms or conditions. 134 | Notwithstanding the above, nothing herein shall supersede or modify 135 | the terms of any separate license agreement you may have executed 136 | with Licensor regarding such Contributions. 137 | 138 | 6. Trademarks. This License does not grant permission to use the trade 139 | names, trademarks, service marks, or product names of the Licensor, 140 | except as required for reasonable and customary use in describing the 141 | origin of the Work and reproducing the content of the NOTICE file. 142 | 143 | 7. Disclaimer of Warranty. Unless required by applicable law or 144 | agreed to in writing, Licensor provides the Work (and each 145 | Contributor provides its Contributions) on an "AS IS" BASIS, 146 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or 147 | implied, including, without limitation, any warranties or conditions 148 | of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A 149 | PARTICULAR PURPOSE. You are solely responsible for determining the 150 | appropriateness of using or redistributing the Work and assume any 151 | risks associated with Your exercise of permissions under this License. 152 | 153 | 8. Limitation of Liability. In no event and under no legal theory, 154 | whether in tort (including negligence), contract, or otherwise, 155 | unless required by applicable law (such as deliberate and grossly 156 | negligent acts) or agreed to in writing, shall any Contributor be 157 | liable to You for damages, including any direct, indirect, special, 158 | incidental, or consequential damages of any character arising as a 159 | result of this License or out of the use or inability to use the 160 | Work (including but not limited to damages for loss of goodwill, 161 | work stoppage, computer failure or malfunction, or any and all 162 | other commercial damages or losses), even if such Contributor 163 | has been advised of the possibility of such damages. 164 | 165 | 9. Accepting Warranty or Additional Liability. While redistributing 166 | the Work or Derivative Works thereof, You may choose to offer, 167 | and charge a fee for, acceptance of support, warranty, indemnity, 168 | or other liability obligations and/or rights consistent with this 169 | License. However, in accepting such obligations, You may act only 170 | on Your own behalf and on Your sole responsibility, not on behalf 171 | of any other Contributor, and only if You agree to indemnify, 172 | defend, and hold each Contributor harmless for any liability 173 | incurred by, or claims asserted against, such Contributor by reason 174 | of your accepting any such warranty or additional liability. 175 | 176 | END OF TERMS AND CONDITIONS 177 | 178 | APPENDIX: How to apply the Apache License to your work. 179 | 180 | To apply the Apache License to your work, attach the following 181 | boilerplate notice, with the fields enclosed by brackets "[]" 182 | replaced with your own identifying information. (Don't include 183 | the brackets!) The text should be enclosed in the appropriate 184 | comment syntax for the file format. We also recommend that a 185 | file or class name and description of purpose be included on the 186 | same "printed page" as the copyright notice for easier 187 | identification within third-party archives. 188 | 189 | Copyright [yyyy] [name of copyright owner] 190 | 191 | Licensed under the Apache License, Version 2.0 (the "License"); 192 | you may not use this file except in compliance with the License. 193 | You may obtain a copy of the License at 194 | 195 | http://www.apache.org/licenses/LICENSE-2.0 196 | 197 | Unless required by applicable law or agreed to in writing, software 198 | distributed under the License is distributed on an "AS IS" BASIS, 199 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 200 | See the License for the specific language governing permissions and 201 | limitations under the License. 202 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # odrive_ros2_control 2 | ENGLISH / [中文]() 3 | ## Introduction 4 | ODrive driver for ros2_control 5 | ## Compatibility 6 | | | ROS 2 Foxy Fitzroy | ROS 2 Humble Hawksbill | 7 | |---|---|---| 8 | | ODrive Firmware v0.5.3 | [foxy-fw-v0.5.3](../../tree/foxy-fw-v0.5.3) | [humble-fw-v0.5.3](../../tree/humble-fw-v0.5.3) | 9 | | ODrive Firmware v0.5.1 | [foxy-fw-v0.5.1](../../tree/foxy-fw-v0.5.1) | [humble-fw-v0.5.1](../../tree/humble-fw-v0.5.1) | 10 | ## Documentation 11 | - [Wiki](https://github.com/Factor-Robotics/odrive_ros2_control/wiki/Documentation) 12 | ## Done 13 | - [x] Support native protocol on USB 14 | - [x] Support position, speed, torque commands 15 | - [x] Support position, speed, torque feedbacks 16 | - [x] Support feedforward control inputs 17 | - [x] Unit conversion adheres to [REP-103]() 18 | - [x] Support using multiple ODrives 19 | - [x] Support using any or both of axes on each ODrive 20 | - [x] Allow multiple axes running in different control modes 21 | - [x] Support smooth switching of control modes 22 | - [x] Provide sensor data (error, voltage, temperature) 23 | - [x] Auto watchdog feeding 24 | - [x] HIL demos inspired by [ros2_control_demos]() 25 | ## Todo 26 | - [ ] Support serial port and CAN 27 | - [ ] Automatic configuration of ODrives based on URDF and YAML files -------------------------------------------------------------------------------- /README_CN.md: -------------------------------------------------------------------------------- 1 | # odrive_ros2_control 2 | [ENGLISH]() / 中文 3 | ## 简介 4 | ODrive 的 ros2_control 驱动 5 | ## 兼容性 6 | | | ROS 2 Foxy Fitzroy | ROS 2 Humble Hawksbill | 7 | |---|---|---| 8 | | ODrive Firmware v0.5.3 | [foxy-fw-v0.5.3](../../tree/foxy-fw-v0.5.3) | [humble-fw-v0.5.3](../../tree/humble-fw-v0.5.3) | 9 | | ODrive Firmware v0.5.1 | [foxy-fw-v0.5.1](../../tree/foxy-fw-v0.5.1) | [humble-fw-v0.5.1](../../tree/humble-fw-v0.5.1) | 10 | ## 文档 11 | - [Wiki](https://github.com/Factor-Robotics/odrive_ros2_control/wiki/%E6%96%87%E6%A1%A3) 12 | ## Done 13 | - [x] 支持 USB 上的原生协议 14 | - [x] 支持位置、速度、力矩命令 15 | - [x] 支持位置、速度、力矩反馈 16 | - [x] 支持前馈控制输入 17 | - [x] 单位换算遵循 [REP-103]() 18 | - [x] 支持使用多个 ODrive 19 | - [x] 支持使用每个 ODrive 上的一个或两个轴 20 | - [x] 允许多轴在不同的控制模式下运行 21 | - [x] 支持控制模式平滑切换 22 | - [x] 提供传感器数据(错误、电压、温度) 23 | - [x] 自动喂狗 24 | - [x] 受[ros2_control_demos]()启发的硬件在环演示 25 | ## Todo 26 | - [ ] 支持串口和CAN 27 | - [ ] 根据URDF和YAML文件自动配置ODrive -------------------------------------------------------------------------------- /odrive_demo_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(odrive_demo_bringup) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | 6 | ament_auto_package(INSTALL_TO_SHARE config launch) 7 | -------------------------------------------------------------------------------- /odrive_demo_bringup/config/diffbot_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_manager: 2 | ros__parameters: 3 | update_rate: 100 # Hz 4 | 5 | joint_state_broadcaster: 6 | type: joint_state_broadcaster/JointStateBroadcaster 7 | 8 | diffbot_base_controller: 9 | type: diff_drive_controller/DiffDriveController 10 | 11 | diffbot_base_controller: 12 | ros__parameters: 13 | left_wheel_names: ["left_wheel_joint"] 14 | right_wheel_names: ["right_wheel_joint"] 15 | 16 | wheel_separation: 0.10 17 | #wheels_per_side: 1 # actually 2, but both are controlled by 1 signal 18 | wheel_radius: 0.015 19 | 20 | wheel_separation_multiplier: 1.0 21 | left_wheel_radius_multiplier: 1.0 22 | right_wheel_radius_multiplier: 1.0 23 | 24 | publish_rate: 100.0 25 | odom_frame_id: odom 26 | base_frame_id: base_link 27 | pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] 28 | twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] 29 | 30 | open_loop: false 31 | enable_odom_tf: true 32 | 33 | cmd_vel_timeout: 0.5 34 | #publish_limited_velocity: true 35 | use_stamped_vel: false 36 | #velocity_rolling_window_size: 10 37 | 38 | # Velocity and acceleration limits 39 | # Whenever a min_* is unspecified, default to -max_* 40 | linear.x.has_velocity_limits: true 41 | linear.x.has_acceleration_limits: true 42 | linear.x.has_jerk_limits: false 43 | linear.x.max_velocity: 1.0 44 | linear.x.min_velocity: -1.0 45 | linear.x.max_acceleration: 1.0 46 | linear.x.max_jerk: 0.0 47 | linear.x.min_jerk: 0.0 48 | 49 | angular.z.has_velocity_limits: true 50 | angular.z.has_acceleration_limits: true 51 | angular.z.has_jerk_limits: false 52 | angular.z.max_velocity: 1.0 53 | angular.z.min_velocity: -1.0 54 | angular.z.max_acceleration: 1.0 55 | angular.z.min_acceleration: -1.0 56 | angular.z.max_jerk: 0.0 57 | angular.z.min_jerk: 0.0 58 | -------------------------------------------------------------------------------- /odrive_demo_bringup/config/odrive_multi_interface_forward_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_manager: 2 | ros__parameters: 3 | update_rate: 100 # Hz 4 | 5 | joint_state_broadcaster: 6 | type: joint_state_broadcaster/JointStateBroadcaster 7 | 8 | joint0_position_controller: 9 | type: position_controllers/JointGroupPositionController 10 | 11 | joint0_velocity_controller: 12 | type: velocity_controllers/JointGroupVelocityController 13 | 14 | joint0_effort_controller: 15 | type: effort_controllers/JointGroupEffortController 16 | 17 | joint1_position_controller: 18 | type: position_controllers/JointGroupPositionController 19 | 20 | joint1_velocity_controller: 21 | type: velocity_controllers/JointGroupVelocityController 22 | 23 | joint1_effort_controller: 24 | type: effort_controllers/JointGroupEffortController 25 | 26 | group_position_controller: 27 | type: position_controllers/JointGroupPositionController 28 | 29 | group_velocity_controller: 30 | type: velocity_controllers/JointGroupVelocityController 31 | 32 | group_effort_controller: 33 | type: effort_controllers/JointGroupEffortController 34 | 35 | joint0_position_controller: 36 | ros__parameters: 37 | joints: 38 | - joint0 39 | 40 | joint0_velocity_controller: 41 | ros__parameters: 42 | joints: 43 | - joint0 44 | 45 | joint0_effort_controller: 46 | ros__parameters: 47 | joints: 48 | - joint0 49 | 50 | joint1_position_controller: 51 | ros__parameters: 52 | joints: 53 | - joint1 54 | 55 | joint1_velocity_controller: 56 | ros__parameters: 57 | joints: 58 | - joint1 59 | 60 | joint1_effort_controller: 61 | ros__parameters: 62 | joints: 63 | - joint1 64 | 65 | group_position_controller: 66 | ros__parameters: 67 | joints: 68 | - joint0 69 | - joint1 70 | 71 | group_velocity_controller: 72 | ros__parameters: 73 | joints: 74 | - joint0 75 | - joint1 76 | 77 | group_effort_controller: 78 | ros__parameters: 79 | joints: 80 | - joint0 81 | - joint1 82 | -------------------------------------------------------------------------------- /odrive_demo_bringup/config/rrbot_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_manager: 2 | ros__parameters: 3 | update_rate: 100 # Hz 4 | 5 | joint_state_broadcaster: 6 | type: joint_state_broadcaster/JointStateBroadcaster 7 | 8 | joint_trajectory_controller: 9 | type: joint_trajectory_controller/JointTrajectoryController 10 | 11 | joint_trajectory_controller: 12 | ros__parameters: 13 | joints: 14 | - joint1 15 | - joint2 16 | 17 | command_interfaces: 18 | - position 19 | - velocity 20 | 21 | state_interfaces: 22 | - position 23 | - velocity 24 | 25 | state_publish_rate: 100.0 # Defaults to 50 26 | action_monitor_rate: 20.0 # Defaults to 20 27 | 28 | allow_partial_joints_goal: false # Defaults to false 29 | open_loop_control: false 30 | allow_integration_in_goal_trajectories: true 31 | constraints: 32 | stopped_velocity_tolerance: 0.01 # Defaults to 0.01 33 | goal_time: 0.0 # Defaults to 0.0 (start immediately) 34 | -------------------------------------------------------------------------------- /odrive_demo_bringup/launch/odrive_diffbot.launch.py: -------------------------------------------------------------------------------- 1 | # Copyright 2022 Factor Robotics 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from launch import LaunchDescription 16 | from launch.substitutions import Command, FindExecutable, PathJoinSubstitution 17 | from launch_ros.actions import Node 18 | from launch_ros.substitutions import FindPackageShare 19 | 20 | 21 | def generate_launch_description(): 22 | robot_description_content = Command( 23 | [ 24 | PathJoinSubstitution([FindExecutable(name="xacro")]), 25 | " ", 26 | PathJoinSubstitution( 27 | [ 28 | FindPackageShare("odrive_demo_description"), 29 | "urdf", 30 | "odrive_diffbot.urdf.xacro" 31 | ] 32 | ), 33 | ] 34 | ) 35 | robot_description = {"robot_description": robot_description_content} 36 | 37 | robot_controllers = PathJoinSubstitution( 38 | [ 39 | FindPackageShare("odrive_demo_bringup"), 40 | "config", 41 | "diffbot_controllers.yaml", 42 | ] 43 | ) 44 | 45 | rviz_config_file = PathJoinSubstitution( 46 | [ 47 | FindPackageShare("diffbot_description"), 48 | "config", 49 | "diffbot.rviz" 50 | ] 51 | ) 52 | 53 | control_node = Node( 54 | package="controller_manager", 55 | executable="ros2_control_node", 56 | parameters=[robot_description, robot_controllers], 57 | output="both", 58 | ) 59 | 60 | robot_state_pub_node = Node( 61 | package="robot_state_publisher", 62 | executable="robot_state_publisher", 63 | output="both", 64 | parameters=[robot_description], 65 | ) 66 | 67 | joint_state_broadcaster_spawner = Node( 68 | package="controller_manager", 69 | executable="spawner", 70 | arguments=["joint_state_broadcaster", "-c", "/controller_manager"], 71 | ) 72 | 73 | robot_controller_spawner = Node( 74 | package="controller_manager", 75 | executable="spawner", 76 | arguments=["diffbot_base_controller", "-c", "/controller_manager"], 77 | ) 78 | 79 | rviz_node = Node( 80 | package="rviz2", 81 | executable="rviz2", 82 | name="rviz2", 83 | arguments=["-d", rviz_config_file], 84 | ) 85 | 86 | return LaunchDescription([ 87 | control_node, 88 | robot_state_pub_node, 89 | joint_state_broadcaster_spawner, 90 | robot_controller_spawner, 91 | rviz_node 92 | ]) 93 | -------------------------------------------------------------------------------- /odrive_demo_bringup/launch/odrive_multi_interface.launch.py: -------------------------------------------------------------------------------- 1 | # Copyright 2021 Factor Robotics 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from launch import LaunchDescription 16 | from launch.actions import DeclareLaunchArgument 17 | from launch.conditions import IfCondition 18 | from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution 19 | from launch_ros.actions import Node 20 | from launch_ros.substitutions import FindPackageShare 21 | 22 | 23 | def generate_launch_description(): 24 | declared_arguments = [] 25 | 26 | declared_arguments.append( 27 | DeclareLaunchArgument( 28 | "enable_joint0", 29 | default_value="true", 30 | ) 31 | ) 32 | 33 | declared_arguments.append( 34 | DeclareLaunchArgument( 35 | "enable_joint1", 36 | default_value="false", 37 | ) 38 | ) 39 | 40 | declared_arguments.append( 41 | DeclareLaunchArgument( 42 | "joint0_controller", 43 | default_value="joint0_velocity_controller", 44 | ) 45 | ) 46 | 47 | declared_arguments.append( 48 | DeclareLaunchArgument( 49 | "joint1_controller", 50 | default_value="joint1_velocity_controller", 51 | ) 52 | ) 53 | 54 | enable_joint0 = LaunchConfiguration("enable_joint0") 55 | enable_joint1 = LaunchConfiguration("enable_joint1") 56 | joint0_controller = LaunchConfiguration("joint0_controller") 57 | joint1_controller = LaunchConfiguration("joint1_controller") 58 | 59 | robot_description_content = Command( 60 | [ 61 | PathJoinSubstitution([FindExecutable(name="xacro")]), 62 | " ", 63 | PathJoinSubstitution( 64 | [ 65 | FindPackageShare("odrive_demo_description"), 66 | "urdf", 67 | "odrive.urdf.xacro", 68 | ] 69 | ), 70 | " ", 71 | "enable_joint0:=", 72 | enable_joint0, 73 | " ", 74 | "enable_joint1:=", 75 | enable_joint1, 76 | ] 77 | ) 78 | robot_description = {"robot_description": robot_description_content} 79 | 80 | robot_controllers = PathJoinSubstitution( 81 | [ 82 | FindPackageShare("odrive_demo_bringup"), 83 | "config", 84 | "odrive_multi_interface_forward_controllers.yaml", 85 | ] 86 | ) 87 | 88 | control_node = Node( 89 | package="controller_manager", 90 | executable="ros2_control_node", 91 | output="both", 92 | parameters=[robot_description, robot_controllers], 93 | ) 94 | 95 | robot_state_pub_node = Node( 96 | package="robot_state_publisher", 97 | executable="robot_state_publisher", 98 | output="both", 99 | parameters=[robot_description], 100 | ) 101 | 102 | joint_state_broadcaster_spawner = Node( 103 | package="controller_manager", 104 | executable="spawner", 105 | arguments=["joint_state_broadcaster", "-c", "/controller_manager"], 106 | ) 107 | 108 | joint0_controller_spawner = Node( 109 | package="controller_manager", 110 | executable="spawner", 111 | arguments=[joint0_controller, "-c", "/controller_manager"], 112 | condition=IfCondition(enable_joint0), 113 | ) 114 | 115 | joint1_controller_spawner = Node( 116 | package="controller_manager", 117 | executable="spawner", 118 | arguments=[joint1_controller, "-c", "/controller_manager"], 119 | condition=IfCondition(enable_joint1), 120 | ) 121 | 122 | nodes = [ 123 | control_node, 124 | robot_state_pub_node, 125 | joint_state_broadcaster_spawner, 126 | joint0_controller_spawner, 127 | joint1_controller_spawner, 128 | ] 129 | 130 | return LaunchDescription(declared_arguments + nodes) 131 | -------------------------------------------------------------------------------- /odrive_demo_bringup/launch/odrive_rrbot.launch.py: -------------------------------------------------------------------------------- 1 | # Copyright 2022 Factor Robotics 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from launch import LaunchDescription 16 | from launch.substitutions import Command, FindExecutable, PathJoinSubstitution 17 | from launch_ros.actions import Node 18 | from launch_ros.substitutions import FindPackageShare 19 | 20 | 21 | def generate_launch_description(): 22 | robot_description_content = Command( 23 | [ 24 | PathJoinSubstitution([FindExecutable(name="xacro")]), 25 | " ", 26 | PathJoinSubstitution( 27 | [ 28 | FindPackageShare("odrive_demo_description"), 29 | "urdf", 30 | "odrive_rrbot.urdf.xacro" 31 | ] 32 | ), 33 | ] 34 | ) 35 | robot_description = {"robot_description": robot_description_content} 36 | 37 | robot_controllers = PathJoinSubstitution( 38 | [ 39 | FindPackageShare("odrive_demo_bringup"), 40 | "config", 41 | "rrbot_controllers.yaml", 42 | ] 43 | ) 44 | 45 | rviz_config_file = PathJoinSubstitution( 46 | [ 47 | FindPackageShare("rrbot_description"), 48 | "config", 49 | "rrbot.rviz" 50 | ] 51 | ) 52 | 53 | control_node = Node( 54 | package="controller_manager", 55 | executable="ros2_control_node", 56 | parameters=[robot_description, robot_controllers], 57 | output="both", 58 | ) 59 | 60 | robot_state_pub_node = Node( 61 | package="robot_state_publisher", 62 | executable="robot_state_publisher", 63 | output="both", 64 | parameters=[robot_description], 65 | ) 66 | 67 | joint_state_broadcaster_spawner = Node( 68 | package="controller_manager", 69 | executable="spawner", 70 | arguments=["joint_state_broadcaster", "-c", "/controller_manager"], 71 | ) 72 | 73 | robot_controller_spawner = Node( 74 | package="controller_manager", 75 | executable="spawner", 76 | arguments=["joint_trajectory_controller", "-c", "/controller_manager"], 77 | ) 78 | 79 | rviz_node = Node( 80 | package="rviz2", 81 | executable="rviz2", 82 | name="rviz2", 83 | arguments=["-d", rviz_config_file], 84 | ) 85 | 86 | return LaunchDescription([ 87 | control_node, 88 | robot_state_pub_node, 89 | joint_state_broadcaster_spawner, 90 | robot_controller_spawner, 91 | rviz_node 92 | ]) 93 | -------------------------------------------------------------------------------- /odrive_demo_bringup/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | odrive_demo_bringup 5 | 0.1.0 6 | Launch files and configurations for ODrive 7 | Borong Yuan 8 | Apache-2.0 9 | 10 | ament_cmake_auto 11 | 12 | odrive_demo_description 13 | robot_state_publisher 14 | ros2_controllers 15 | xacro 16 | 17 | 18 | ament_cmake 19 | 20 | 21 | -------------------------------------------------------------------------------- /odrive_demo_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(odrive_demo_description) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | 6 | ament_auto_package(INSTALL_TO_SHARE urdf) 7 | -------------------------------------------------------------------------------- /odrive_demo_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | odrive_demo_description 5 | 0.1.0 6 | ODrive ros2_control description 7 | Borong Yuan 8 | Apache-2.0 9 | 10 | ament_cmake_auto 11 | 12 | ros2_control_demo_description 13 | 14 | 15 | ament_cmake 16 | 17 | 18 | -------------------------------------------------------------------------------- /odrive_demo_description/urdf/odrive.ros2_control.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | odrive_hardware_interface/ODriveHardwareInterface 10 | 11 | 12 | 13 | ${serial_number} 14 | 15 | 16 | 17 | 18 | ${serial_number} 19 | 0 20 | 1 21 | 0.1 22 | 23 | 24 | 25 | 26 | 27 | ${serial_number} 28 | 1 29 | 1 30 | 0.1 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | -------------------------------------------------------------------------------- /odrive_demo_description/urdf/odrive.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /odrive_demo_description/urdf/odrive_diffbot.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /odrive_demo_description/urdf/odrive_rrbot.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /odrive_hardware_interface/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(odrive_hardware_interface) 3 | 4 | # Default to C99 5 | if(NOT CMAKE_C_STANDARD) 6 | set(CMAKE_C_STANDARD 99) 7 | endif() 8 | 9 | # Default to C++14 10 | if(NOT CMAKE_CXX_STANDARD) 11 | set(CMAKE_CXX_STANDARD 14) 12 | endif() 13 | 14 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 15 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-implicit-fallthrough) 16 | endif() 17 | 18 | # find dependencies 19 | find_package(ament_cmake_auto REQUIRED) 20 | ament_auto_find_build_dependencies() 21 | 22 | include(FindPkgConfig) 23 | pkg_search_module(LIBUSB1 REQUIRED libusb-1.0) 24 | 25 | if(LIBUSB1_FOUND) 26 | include_directories(SYSTEM ${LIBUSB1_INCLUDE_DIRS}) 27 | else() 28 | message( FATAL_ERROR "Failed to find libusb-1.0" ) 29 | endif() 30 | 31 | ament_auto_add_library( 32 | odrive_usb SHARED 33 | src/odrive_usb.cpp 34 | ) 35 | target_link_libraries( 36 | odrive_usb 37 | ${LIBUSB1_LIBRARIES} 38 | ) 39 | 40 | ament_auto_add_library( 41 | ${PROJECT_NAME} SHARED 42 | src/odrive_hardware_interface.cpp 43 | ) 44 | 45 | pluginlib_export_plugin_description_file(hardware_interface odrive_hardware_interface.xml) 46 | 47 | if(BUILD_TESTING) 48 | find_package(ament_lint_auto REQUIRED) 49 | # the following line skips the linter which checks for copyrights 50 | # uncomment the line when a copyright and license is not present in all source files 51 | #set(ament_cmake_copyright_FOUND TRUE) 52 | # the following line skips cpplint (only works in a git repo) 53 | # uncomment the line when this package is not in a git repo 54 | #set(ament_cmake_cpplint_FOUND TRUE) 55 | ament_lint_auto_find_test_dependencies() 56 | endif() 57 | 58 | ament_auto_package() 59 | -------------------------------------------------------------------------------- /odrive_hardware_interface/include/odrive_hardware_interface/odrive_endpoints.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * This file was autogenerated using the "odrivetool generate-code" feature. 3 | * 4 | * The file matches a specific firmware version. If you add/remove/rename any 5 | * properties exposed by the ODrive, this file needs to be regenerated, otherwise 6 | * the ODrive will ignore all commands. 7 | */ 8 | 9 | #ifndef __ODRIVE_ENDPOINTS_HPP 10 | #define __ODRIVE_ENDPOINTS_HPP 11 | 12 | 13 | namespace odrive { 14 | 15 | static constexpr const uint16_t json_crc = 0xebfb; 16 | 17 | static constexpr const uint16_t per_axis_offset = 304; 18 | 19 | enum { 20 | ERROR = 1, 21 | VBUS_VOLTAGE = 2, 22 | IBUS = 3, 23 | IBUS_REPORT_FILTER_K = 4, 24 | SERIAL_NUMBER = 5, 25 | HW_VERSION_MAJOR = 6, 26 | HW_VERSION_MINOR = 7, 27 | HW_VERSION_VARIANT = 8, 28 | FW_VERSION_MAJOR = 9, 29 | FW_VERSION_MINOR = 10, 30 | FW_VERSION_REVISION = 11, 31 | FW_VERSION_UNRELEASED = 12, 32 | BRAKE_RESISTOR_ARMED = 13, 33 | BRAKE_RESISTOR_SATURATED = 14, 34 | BRAKE_RESISTOR_CURRENT = 15, 35 | N_EVT_SAMPLING = 16, 36 | N_EVT_CONTROL_LOOP = 17, 37 | TASK_TIMERS_ARMED = 18, 38 | TASK_TIMES__SAMPLING__START_TIME = 19, 39 | TASK_TIMES__SAMPLING__END_TIME = 20, 40 | TASK_TIMES__SAMPLING__LENGTH = 21, 41 | TASK_TIMES__SAMPLING__MAX_LENGTH = 22, 42 | TASK_TIMES__CONTROL_LOOP_MISC__START_TIME = 23, 43 | TASK_TIMES__CONTROL_LOOP_MISC__END_TIME = 24, 44 | TASK_TIMES__CONTROL_LOOP_MISC__LENGTH = 25, 45 | TASK_TIMES__CONTROL_LOOP_MISC__MAX_LENGTH = 26, 46 | TASK_TIMES__CONTROL_LOOP_CHECKS__START_TIME = 27, 47 | TASK_TIMES__CONTROL_LOOP_CHECKS__END_TIME = 28, 48 | TASK_TIMES__CONTROL_LOOP_CHECKS__LENGTH = 29, 49 | TASK_TIMES__CONTROL_LOOP_CHECKS__MAX_LENGTH = 30, 50 | TASK_TIMES__DC_CALIB_WAIT__START_TIME = 31, 51 | TASK_TIMES__DC_CALIB_WAIT__END_TIME = 32, 52 | TASK_TIMES__DC_CALIB_WAIT__LENGTH = 33, 53 | TASK_TIMES__DC_CALIB_WAIT__MAX_LENGTH = 34, 54 | SYSTEM_STATS__UPTIME = 35, 55 | SYSTEM_STATS__MIN_HEAP_SPACE = 36, 56 | SYSTEM_STATS__MAX_STACK_USAGE_AXIS = 37, 57 | SYSTEM_STATS__MAX_STACK_USAGE_USB = 38, 58 | SYSTEM_STATS__MAX_STACK_USAGE_UART = 39, 59 | SYSTEM_STATS__MAX_STACK_USAGE_CAN = 40, 60 | SYSTEM_STATS__MAX_STACK_USAGE_STARTUP = 41, 61 | SYSTEM_STATS__MAX_STACK_USAGE_ANALOG = 42, 62 | SYSTEM_STATS__STACK_SIZE_AXIS = 43, 63 | SYSTEM_STATS__STACK_SIZE_USB = 44, 64 | SYSTEM_STATS__STACK_SIZE_UART = 45, 65 | SYSTEM_STATS__STACK_SIZE_STARTUP = 46, 66 | SYSTEM_STATS__STACK_SIZE_CAN = 47, 67 | SYSTEM_STATS__STACK_SIZE_ANALOG = 48, 68 | SYSTEM_STATS__PRIO_AXIS = 49, 69 | SYSTEM_STATS__PRIO_USB = 50, 70 | SYSTEM_STATS__PRIO_UART = 51, 71 | SYSTEM_STATS__PRIO_STARTUP = 52, 72 | SYSTEM_STATS__PRIO_CAN = 53, 73 | SYSTEM_STATS__PRIO_ANALOG = 54, 74 | SYSTEM_STATS__USB__RX_CNT = 55, 75 | SYSTEM_STATS__USB__TX_CNT = 56, 76 | SYSTEM_STATS__USB__TX_OVERRUN_CNT = 57, 77 | SYSTEM_STATS__I2C__ADDR = 58, 78 | SYSTEM_STATS__I2C__ADDR_MATCH_CNT = 59, 79 | SYSTEM_STATS__I2C__RX_CNT = 60, 80 | SYSTEM_STATS__I2C__ERROR_CNT = 61, 81 | USER_CONFIG_LOADED = 62, 82 | MISCONFIGURED = 63, 83 | OSCILLOSCOPE__SIZE = 64, 84 | CAN__ERROR = 68, 85 | CAN__CONFIG__BAUD_RATE = 69, 86 | CAN__CONFIG__PROTOCOL = 70, 87 | TEST_PROPERTY = 71, 88 | OTP_VALID = 72, 89 | CONFIG__ENABLE_UART_A = 73, 90 | CONFIG__ENABLE_UART_B = 74, 91 | CONFIG__ENABLE_UART_C = 75, 92 | CONFIG__UART_A_BAUDRATE = 76, 93 | CONFIG__UART_B_BAUDRATE = 77, 94 | CONFIG__UART_C_BAUDRATE = 78, 95 | CONFIG__ENABLE_CAN_A = 79, 96 | CONFIG__ENABLE_I2C_A = 80, 97 | CONFIG__USB_CDC_PROTOCOL = 81, 98 | CONFIG__UART0_PROTOCOL = 82, 99 | CONFIG__UART1_PROTOCOL = 83, 100 | CONFIG__UART2_PROTOCOL = 84, 101 | CONFIG__MAX_REGEN_CURRENT = 85, 102 | CONFIG__BRAKE_RESISTANCE = 86, 103 | CONFIG__ENABLE_BRAKE_RESISTOR = 87, 104 | CONFIG__DC_BUS_UNDERVOLTAGE_TRIP_LEVEL = 88, 105 | CONFIG__DC_BUS_OVERVOLTAGE_TRIP_LEVEL = 89, 106 | CONFIG__ENABLE_DC_BUS_OVERVOLTAGE_RAMP = 90, 107 | CONFIG__DC_BUS_OVERVOLTAGE_RAMP_START = 91, 108 | CONFIG__DC_BUS_OVERVOLTAGE_RAMP_END = 92, 109 | CONFIG__DC_MAX_POSITIVE_CURRENT = 93, 110 | CONFIG__DC_MAX_NEGATIVE_CURRENT = 94, 111 | CONFIG__ERROR_GPIO_PIN = 95, 112 | CONFIG__GPIO3_ANALOG_MAPPING__MIN = 97, 113 | CONFIG__GPIO3_ANALOG_MAPPING__MAX = 98, 114 | CONFIG__GPIO4_ANALOG_MAPPING__MIN = 100, 115 | CONFIG__GPIO4_ANALOG_MAPPING__MAX = 101, 116 | CONFIG__GPIO1_MODE = 102, 117 | CONFIG__GPIO2_MODE = 103, 118 | CONFIG__GPIO3_MODE = 104, 119 | CONFIG__GPIO4_MODE = 105, 120 | CONFIG__GPIO5_MODE = 106, 121 | CONFIG__GPIO6_MODE = 107, 122 | CONFIG__GPIO7_MODE = 108, 123 | CONFIG__GPIO8_MODE = 109, 124 | CONFIG__GPIO9_MODE = 110, 125 | CONFIG__GPIO10_MODE = 111, 126 | CONFIG__GPIO11_MODE = 112, 127 | CONFIG__GPIO12_MODE = 113, 128 | CONFIG__GPIO13_MODE = 114, 129 | CONFIG__GPIO14_MODE = 115, 130 | CONFIG__GPIO15_MODE = 116, 131 | CONFIG__GPIO16_MODE = 117, 132 | CONFIG__GPIO1_PWM_MAPPING__MIN = 119, 133 | CONFIG__GPIO1_PWM_MAPPING__MAX = 120, 134 | CONFIG__GPIO2_PWM_MAPPING__MIN = 122, 135 | CONFIG__GPIO2_PWM_MAPPING__MAX = 123, 136 | CONFIG__GPIO3_PWM_MAPPING__MIN = 125, 137 | CONFIG__GPIO3_PWM_MAPPING__MAX = 126, 138 | CONFIG__GPIO4_PWM_MAPPING__MIN = 128, 139 | CONFIG__GPIO4_PWM_MAPPING__MAX = 129, 140 | ERASE_CONFIGURATION = 746, 141 | REBOOT = 747, 142 | ENTER_DFU_MODE = 748, 143 | CLEAR_ERRORS = 759, 144 | 145 | // Per-Axis endpoints (to be used with read_axis_property and write_axis_property) 146 | AXIS__ERROR = 130, 147 | AXIS__STEP_DIR_ACTIVE = 131, 148 | AXIS__LAST_DRV_FAULT = 132, 149 | AXIS__STEPS = 133, 150 | AXIS__CURRENT_STATE = 134, 151 | AXIS__REQUESTED_STATE = 135, 152 | AXIS__IS_HOMED = 136, 153 | AXIS__CONFIG__STARTUP_MOTOR_CALIBRATION = 137, 154 | AXIS__CONFIG__STARTUP_ENCODER_INDEX_SEARCH = 138, 155 | AXIS__CONFIG__STARTUP_ENCODER_OFFSET_CALIBRATION = 139, 156 | AXIS__CONFIG__STARTUP_CLOSED_LOOP_CONTROL = 140, 157 | AXIS__CONFIG__STARTUP_HOMING = 141, 158 | AXIS__CONFIG__ENABLE_STEP_DIR = 142, 159 | AXIS__CONFIG__STEP_DIR_ALWAYS_ON = 143, 160 | AXIS__CONFIG__ENABLE_SENSORLESS_MODE = 144, 161 | AXIS__CONFIG__WATCHDOG_TIMEOUT = 145, 162 | AXIS__CONFIG__ENABLE_WATCHDOG = 146, 163 | AXIS__CONFIG__STEP_GPIO_PIN = 147, 164 | AXIS__CONFIG__DIR_GPIO_PIN = 148, 165 | AXIS__CONFIG__CALIBRATION_LOCKIN__CURRENT = 149, 166 | AXIS__CONFIG__CALIBRATION_LOCKIN__RAMP_TIME = 150, 167 | AXIS__CONFIG__CALIBRATION_LOCKIN__RAMP_DISTANCE = 151, 168 | AXIS__CONFIG__CALIBRATION_LOCKIN__ACCEL = 152, 169 | AXIS__CONFIG__CALIBRATION_LOCKIN__VEL = 153, 170 | AXIS__CONFIG__SENSORLESS_RAMP__CURRENT = 154, 171 | AXIS__CONFIG__SENSORLESS_RAMP__RAMP_TIME = 155, 172 | AXIS__CONFIG__SENSORLESS_RAMP__RAMP_DISTANCE = 156, 173 | AXIS__CONFIG__SENSORLESS_RAMP__ACCEL = 157, 174 | AXIS__CONFIG__SENSORLESS_RAMP__VEL = 158, 175 | AXIS__CONFIG__SENSORLESS_RAMP__FINISH_DISTANCE = 159, 176 | AXIS__CONFIG__SENSORLESS_RAMP__FINISH_ON_VEL = 160, 177 | AXIS__CONFIG__SENSORLESS_RAMP__FINISH_ON_DISTANCE = 161, 178 | AXIS__CONFIG__SENSORLESS_RAMP__FINISH_ON_ENC_IDX = 162, 179 | AXIS__CONFIG__GENERAL_LOCKIN__CURRENT = 163, 180 | AXIS__CONFIG__GENERAL_LOCKIN__RAMP_TIME = 164, 181 | AXIS__CONFIG__GENERAL_LOCKIN__RAMP_DISTANCE = 165, 182 | AXIS__CONFIG__GENERAL_LOCKIN__ACCEL = 166, 183 | AXIS__CONFIG__GENERAL_LOCKIN__VEL = 167, 184 | AXIS__CONFIG__GENERAL_LOCKIN__FINISH_DISTANCE = 168, 185 | AXIS__CONFIG__GENERAL_LOCKIN__FINISH_ON_VEL = 169, 186 | AXIS__CONFIG__GENERAL_LOCKIN__FINISH_ON_DISTANCE = 170, 187 | AXIS__CONFIG__GENERAL_LOCKIN__FINISH_ON_ENC_IDX = 171, 188 | AXIS__CONFIG__CAN__NODE_ID = 172, 189 | AXIS__CONFIG__CAN__IS_EXTENDED = 173, 190 | AXIS__CONFIG__CAN__HEARTBEAT_RATE_MS = 174, 191 | AXIS__CONFIG__CAN__ENCODER_RATE_MS = 175, 192 | AXIS__MOTOR__LAST_ERROR_TIME = 176, 193 | AXIS__MOTOR__ERROR = 177, 194 | AXIS__MOTOR__IS_ARMED = 178, 195 | AXIS__MOTOR__IS_CALIBRATED = 179, 196 | AXIS__MOTOR__CURRENT_MEAS_PHA = 180, 197 | AXIS__MOTOR__CURRENT_MEAS_PHB = 181, 198 | AXIS__MOTOR__CURRENT_MEAS_PHC = 182, 199 | AXIS__MOTOR__DC_CALIB_PHA = 183, 200 | AXIS__MOTOR__DC_CALIB_PHB = 184, 201 | AXIS__MOTOR__DC_CALIB_PHC = 185, 202 | AXIS__MOTOR__I_BUS = 186, 203 | AXIS__MOTOR__PHASE_CURRENT_REV_GAIN = 187, 204 | AXIS__MOTOR__EFFECTIVE_CURRENT_LIM = 188, 205 | AXIS__MOTOR__MAX_ALLOWED_CURRENT = 189, 206 | AXIS__MOTOR__MAX_DC_CALIB = 190, 207 | AXIS__MOTOR__FET_THERMISTOR__TEMPERATURE = 191, 208 | AXIS__MOTOR__FET_THERMISTOR__CONFIG__TEMP_LIMIT_LOWER = 192, 209 | AXIS__MOTOR__FET_THERMISTOR__CONFIG__TEMP_LIMIT_UPPER = 193, 210 | AXIS__MOTOR__FET_THERMISTOR__CONFIG__ENABLED = 194, 211 | AXIS__MOTOR__MOTOR_THERMISTOR__TEMPERATURE = 195, 212 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__GPIO_PIN = 196, 213 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__POLY_COEFFICIENT_0 = 197, 214 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__POLY_COEFFICIENT_1 = 198, 215 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__POLY_COEFFICIENT_2 = 199, 216 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__POLY_COEFFICIENT_3 = 200, 217 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__TEMP_LIMIT_LOWER = 201, 218 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__TEMP_LIMIT_UPPER = 202, 219 | AXIS__MOTOR__MOTOR_THERMISTOR__CONFIG__ENABLED = 203, 220 | AXIS__MOTOR__CURRENT_CONTROL__P_GAIN = 204, 221 | AXIS__MOTOR__CURRENT_CONTROL__I_GAIN = 205, 222 | AXIS__MOTOR__CURRENT_CONTROL__I_MEASURED_REPORT_FILTER_K = 206, 223 | AXIS__MOTOR__CURRENT_CONTROL__ID_SETPOINT = 207, 224 | AXIS__MOTOR__CURRENT_CONTROL__IQ_SETPOINT = 208, 225 | AXIS__MOTOR__CURRENT_CONTROL__VD_SETPOINT = 209, 226 | AXIS__MOTOR__CURRENT_CONTROL__VQ_SETPOINT = 210, 227 | AXIS__MOTOR__CURRENT_CONTROL__PHASE = 211, 228 | AXIS__MOTOR__CURRENT_CONTROL__PHASE_VEL = 212, 229 | AXIS__MOTOR__CURRENT_CONTROL__IALPHA_MEASURED = 213, 230 | AXIS__MOTOR__CURRENT_CONTROL__IBETA_MEASURED = 214, 231 | AXIS__MOTOR__CURRENT_CONTROL__ID_MEASURED = 215, 232 | AXIS__MOTOR__CURRENT_CONTROL__IQ_MEASURED = 216, 233 | AXIS__MOTOR__CURRENT_CONTROL__POWER = 217, 234 | AXIS__MOTOR__CURRENT_CONTROL__V_CURRENT_CONTROL_INTEGRAL_D = 218, 235 | AXIS__MOTOR__CURRENT_CONTROL__V_CURRENT_CONTROL_INTEGRAL_Q = 219, 236 | AXIS__MOTOR__CURRENT_CONTROL__FINAL_V_ALPHA = 220, 237 | AXIS__MOTOR__CURRENT_CONTROL__FINAL_V_BETA = 221, 238 | AXIS__MOTOR__N_EVT_CURRENT_MEASUREMENT = 222, 239 | AXIS__MOTOR__N_EVT_PWM_UPDATE = 223, 240 | AXIS__MOTOR__CONFIG__PRE_CALIBRATED = 224, 241 | AXIS__MOTOR__CONFIG__POLE_PAIRS = 225, 242 | AXIS__MOTOR__CONFIG__CALIBRATION_CURRENT = 226, 243 | AXIS__MOTOR__CONFIG__RESISTANCE_CALIB_MAX_VOLTAGE = 227, 244 | AXIS__MOTOR__CONFIG__PHASE_INDUCTANCE = 228, 245 | AXIS__MOTOR__CONFIG__PHASE_RESISTANCE = 229, 246 | AXIS__MOTOR__CONFIG__TORQUE_CONSTANT = 230, 247 | AXIS__MOTOR__CONFIG__MOTOR_TYPE = 231, 248 | AXIS__MOTOR__CONFIG__CURRENT_LIM = 232, 249 | AXIS__MOTOR__CONFIG__CURRENT_LIM_MARGIN = 233, 250 | AXIS__MOTOR__CONFIG__TORQUE_LIM = 234, 251 | AXIS__MOTOR__CONFIG__INVERTER_TEMP_LIMIT_LOWER = 235, 252 | AXIS__MOTOR__CONFIG__INVERTER_TEMP_LIMIT_UPPER = 236, 253 | AXIS__MOTOR__CONFIG__REQUESTED_CURRENT_RANGE = 237, 254 | AXIS__MOTOR__CONFIG__CURRENT_CONTROL_BANDWIDTH = 238, 255 | AXIS__MOTOR__CONFIG__ACIM_GAIN_MIN_FLUX = 239, 256 | AXIS__MOTOR__CONFIG__ACIM_AUTOFLUX_MIN_ID = 240, 257 | AXIS__MOTOR__CONFIG__ACIM_AUTOFLUX_ENABLE = 241, 258 | AXIS__MOTOR__CONFIG__ACIM_AUTOFLUX_ATTACK_GAIN = 242, 259 | AXIS__MOTOR__CONFIG__ACIM_AUTOFLUX_DECAY_GAIN = 243, 260 | AXIS__MOTOR__CONFIG__R_WL_FF_ENABLE = 244, 261 | AXIS__MOTOR__CONFIG__BEMF_FF_ENABLE = 245, 262 | AXIS__MOTOR__CONFIG__I_BUS_HARD_MIN = 246, 263 | AXIS__MOTOR__CONFIG__I_BUS_HARD_MAX = 247, 264 | AXIS__MOTOR__CONFIG__I_LEAK_MAX = 248, 265 | AXIS__MOTOR__CONFIG__DC_CALIB_TAU = 249, 266 | AXIS__CONTROLLER__ERROR = 250, 267 | AXIS__CONTROLLER__LAST_ERROR_TIME = 251, 268 | AXIS__CONTROLLER__INPUT_POS = 252, 269 | AXIS__CONTROLLER__INPUT_VEL = 253, 270 | AXIS__CONTROLLER__INPUT_TORQUE = 254, 271 | AXIS__CONTROLLER__POS_SETPOINT = 255, 272 | AXIS__CONTROLLER__VEL_SETPOINT = 256, 273 | AXIS__CONTROLLER__TORQUE_SETPOINT = 257, 274 | AXIS__CONTROLLER__TRAJECTORY_DONE = 258, 275 | AXIS__CONTROLLER__VEL_INTEGRATOR_TORQUE = 259, 276 | AXIS__CONTROLLER__ANTICOGGING_VALID = 260, 277 | AXIS__CONTROLLER__AUTOTUNING_PHASE = 261, 278 | AXIS__CONTROLLER__CONFIG__GAIN_SCHEDULING_WIDTH = 262, 279 | AXIS__CONTROLLER__CONFIG__ENABLE_VEL_LIMIT = 263, 280 | AXIS__CONTROLLER__CONFIG__ENABLE_TORQUE_MODE_VEL_LIMIT = 264, 281 | AXIS__CONTROLLER__CONFIG__ENABLE_GAIN_SCHEDULING = 265, 282 | AXIS__CONTROLLER__CONFIG__ENABLE_OVERSPEED_ERROR = 266, 283 | AXIS__CONTROLLER__CONFIG__CONTROL_MODE = 267, 284 | AXIS__CONTROLLER__CONFIG__INPUT_MODE = 268, 285 | AXIS__CONTROLLER__CONFIG__POS_GAIN = 269, 286 | AXIS__CONTROLLER__CONFIG__VEL_GAIN = 270, 287 | AXIS__CONTROLLER__CONFIG__VEL_INTEGRATOR_GAIN = 271, 288 | AXIS__CONTROLLER__CONFIG__VEL_LIMIT = 272, 289 | AXIS__CONTROLLER__CONFIG__VEL_LIMIT_TOLERANCE = 273, 290 | AXIS__CONTROLLER__CONFIG__VEL_RAMP_RATE = 274, 291 | AXIS__CONTROLLER__CONFIG__TORQUE_RAMP_RATE = 275, 292 | AXIS__CONTROLLER__CONFIG__CIRCULAR_SETPOINTS = 276, 293 | AXIS__CONTROLLER__CONFIG__CIRCULAR_SETPOINT_RANGE = 277, 294 | AXIS__CONTROLLER__CONFIG__STEPS_PER_CIRCULAR_RANGE = 278, 295 | AXIS__CONTROLLER__CONFIG__HOMING_SPEED = 279, 296 | AXIS__CONTROLLER__CONFIG__INERTIA = 280, 297 | AXIS__CONTROLLER__CONFIG__AXIS_TO_MIRROR = 281, 298 | AXIS__CONTROLLER__CONFIG__MIRROR_RATIO = 282, 299 | AXIS__CONTROLLER__CONFIG__TORQUE_MIRROR_RATIO = 283, 300 | AXIS__CONTROLLER__CONFIG__LOAD_ENCODER_AXIS = 284, 301 | AXIS__CONTROLLER__CONFIG__INPUT_FILTER_BANDWIDTH = 285, 302 | AXIS__CONTROLLER__CONFIG__ANTICOGGING__INDEX = 286, 303 | AXIS__CONTROLLER__CONFIG__ANTICOGGING__PRE_CALIBRATED = 287, 304 | AXIS__CONTROLLER__CONFIG__ANTICOGGING__CALIB_ANTICOGGING = 288, 305 | AXIS__CONTROLLER__CONFIG__ANTICOGGING__CALIB_POS_THRESHOLD = 289, 306 | AXIS__CONTROLLER__CONFIG__ANTICOGGING__CALIB_VEL_THRESHOLD = 290, 307 | AXIS__CONTROLLER__CONFIG__ANTICOGGING__COGGING_RATIO = 291, 308 | AXIS__CONTROLLER__CONFIG__ANTICOGGING__ANTICOGGING_ENABLED = 292, 309 | AXIS__CONTROLLER__CONFIG__MECHANICAL_POWER_BANDWIDTH = 293, 310 | AXIS__CONTROLLER__CONFIG__ELECTRICAL_POWER_BANDWIDTH = 294, 311 | AXIS__CONTROLLER__CONFIG__SPINOUT_MECHANICAL_POWER_THRESHOLD = 295, 312 | AXIS__CONTROLLER__CONFIG__SPINOUT_ELECTRICAL_POWER_THRESHOLD = 296, 313 | AXIS__CONTROLLER__AUTOTUNING__FREQUENCY = 297, 314 | AXIS__CONTROLLER__AUTOTUNING__POS_AMPLITUDE = 298, 315 | AXIS__CONTROLLER__AUTOTUNING__VEL_AMPLITUDE = 299, 316 | AXIS__CONTROLLER__AUTOTUNING__TORQUE_AMPLITUDE = 300, 317 | AXIS__CONTROLLER__MECHANICAL_POWER = 301, 318 | AXIS__CONTROLLER__ELECTRICAL_POWER = 302, 319 | AXIS__CONTROLLER__START_ANTICOGGING_CALIBRATION = 306, 320 | AXIS__ENCODER__ERROR = 307, 321 | AXIS__ENCODER__IS_READY = 308, 322 | AXIS__ENCODER__INDEX_FOUND = 309, 323 | AXIS__ENCODER__SHADOW_COUNT = 310, 324 | AXIS__ENCODER__COUNT_IN_CPR = 311, 325 | AXIS__ENCODER__INTERPOLATION = 312, 326 | AXIS__ENCODER__PHASE = 313, 327 | AXIS__ENCODER__POS_ESTIMATE = 314, 328 | AXIS__ENCODER__POS_ESTIMATE_COUNTS = 315, 329 | AXIS__ENCODER__POS_CIRCULAR = 316, 330 | AXIS__ENCODER__POS_CPR_COUNTS = 317, 331 | AXIS__ENCODER__DELTA_POS_CPR_COUNTS = 318, 332 | AXIS__ENCODER__HALL_STATE = 319, 333 | AXIS__ENCODER__VEL_ESTIMATE = 320, 334 | AXIS__ENCODER__VEL_ESTIMATE_COUNTS = 321, 335 | AXIS__ENCODER__CALIB_SCAN_RESPONSE = 322, 336 | AXIS__ENCODER__POS_ABS = 323, 337 | AXIS__ENCODER__SPI_ERROR_RATE = 324, 338 | AXIS__ENCODER__CONFIG__MODE = 325, 339 | AXIS__ENCODER__CONFIG__USE_INDEX = 326, 340 | AXIS__ENCODER__CONFIG__INDEX_OFFSET = 327, 341 | AXIS__ENCODER__CONFIG__USE_INDEX_OFFSET = 328, 342 | AXIS__ENCODER__CONFIG__FIND_IDX_ON_LOCKIN_ONLY = 329, 343 | AXIS__ENCODER__CONFIG__ABS_SPI_CS_GPIO_PIN = 330, 344 | AXIS__ENCODER__CONFIG__CPR = 331, 345 | AXIS__ENCODER__CONFIG__PHASE_OFFSET = 332, 346 | AXIS__ENCODER__CONFIG__PHASE_OFFSET_FLOAT = 333, 347 | AXIS__ENCODER__CONFIG__DIRECTION = 334, 348 | AXIS__ENCODER__CONFIG__PRE_CALIBRATED = 335, 349 | AXIS__ENCODER__CONFIG__ENABLE_PHASE_INTERPOLATION = 336, 350 | AXIS__ENCODER__CONFIG__BANDWIDTH = 337, 351 | AXIS__ENCODER__CONFIG__CALIB_RANGE = 338, 352 | AXIS__ENCODER__CONFIG__CALIB_SCAN_DISTANCE = 339, 353 | AXIS__ENCODER__CONFIG__CALIB_SCAN_OMEGA = 340, 354 | AXIS__ENCODER__CONFIG__IGNORE_ILLEGAL_HALL_STATE = 341, 355 | AXIS__ENCODER__CONFIG__HALL_POLARITY = 342, 356 | AXIS__ENCODER__CONFIG__HALL_POLARITY_CALIBRATED = 343, 357 | AXIS__ENCODER__CONFIG__SINCOS_GPIO_PIN_SIN = 344, 358 | AXIS__ENCODER__CONFIG__SINCOS_GPIO_PIN_COS = 345, 359 | AXIS__ACIM_ESTIMATOR__ROTOR_FLUX = 348, 360 | AXIS__ACIM_ESTIMATOR__SLIP_VEL = 349, 361 | AXIS__ACIM_ESTIMATOR__PHASE_OFFSET = 350, 362 | AXIS__ACIM_ESTIMATOR__STATOR_PHASE_VEL = 351, 363 | AXIS__ACIM_ESTIMATOR__STATOR_PHASE = 352, 364 | AXIS__ACIM_ESTIMATOR__CONFIG__SLIP_VELOCITY = 353, 365 | AXIS__SENSORLESS_ESTIMATOR__ERROR = 354, 366 | AXIS__SENSORLESS_ESTIMATOR__PHASE = 355, 367 | AXIS__SENSORLESS_ESTIMATOR__PLL_POS = 356, 368 | AXIS__SENSORLESS_ESTIMATOR__PHASE_VEL = 357, 369 | AXIS__SENSORLESS_ESTIMATOR__VEL_ESTIMATE = 358, 370 | AXIS__SENSORLESS_ESTIMATOR__CONFIG__OBSERVER_GAIN = 359, 371 | AXIS__SENSORLESS_ESTIMATOR__CONFIG__PLL_BANDWIDTH = 360, 372 | AXIS__SENSORLESS_ESTIMATOR__CONFIG__PM_FLUX_LINKAGE = 361, 373 | AXIS__TRAP_TRAJ__CONFIG__VEL_LIMIT = 362, 374 | AXIS__TRAP_TRAJ__CONFIG__ACCEL_LIMIT = 363, 375 | AXIS__TRAP_TRAJ__CONFIG__DECEL_LIMIT = 364, 376 | AXIS__MIN_ENDSTOP__ENDSTOP_STATE = 365, 377 | AXIS__MIN_ENDSTOP__CONFIG__GPIO_NUM = 366, 378 | AXIS__MIN_ENDSTOP__CONFIG__ENABLED = 367, 379 | AXIS__MIN_ENDSTOP__CONFIG__OFFSET = 368, 380 | AXIS__MIN_ENDSTOP__CONFIG__IS_ACTIVE_HIGH = 369, 381 | AXIS__MIN_ENDSTOP__CONFIG__DEBOUNCE_MS = 370, 382 | AXIS__MAX_ENDSTOP__ENDSTOP_STATE = 371, 383 | AXIS__MAX_ENDSTOP__CONFIG__GPIO_NUM = 372, 384 | AXIS__MAX_ENDSTOP__CONFIG__ENABLED = 373, 385 | AXIS__MAX_ENDSTOP__CONFIG__OFFSET = 374, 386 | AXIS__MAX_ENDSTOP__CONFIG__IS_ACTIVE_HIGH = 375, 387 | AXIS__MAX_ENDSTOP__CONFIG__DEBOUNCE_MS = 376, 388 | AXIS__MECHANICAL_BRAKE__CONFIG__GPIO_NUM = 377, 389 | AXIS__MECHANICAL_BRAKE__CONFIG__IS_ACTIVE_LOW = 378, 390 | AXIS__MECHANICAL_BRAKE__ENGAGE = 379, 391 | AXIS__MECHANICAL_BRAKE__RELEASE = 380, 392 | AXIS__TASK_TIMES__THERMISTOR_UPDATE__START_TIME = 381, 393 | AXIS__TASK_TIMES__THERMISTOR_UPDATE__END_TIME = 382, 394 | AXIS__TASK_TIMES__THERMISTOR_UPDATE__LENGTH = 383, 395 | AXIS__TASK_TIMES__THERMISTOR_UPDATE__MAX_LENGTH = 384, 396 | AXIS__TASK_TIMES__ENCODER_UPDATE__START_TIME = 385, 397 | AXIS__TASK_TIMES__ENCODER_UPDATE__END_TIME = 386, 398 | AXIS__TASK_TIMES__ENCODER_UPDATE__LENGTH = 387, 399 | AXIS__TASK_TIMES__ENCODER_UPDATE__MAX_LENGTH = 388, 400 | AXIS__TASK_TIMES__SENSORLESS_ESTIMATOR_UPDATE__START_TIME = 389, 401 | AXIS__TASK_TIMES__SENSORLESS_ESTIMATOR_UPDATE__END_TIME = 390, 402 | AXIS__TASK_TIMES__SENSORLESS_ESTIMATOR_UPDATE__LENGTH = 391, 403 | AXIS__TASK_TIMES__SENSORLESS_ESTIMATOR_UPDATE__MAX_LENGTH = 392, 404 | AXIS__TASK_TIMES__ENDSTOP_UPDATE__START_TIME = 393, 405 | AXIS__TASK_TIMES__ENDSTOP_UPDATE__END_TIME = 394, 406 | AXIS__TASK_TIMES__ENDSTOP_UPDATE__LENGTH = 395, 407 | AXIS__TASK_TIMES__ENDSTOP_UPDATE__MAX_LENGTH = 396, 408 | AXIS__TASK_TIMES__CAN_HEARTBEAT__START_TIME = 397, 409 | AXIS__TASK_TIMES__CAN_HEARTBEAT__END_TIME = 398, 410 | AXIS__TASK_TIMES__CAN_HEARTBEAT__LENGTH = 399, 411 | AXIS__TASK_TIMES__CAN_HEARTBEAT__MAX_LENGTH = 400, 412 | AXIS__TASK_TIMES__CONTROLLER_UPDATE__START_TIME = 401, 413 | AXIS__TASK_TIMES__CONTROLLER_UPDATE__END_TIME = 402, 414 | AXIS__TASK_TIMES__CONTROLLER_UPDATE__LENGTH = 403, 415 | AXIS__TASK_TIMES__CONTROLLER_UPDATE__MAX_LENGTH = 404, 416 | AXIS__TASK_TIMES__OPEN_LOOP_CONTROLLER_UPDATE__START_TIME = 405, 417 | AXIS__TASK_TIMES__OPEN_LOOP_CONTROLLER_UPDATE__END_TIME = 406, 418 | AXIS__TASK_TIMES__OPEN_LOOP_CONTROLLER_UPDATE__LENGTH = 407, 419 | AXIS__TASK_TIMES__OPEN_LOOP_CONTROLLER_UPDATE__MAX_LENGTH = 408, 420 | AXIS__TASK_TIMES__ACIM_ESTIMATOR_UPDATE__START_TIME = 409, 421 | AXIS__TASK_TIMES__ACIM_ESTIMATOR_UPDATE__END_TIME = 410, 422 | AXIS__TASK_TIMES__ACIM_ESTIMATOR_UPDATE__LENGTH = 411, 423 | AXIS__TASK_TIMES__ACIM_ESTIMATOR_UPDATE__MAX_LENGTH = 412, 424 | AXIS__TASK_TIMES__MOTOR_UPDATE__START_TIME = 413, 425 | AXIS__TASK_TIMES__MOTOR_UPDATE__END_TIME = 414, 426 | AXIS__TASK_TIMES__MOTOR_UPDATE__LENGTH = 415, 427 | AXIS__TASK_TIMES__MOTOR_UPDATE__MAX_LENGTH = 416, 428 | AXIS__TASK_TIMES__CURRENT_CONTROLLER_UPDATE__START_TIME = 417, 429 | AXIS__TASK_TIMES__CURRENT_CONTROLLER_UPDATE__END_TIME = 418, 430 | AXIS__TASK_TIMES__CURRENT_CONTROLLER_UPDATE__LENGTH = 419, 431 | AXIS__TASK_TIMES__CURRENT_CONTROLLER_UPDATE__MAX_LENGTH = 420, 432 | AXIS__TASK_TIMES__DC_CALIB__START_TIME = 421, 433 | AXIS__TASK_TIMES__DC_CALIB__END_TIME = 422, 434 | AXIS__TASK_TIMES__DC_CALIB__LENGTH = 423, 435 | AXIS__TASK_TIMES__DC_CALIB__MAX_LENGTH = 424, 436 | AXIS__TASK_TIMES__CURRENT_SENSE__START_TIME = 425, 437 | AXIS__TASK_TIMES__CURRENT_SENSE__END_TIME = 426, 438 | AXIS__TASK_TIMES__CURRENT_SENSE__LENGTH = 427, 439 | AXIS__TASK_TIMES__CURRENT_SENSE__MAX_LENGTH = 428, 440 | AXIS__TASK_TIMES__PWM_UPDATE__START_TIME = 429, 441 | AXIS__TASK_TIMES__PWM_UPDATE__END_TIME = 430, 442 | AXIS__TASK_TIMES__PWM_UPDATE__LENGTH = 431, 443 | AXIS__TASK_TIMES__PWM_UPDATE__MAX_LENGTH = 432, 444 | AXIS__WATCHDOG_FEED = 433, 445 | }; 446 | 447 | template 448 | struct endpoint_type; 449 | 450 | template<> struct endpoint_type { typedef uint8_t type; }; 451 | template<> struct endpoint_type { typedef float type; }; 452 | template<> struct endpoint_type { typedef float type; }; 453 | template<> struct endpoint_type { typedef float type; }; 454 | template<> struct endpoint_type { typedef uint64_t type; }; 455 | template<> struct endpoint_type { typedef uint8_t type; }; 456 | template<> struct endpoint_type { typedef uint8_t type; }; 457 | template<> struct endpoint_type { typedef uint8_t type; }; 458 | template<> struct endpoint_type { typedef uint8_t type; }; 459 | template<> struct endpoint_type { typedef uint8_t type; }; 460 | template<> struct endpoint_type { typedef uint8_t type; }; 461 | template<> struct endpoint_type { typedef uint8_t type; }; 462 | template<> struct endpoint_type { typedef bool type; }; 463 | template<> struct endpoint_type { typedef bool type; }; 464 | template<> struct endpoint_type { typedef float type; }; 465 | template<> struct endpoint_type { typedef uint32_t type; }; 466 | template<> struct endpoint_type { typedef uint32_t type; }; 467 | template<> struct endpoint_type { typedef bool type; }; 468 | template<> struct endpoint_type { typedef uint32_t type; }; 469 | template<> struct endpoint_type { typedef uint32_t type; }; 470 | template<> struct endpoint_type { typedef uint32_t type; }; 471 | template<> struct endpoint_type { typedef uint32_t type; }; 472 | template<> struct endpoint_type { typedef uint32_t type; }; 473 | template<> struct endpoint_type { typedef uint32_t type; }; 474 | template<> struct endpoint_type { typedef uint32_t type; }; 475 | template<> struct endpoint_type { typedef uint32_t type; }; 476 | template<> struct endpoint_type { typedef uint32_t type; }; 477 | template<> struct endpoint_type { typedef uint32_t type; }; 478 | template<> struct endpoint_type { typedef uint32_t type; }; 479 | template<> struct endpoint_type { typedef uint32_t type; }; 480 | template<> struct endpoint_type { typedef uint32_t type; }; 481 | template<> struct endpoint_type { typedef uint32_t type; }; 482 | template<> struct endpoint_type { typedef uint32_t type; }; 483 | template<> struct endpoint_type { typedef uint32_t type; }; 484 | template<> struct endpoint_type { typedef uint32_t type; }; 485 | template<> struct endpoint_type { typedef uint32_t type; }; 486 | template<> struct endpoint_type { typedef uint32_t type; }; 487 | template<> struct endpoint_type { typedef uint32_t type; }; 488 | template<> struct endpoint_type { typedef uint32_t type; }; 489 | template<> struct endpoint_type { typedef uint32_t type; }; 490 | template<> struct endpoint_type { typedef uint32_t type; }; 491 | template<> struct endpoint_type { typedef uint32_t type; }; 492 | template<> struct endpoint_type { typedef uint32_t type; }; 493 | template<> struct endpoint_type { typedef uint32_t type; }; 494 | template<> struct endpoint_type { typedef uint32_t type; }; 495 | template<> struct endpoint_type { typedef uint32_t type; }; 496 | template<> struct endpoint_type { typedef uint32_t type; }; 497 | template<> struct endpoint_type { typedef uint32_t type; }; 498 | template<> struct endpoint_type { typedef int32_t type; }; 499 | template<> struct endpoint_type { typedef int32_t type; }; 500 | template<> struct endpoint_type { typedef int32_t type; }; 501 | template<> struct endpoint_type { typedef int32_t type; }; 502 | template<> struct endpoint_type { typedef int32_t type; }; 503 | template<> struct endpoint_type { typedef int32_t type; }; 504 | template<> struct endpoint_type { typedef uint32_t type; }; 505 | template<> struct endpoint_type { typedef uint32_t type; }; 506 | template<> struct endpoint_type { typedef uint32_t type; }; 507 | template<> struct endpoint_type { typedef uint8_t type; }; 508 | template<> struct endpoint_type { typedef uint32_t type; }; 509 | template<> struct endpoint_type { typedef uint32_t type; }; 510 | template<> struct endpoint_type { typedef uint32_t type; }; 511 | template<> struct endpoint_type { typedef uint32_t type; }; 512 | template<> struct endpoint_type { typedef bool type; }; 513 | template<> struct endpoint_type { typedef uint32_t type; }; 514 | template<> struct endpoint_type { typedef uint8_t type; }; 515 | template<> struct endpoint_type { typedef uint32_t type; }; 516 | template<> struct endpoint_type { typedef uint8_t type; }; 517 | template<> struct endpoint_type { typedef uint32_t type; }; 518 | template<> struct endpoint_type { typedef bool type; }; 519 | template<> struct endpoint_type { typedef bool type; }; 520 | template<> struct endpoint_type { typedef bool type; }; 521 | template<> struct endpoint_type { typedef bool type; }; 522 | template<> struct endpoint_type { typedef uint32_t type; }; 523 | template<> struct endpoint_type { typedef uint32_t type; }; 524 | template<> struct endpoint_type { typedef uint32_t type; }; 525 | template<> struct endpoint_type { typedef bool type; }; 526 | template<> struct endpoint_type { typedef bool type; }; 527 | template<> struct endpoint_type { typedef uint8_t type; }; 528 | template<> struct endpoint_type { typedef uint8_t type; }; 529 | template<> struct endpoint_type { typedef uint8_t type; }; 530 | template<> struct endpoint_type { typedef uint8_t type; }; 531 | template<> struct endpoint_type { typedef float type; }; 532 | template<> struct endpoint_type { typedef float type; }; 533 | template<> struct endpoint_type { typedef bool type; }; 534 | template<> struct endpoint_type { typedef float type; }; 535 | template<> struct endpoint_type { typedef float type; }; 536 | template<> struct endpoint_type { typedef bool type; }; 537 | template<> struct endpoint_type { typedef float type; }; 538 | template<> struct endpoint_type { typedef float type; }; 539 | template<> struct endpoint_type { typedef float type; }; 540 | template<> struct endpoint_type { typedef float type; }; 541 | template<> struct endpoint_type { typedef uint32_t type; }; 542 | template<> struct endpoint_type { typedef float type; }; 543 | template<> struct endpoint_type { typedef float type; }; 544 | template<> struct endpoint_type { typedef float type; }; 545 | template<> struct endpoint_type { typedef float type; }; 546 | template<> struct endpoint_type { typedef uint8_t type; }; 547 | template<> struct endpoint_type { typedef uint8_t type; }; 548 | template<> struct endpoint_type { typedef uint8_t type; }; 549 | template<> struct endpoint_type { typedef uint8_t type; }; 550 | template<> struct endpoint_type { typedef uint8_t type; }; 551 | template<> struct endpoint_type { typedef uint8_t type; }; 552 | template<> struct endpoint_type { typedef uint8_t type; }; 553 | template<> struct endpoint_type { typedef uint8_t type; }; 554 | template<> struct endpoint_type { typedef uint8_t type; }; 555 | template<> struct endpoint_type { typedef uint8_t type; }; 556 | template<> struct endpoint_type { typedef uint8_t type; }; 557 | template<> struct endpoint_type { typedef uint8_t type; }; 558 | template<> struct endpoint_type { typedef uint8_t type; }; 559 | template<> struct endpoint_type { typedef uint8_t type; }; 560 | template<> struct endpoint_type { typedef uint8_t type; }; 561 | template<> struct endpoint_type { typedef uint8_t type; }; 562 | template<> struct endpoint_type { typedef float type; }; 563 | template<> struct endpoint_type { typedef float type; }; 564 | template<> struct endpoint_type { typedef float type; }; 565 | template<> struct endpoint_type { typedef float type; }; 566 | template<> struct endpoint_type { typedef float type; }; 567 | template<> struct endpoint_type { typedef float type; }; 568 | template<> struct endpoint_type { typedef float type; }; 569 | template<> struct endpoint_type { typedef float type; }; 570 | template<> struct endpoint_type { typedef void type; }; 571 | template<> struct endpoint_type { typedef void type; }; 572 | template<> struct endpoint_type { typedef void type; }; 573 | template<> struct endpoint_type { typedef void type; }; 574 | 575 | 576 | // Per-axis endpoints 577 | template<> struct endpoint_type { typedef uint32_t type; }; 578 | template<> struct endpoint_type { typedef bool type; }; 579 | template<> struct endpoint_type { typedef uint32_t type; }; 580 | template<> struct endpoint_type { typedef int64_t type; }; 581 | template<> struct endpoint_type { typedef uint8_t type; }; 582 | template<> struct endpoint_type { typedef uint8_t type; }; 583 | template<> struct endpoint_type { typedef bool type; }; 584 | template<> struct endpoint_type { typedef bool type; }; 585 | template<> struct endpoint_type { typedef bool type; }; 586 | template<> struct endpoint_type { typedef bool type; }; 587 | template<> struct endpoint_type { typedef bool type; }; 588 | template<> struct endpoint_type { typedef bool type; }; 589 | template<> struct endpoint_type { typedef bool type; }; 590 | template<> struct endpoint_type { typedef bool type; }; 591 | template<> struct endpoint_type { typedef bool type; }; 592 | template<> struct endpoint_type { typedef float type; }; 593 | template<> struct endpoint_type { typedef bool type; }; 594 | template<> struct endpoint_type { typedef uint16_t type; }; 595 | template<> struct endpoint_type { typedef uint16_t type; }; 596 | template<> struct endpoint_type { typedef float type; }; 597 | template<> struct endpoint_type { typedef float type; }; 598 | template<> struct endpoint_type { typedef float type; }; 599 | template<> struct endpoint_type { typedef float type; }; 600 | template<> struct endpoint_type { typedef float type; }; 601 | template<> struct endpoint_type { typedef float type; }; 602 | template<> struct endpoint_type { typedef float type; }; 603 | template<> struct endpoint_type { typedef float type; }; 604 | template<> struct endpoint_type { typedef float type; }; 605 | template<> struct endpoint_type { typedef float type; }; 606 | template<> struct endpoint_type { typedef float type; }; 607 | template<> struct endpoint_type { typedef bool type; }; 608 | template<> struct endpoint_type { typedef bool type; }; 609 | template<> struct endpoint_type { typedef bool type; }; 610 | template<> struct endpoint_type { typedef float type; }; 611 | template<> struct endpoint_type { typedef float type; }; 612 | template<> struct endpoint_type { typedef float type; }; 613 | template<> struct endpoint_type { typedef float type; }; 614 | template<> struct endpoint_type { typedef float type; }; 615 | template<> struct endpoint_type { typedef float type; }; 616 | template<> struct endpoint_type { typedef bool type; }; 617 | template<> struct endpoint_type { typedef bool type; }; 618 | template<> struct endpoint_type { typedef bool type; }; 619 | template<> struct endpoint_type { typedef uint32_t type; }; 620 | template<> struct endpoint_type { typedef bool type; }; 621 | template<> struct endpoint_type { typedef uint32_t type; }; 622 | template<> struct endpoint_type { typedef uint32_t type; }; 623 | template<> struct endpoint_type { typedef float type; }; 624 | template<> struct endpoint_type { typedef uint64_t type; }; 625 | template<> struct endpoint_type { typedef bool type; }; 626 | template<> struct endpoint_type { typedef bool type; }; 627 | template<> struct endpoint_type { typedef float type; }; 628 | template<> struct endpoint_type { typedef float type; }; 629 | template<> struct endpoint_type { typedef float type; }; 630 | template<> struct endpoint_type { typedef float type; }; 631 | template<> struct endpoint_type { typedef float type; }; 632 | template<> struct endpoint_type { typedef float type; }; 633 | template<> struct endpoint_type { typedef float type; }; 634 | template<> struct endpoint_type { typedef float type; }; 635 | template<> struct endpoint_type { typedef float type; }; 636 | template<> struct endpoint_type { typedef float type; }; 637 | template<> struct endpoint_type { typedef float type; }; 638 | template<> struct endpoint_type { typedef float type; }; 639 | template<> struct endpoint_type { typedef float type; }; 640 | template<> struct endpoint_type { typedef float type; }; 641 | template<> struct endpoint_type { typedef bool type; }; 642 | template<> struct endpoint_type { typedef float type; }; 643 | template<> struct endpoint_type { typedef uint16_t type; }; 644 | template<> struct endpoint_type { typedef float type; }; 645 | template<> struct endpoint_type { typedef float type; }; 646 | template<> struct endpoint_type { typedef float type; }; 647 | template<> struct endpoint_type { typedef float type; }; 648 | template<> struct endpoint_type { typedef float type; }; 649 | template<> struct endpoint_type { typedef float type; }; 650 | template<> struct endpoint_type { typedef bool type; }; 651 | template<> struct endpoint_type { typedef float type; }; 652 | template<> struct endpoint_type { typedef float type; }; 653 | template<> struct endpoint_type { typedef float type; }; 654 | template<> struct endpoint_type { typedef float type; }; 655 | template<> struct endpoint_type { typedef float type; }; 656 | template<> struct endpoint_type { typedef float type; }; 657 | template<> struct endpoint_type { typedef float type; }; 658 | template<> struct endpoint_type { typedef float type; }; 659 | template<> struct endpoint_type { typedef float type; }; 660 | template<> struct endpoint_type { typedef float type; }; 661 | template<> struct endpoint_type { typedef float type; }; 662 | template<> struct endpoint_type { typedef float type; }; 663 | template<> struct endpoint_type { typedef float type; }; 664 | template<> struct endpoint_type { typedef float type; }; 665 | template<> struct endpoint_type { typedef float type; }; 666 | template<> struct endpoint_type { typedef float type; }; 667 | template<> struct endpoint_type { typedef float type; }; 668 | template<> struct endpoint_type { typedef float type; }; 669 | template<> struct endpoint_type { typedef uint32_t type; }; 670 | template<> struct endpoint_type { typedef uint32_t type; }; 671 | template<> struct endpoint_type { typedef bool type; }; 672 | template<> struct endpoint_type { typedef int32_t type; }; 673 | template<> struct endpoint_type { typedef float type; }; 674 | template<> struct endpoint_type { typedef float type; }; 675 | template<> struct endpoint_type { typedef float type; }; 676 | template<> struct endpoint_type { typedef float type; }; 677 | template<> struct endpoint_type { typedef float type; }; 678 | template<> struct endpoint_type { typedef uint8_t type; }; 679 | template<> struct endpoint_type { typedef float type; }; 680 | template<> struct endpoint_type { typedef float type; }; 681 | template<> struct endpoint_type { typedef float type; }; 682 | template<> struct endpoint_type { typedef float type; }; 683 | template<> struct endpoint_type { typedef float type; }; 684 | template<> struct endpoint_type { typedef float type; }; 685 | template<> struct endpoint_type { typedef float type; }; 686 | template<> struct endpoint_type { typedef float type; }; 687 | template<> struct endpoint_type { typedef float type; }; 688 | template<> struct endpoint_type { typedef bool type; }; 689 | template<> struct endpoint_type { typedef float type; }; 690 | template<> struct endpoint_type { typedef float type; }; 691 | template<> struct endpoint_type { typedef bool type; }; 692 | template<> struct endpoint_type { typedef bool type; }; 693 | template<> struct endpoint_type { typedef float type; }; 694 | template<> struct endpoint_type { typedef float type; }; 695 | template<> struct endpoint_type { typedef float type; }; 696 | template<> struct endpoint_type { typedef float type; }; 697 | template<> struct endpoint_type { typedef uint8_t type; }; 698 | template<> struct endpoint_type { typedef float type; }; 699 | template<> struct endpoint_type { typedef float type; }; 700 | template<> struct endpoint_type { typedef float type; }; 701 | template<> struct endpoint_type { typedef float type; }; 702 | template<> struct endpoint_type { typedef float type; }; 703 | template<> struct endpoint_type { typedef float type; }; 704 | template<> struct endpoint_type { typedef float type; }; 705 | template<> struct endpoint_type { typedef bool type; }; 706 | template<> struct endpoint_type { typedef float type; }; 707 | template<> struct endpoint_type { typedef bool type; }; 708 | template<> struct endpoint_type { typedef float type; }; 709 | template<> struct endpoint_type { typedef float type; }; 710 | template<> struct endpoint_type { typedef bool type; }; 711 | template<> struct endpoint_type { typedef bool type; }; 712 | template<> struct endpoint_type { typedef bool type; }; 713 | template<> struct endpoint_type { typedef bool type; }; 714 | template<> struct endpoint_type { typedef uint8_t type; }; 715 | template<> struct endpoint_type { typedef uint8_t type; }; 716 | template<> struct endpoint_type { typedef float type; }; 717 | template<> struct endpoint_type { typedef float type; }; 718 | template<> struct endpoint_type { typedef float type; }; 719 | template<> struct endpoint_type { typedef float type; }; 720 | template<> struct endpoint_type { typedef float type; }; 721 | template<> struct endpoint_type { typedef float type; }; 722 | template<> struct endpoint_type { typedef float type; }; 723 | template<> struct endpoint_type { typedef bool type; }; 724 | template<> struct endpoint_type { typedef float type; }; 725 | template<> struct endpoint_type { typedef int32_t type; }; 726 | template<> struct endpoint_type { typedef float type; }; 727 | template<> struct endpoint_type { typedef float type; }; 728 | template<> struct endpoint_type { typedef uint8_t type; }; 729 | template<> struct endpoint_type { typedef float type; }; 730 | template<> struct endpoint_type { typedef float type; }; 731 | template<> struct endpoint_type { typedef uint8_t type; }; 732 | template<> struct endpoint_type { typedef float type; }; 733 | template<> struct endpoint_type { typedef uint32_t type; }; 734 | template<> struct endpoint_type { typedef bool type; }; 735 | template<> struct endpoint_type { typedef bool type; }; 736 | template<> struct endpoint_type { typedef float type; }; 737 | template<> struct endpoint_type { typedef float type; }; 738 | template<> struct endpoint_type { typedef float type; }; 739 | template<> struct endpoint_type { typedef bool type; }; 740 | template<> struct endpoint_type { typedef float type; }; 741 | template<> struct endpoint_type { typedef float type; }; 742 | template<> struct endpoint_type { typedef float type; }; 743 | template<> struct endpoint_type { typedef float type; }; 744 | template<> struct endpoint_type { typedef float type; }; 745 | template<> struct endpoint_type { typedef float type; }; 746 | template<> struct endpoint_type { typedef float type; }; 747 | template<> struct endpoint_type { typedef float type; }; 748 | template<> struct endpoint_type { typedef float type; }; 749 | template<> struct endpoint_type { typedef float type; }; 750 | template<> struct endpoint_type { typedef void type; }; 751 | template<> struct endpoint_type { typedef uint16_t type; }; 752 | template<> struct endpoint_type { typedef bool type; }; 753 | template<> struct endpoint_type { typedef bool type; }; 754 | template<> struct endpoint_type { typedef int32_t type; }; 755 | template<> struct endpoint_type { typedef int32_t type; }; 756 | template<> struct endpoint_type { typedef float type; }; 757 | template<> struct endpoint_type { typedef float type; }; 758 | template<> struct endpoint_type { typedef float type; }; 759 | template<> struct endpoint_type { typedef float type; }; 760 | template<> struct endpoint_type { typedef float type; }; 761 | template<> struct endpoint_type { typedef float type; }; 762 | template<> struct endpoint_type { typedef float type; }; 763 | template<> struct endpoint_type { typedef uint8_t type; }; 764 | template<> struct endpoint_type { typedef float type; }; 765 | template<> struct endpoint_type { typedef float type; }; 766 | template<> struct endpoint_type { typedef float type; }; 767 | template<> struct endpoint_type { typedef int32_t type; }; 768 | template<> struct endpoint_type { typedef float type; }; 769 | template<> struct endpoint_type { typedef uint16_t type; }; 770 | template<> struct endpoint_type { typedef bool type; }; 771 | template<> struct endpoint_type { typedef float type; }; 772 | template<> struct endpoint_type { typedef bool type; }; 773 | template<> struct endpoint_type { typedef bool type; }; 774 | template<> struct endpoint_type { typedef uint16_t type; }; 775 | template<> struct endpoint_type { typedef int32_t type; }; 776 | template<> struct endpoint_type { typedef int32_t type; }; 777 | template<> struct endpoint_type { typedef float type; }; 778 | template<> struct endpoint_type { typedef int32_t type; }; 779 | template<> struct endpoint_type { typedef bool type; }; 780 | template<> struct endpoint_type { typedef bool type; }; 781 | template<> struct endpoint_type { typedef float type; }; 782 | template<> struct endpoint_type { typedef float type; }; 783 | template<> struct endpoint_type { typedef float type; }; 784 | template<> struct endpoint_type { typedef float type; }; 785 | template<> struct endpoint_type { typedef bool type; }; 786 | template<> struct endpoint_type { typedef uint8_t type; }; 787 | template<> struct endpoint_type { typedef bool type; }; 788 | template<> struct endpoint_type { typedef uint16_t type; }; 789 | template<> struct endpoint_type { typedef uint16_t type; }; 790 | template<> struct endpoint_type { typedef float type; }; 791 | template<> struct endpoint_type { typedef float type; }; 792 | template<> struct endpoint_type { typedef float type; }; 793 | template<> struct endpoint_type { typedef float type; }; 794 | template<> struct endpoint_type { typedef float type; }; 795 | template<> struct endpoint_type { typedef float type; }; 796 | template<> struct endpoint_type { typedef uint8_t type; }; 797 | template<> struct endpoint_type { typedef float type; }; 798 | template<> struct endpoint_type { typedef float type; }; 799 | template<> struct endpoint_type { typedef float type; }; 800 | template<> struct endpoint_type { typedef float type; }; 801 | template<> struct endpoint_type { typedef float type; }; 802 | template<> struct endpoint_type { typedef float type; }; 803 | template<> struct endpoint_type { typedef float type; }; 804 | template<> struct endpoint_type { typedef float type; }; 805 | template<> struct endpoint_type { typedef float type; }; 806 | template<> struct endpoint_type { typedef float type; }; 807 | template<> struct endpoint_type { typedef bool type; }; 808 | template<> struct endpoint_type { typedef uint16_t type; }; 809 | template<> struct endpoint_type { typedef bool type; }; 810 | template<> struct endpoint_type { typedef float type; }; 811 | template<> struct endpoint_type { typedef bool type; }; 812 | template<> struct endpoint_type { typedef uint32_t type; }; 813 | template<> struct endpoint_type { typedef bool type; }; 814 | template<> struct endpoint_type { typedef uint16_t type; }; 815 | template<> struct endpoint_type { typedef bool type; }; 816 | template<> struct endpoint_type { typedef float type; }; 817 | template<> struct endpoint_type { typedef bool type; }; 818 | template<> struct endpoint_type { typedef uint32_t type; }; 819 | template<> struct endpoint_type { typedef uint16_t type; }; 820 | template<> struct endpoint_type { typedef bool type; }; 821 | template<> struct endpoint_type { typedef void type; }; 822 | template<> struct endpoint_type { typedef void type; }; 823 | template<> struct endpoint_type { typedef uint32_t type; }; 824 | template<> struct endpoint_type { typedef uint32_t type; }; 825 | template<> struct endpoint_type { typedef uint32_t type; }; 826 | template<> struct endpoint_type { typedef uint32_t type; }; 827 | template<> struct endpoint_type { typedef uint32_t type; }; 828 | template<> struct endpoint_type { typedef uint32_t type; }; 829 | template<> struct endpoint_type { typedef uint32_t type; }; 830 | template<> struct endpoint_type { typedef uint32_t type; }; 831 | template<> struct endpoint_type { typedef uint32_t type; }; 832 | template<> struct endpoint_type { typedef uint32_t type; }; 833 | template<> struct endpoint_type { typedef uint32_t type; }; 834 | template<> struct endpoint_type { typedef uint32_t type; }; 835 | template<> struct endpoint_type { typedef uint32_t type; }; 836 | template<> struct endpoint_type { typedef uint32_t type; }; 837 | template<> struct endpoint_type { typedef uint32_t type; }; 838 | template<> struct endpoint_type { typedef uint32_t type; }; 839 | template<> struct endpoint_type { typedef uint32_t type; }; 840 | template<> struct endpoint_type { typedef uint32_t type; }; 841 | template<> struct endpoint_type { typedef uint32_t type; }; 842 | template<> struct endpoint_type { typedef uint32_t type; }; 843 | template<> struct endpoint_type { typedef uint32_t type; }; 844 | template<> struct endpoint_type { typedef uint32_t type; }; 845 | template<> struct endpoint_type { typedef uint32_t type; }; 846 | template<> struct endpoint_type { typedef uint32_t type; }; 847 | template<> struct endpoint_type { typedef uint32_t type; }; 848 | template<> struct endpoint_type { typedef uint32_t type; }; 849 | template<> struct endpoint_type { typedef uint32_t type; }; 850 | template<> struct endpoint_type { typedef uint32_t type; }; 851 | template<> struct endpoint_type { typedef uint32_t type; }; 852 | template<> struct endpoint_type { typedef uint32_t type; }; 853 | template<> struct endpoint_type { typedef uint32_t type; }; 854 | template<> struct endpoint_type { typedef uint32_t type; }; 855 | template<> struct endpoint_type { typedef uint32_t type; }; 856 | template<> struct endpoint_type { typedef uint32_t type; }; 857 | template<> struct endpoint_type { typedef uint32_t type; }; 858 | template<> struct endpoint_type { typedef uint32_t type; }; 859 | template<> struct endpoint_type { typedef uint32_t type; }; 860 | template<> struct endpoint_type { typedef uint32_t type; }; 861 | template<> struct endpoint_type { typedef uint32_t type; }; 862 | template<> struct endpoint_type { typedef uint32_t type; }; 863 | template<> struct endpoint_type { typedef uint32_t type; }; 864 | template<> struct endpoint_type { typedef uint32_t type; }; 865 | template<> struct endpoint_type { typedef uint32_t type; }; 866 | template<> struct endpoint_type { typedef uint32_t type; }; 867 | template<> struct endpoint_type { typedef uint32_t type; }; 868 | template<> struct endpoint_type { typedef uint32_t type; }; 869 | template<> struct endpoint_type { typedef uint32_t type; }; 870 | template<> struct endpoint_type { typedef uint32_t type; }; 871 | template<> struct endpoint_type { typedef uint32_t type; }; 872 | template<> struct endpoint_type { typedef uint32_t type; }; 873 | template<> struct endpoint_type { typedef uint32_t type; }; 874 | template<> struct endpoint_type { typedef uint32_t type; }; 875 | template<> struct endpoint_type { typedef void type; }; 876 | 877 | 878 | template 879 | using endpoint_type_t = typename endpoint_type::type; 880 | 881 | } 882 | 883 | #endif // __ODRIVE_ENDPOINTS_HPP -------------------------------------------------------------------------------- /odrive_hardware_interface/include/odrive_hardware_interface/odrive_hardware_interface.hpp: -------------------------------------------------------------------------------- 1 | // Copyright 2021 Factor Robotics 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | 19 | #include "hardware_interface/system_interface.hpp" 20 | #include "hardware_interface/types/hardware_interface_type_values.hpp" 21 | #include "odrive_hardware_interface/odrive_usb.hpp" 22 | #include "odrive_hardware_interface/visibility_control.hpp" 23 | #include "rclcpp/rclcpp.hpp" 24 | 25 | #define AXIS_STATE_IDLE 1 26 | #define AXIS_STATE_CLOSED_LOOP_CONTROL 8 27 | 28 | #define CHECK_TS(status) \ 29 | do { \ 30 | int ret = (status); \ 31 | if (ret != 0) { \ 32 | RCLCPP_ERROR(rclcpp::get_logger("ODriveHardwareInterface"), libusb_error_name(ret)); \ 33 | return CallbackReturn::ERROR; \ 34 | } \ 35 | } while (0) 36 | 37 | #define CHECK_RW(status) \ 38 | do { \ 39 | int ret = (status); \ 40 | if (ret != 0) { \ 41 | RCLCPP_ERROR(rclcpp::get_logger("ODriveHardwareInterface"), libusb_error_name(ret)); \ 42 | return return_type::ERROR; \ 43 | } \ 44 | } while (0) 45 | 46 | using namespace odrive; 47 | using hardware_interface::CallbackReturn; 48 | using hardware_interface::return_type; 49 | 50 | namespace odrive_hardware_interface 51 | { 52 | class ODriveHardwareInterface : public hardware_interface::SystemInterface 53 | { 54 | public: 55 | RCLCPP_SHARED_PTR_DEFINITIONS(ODriveHardwareInterface) 56 | 57 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 58 | CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; 59 | 60 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 61 | CallbackReturn on_activate(const rclcpp_lifecycle::State &) override; 62 | 63 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 64 | CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) override; 65 | 66 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 67 | std::vector export_state_interfaces() override; 68 | 69 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 70 | std::vector export_command_interfaces() override; 71 | 72 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 73 | return_type prepare_command_mode_switch( 74 | const std::vector & start_interfaces, 75 | const std::vector & stop_interfaces) override; 76 | 77 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 78 | return_type perform_command_mode_switch( 79 | const std::vector &, const std::vector &) override; 80 | 81 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 82 | return_type read(const rclcpp::Time &, const rclcpp::Duration &) override; 83 | 84 | ODRIVE_HARDWARE_INTERFACE_PUBLIC 85 | return_type write(const rclcpp::Time &, const rclcpp::Duration &) override; 86 | 87 | private: 88 | ODriveUSB * odrive; 89 | 90 | std::vector> serial_numbers_; 91 | std::vector axes_; 92 | std::vector torque_constants_; 93 | std::vector enable_watchdogs_; 94 | 95 | std::vector hw_vbus_voltages_; 96 | 97 | std::vector hw_commands_positions_; 98 | std::vector hw_commands_velocities_; 99 | std::vector hw_commands_efforts_; 100 | std::vector hw_positions_; 101 | std::vector hw_velocities_; 102 | std::vector hw_efforts_; 103 | 104 | std::vector hw_axis_errors_; 105 | std::vector hw_motor_errors_; 106 | std::vector hw_encoder_errors_; 107 | std::vector hw_controller_errors_; 108 | std::vector hw_fet_temperatures_; 109 | std::vector hw_motor_temperatures_; 110 | 111 | enum class integration_level_t : int32_t 112 | { 113 | UNDEFINED = 0, 114 | EFFORT = 1, 115 | VELOCITY = 2, 116 | POSITION = 3 117 | }; 118 | 119 | std::vector control_level_; 120 | }; 121 | } // namespace odrive_hardware_interface 122 | -------------------------------------------------------------------------------- /odrive_hardware_interface/include/odrive_hardware_interface/odrive_usb.hpp: -------------------------------------------------------------------------------- 1 | // Copyright 2021 Factor Robotics 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | 19 | #include 20 | #include 21 | #include 22 | #include 23 | 24 | #include "odrive_hardware_interface/odrive_endpoints.hpp" 25 | 26 | #define ODRIVE_USB_VENDORID 0x1209 27 | #define ODRIVE_USB_PRODUCTID 0x0d32 28 | 29 | #define ODRIVE_OUT_ENDPOINT 0x03 30 | #define ODRIVE_IN_ENDPOINT 0x83 31 | 32 | #define ODRIVE_PROTOCOL_VERSION 1 33 | #define ODRIVE_MAX_PACKET_SIZE 16 34 | 35 | typedef std::vector bytes; 36 | 37 | namespace odrive 38 | { 39 | class ODriveUSB 40 | { 41 | public: 42 | ODriveUSB(); 43 | ~ODriveUSB(); 44 | 45 | int init(const std::vector> & serial_numbers); 46 | 47 | template 48 | int read(int64_t & serial_number, short endpoint_id, T & value); 49 | template 50 | int write(int64_t & serial_number, short endpoint_id, const T & value); 51 | int call(int64_t & serial_number, short endpoint_id); 52 | 53 | private: 54 | libusb_context * libusb_context_; 55 | 56 | std::map odrive_map_; 57 | 58 | short sequence_number_; 59 | 60 | template 61 | int read(libusb_device_handle * odrive_handle, short endpoint_id, T & value); 62 | template 63 | int write(libusb_device_handle * odrive_handle, short endpoint_id, const T & value); 64 | int call(libusb_device_handle * odrive_handle, short endpoint_id); 65 | 66 | int endpointOperation( 67 | libusb_device_handle * odrive_handle, short endpoint_id, short response_size, 68 | bytes request_payload, bytes & response_payload, bool MSB); 69 | 70 | bytes encodePacket( 71 | short sequence_number, short endpoint_id, short response_size, const bytes & request_payload); 72 | bytes decodePacket(bytes & response_packet); 73 | }; 74 | } // namespace odrive 75 | -------------------------------------------------------------------------------- /odrive_hardware_interface/include/odrive_hardware_interface/visibility_control.hpp: -------------------------------------------------------------------------------- 1 | // Copyright 2021 Factor Robotics 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ODRIVE_HARDWARE_INTERFACE__VISIBILITY_CONTROL_HPP_ 16 | #define ODRIVE_HARDWARE_INTERFACE__VISIBILITY_CONTROL_HPP_ 17 | 18 | // This logic was borrowed (then namespaced) from the examples on the gcc wiki: 19 | // https://gcc.gnu.org/wiki/Visibility 20 | 21 | #if defined _WIN32 || defined __CYGWIN__ 22 | #ifdef __GNUC__ 23 | #define ODRIVE_HARDWARE_INTERFACE_EXPORT __attribute__((dllexport)) 24 | #define ODRIVE_HARDWARE_INTERFACE_IMPORT __attribute__((dllimport)) 25 | #else 26 | #define ODRIVE_HARDWARE_INTERFACE_EXPORT __declspec(dllexport) 27 | #define ODRIVE_HARDWARE_INTERFACE_IMPORT __declspec(dllimport) 28 | #endif 29 | #ifdef ODRIVE_HARDWARE_INTERFACE_BUILDING_LIBRARY 30 | #define ODRIVE_HARDWARE_INTERFACE_PUBLIC ODRIVE_HARDWARE_INTERFACE_EXPORT 31 | #else 32 | #define ODRIVE_HARDWARE_INTERFACE_PUBLIC ODRIVE_HARDWARE_INTERFACE_IMPORT 33 | #endif 34 | #define ODRIVE_HARDWARE_INTERFACE_PUBLIC_TYPE ODRIVE_HARDWARE_INTERFACE_PUBLIC 35 | #define ODRIVE_HARDWARE_INTERFACE_LOCAL 36 | #else 37 | #define ODRIVE_HARDWARE_INTERFACE_EXPORT __attribute__((visibility("default"))) 38 | #define ODRIVE_HARDWARE_INTERFACE_IMPORT 39 | #if __GNUC__ >= 4 40 | #define ODRIVE_HARDWARE_INTERFACE_PUBLIC __attribute__((visibility("default"))) 41 | #define ODRIVE_HARDWARE_INTERFACE_LOCAL __attribute__((visibility("hidden"))) 42 | #else 43 | #define ODRIVE_HARDWARE_INTERFACE_PUBLIC 44 | #define ODRIVE_HARDWARE_INTERFACE_LOCAL 45 | #endif 46 | #define ODRIVE_HARDWARE_INTERFACE_PUBLIC_TYPE 47 | #endif 48 | 49 | #endif // ODRIVE_HARDWARE_INTERFACE__VISIBILITY_CONTROL_HPP_ 50 | -------------------------------------------------------------------------------- /odrive_hardware_interface/odrive_hardware_interface.xml: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | ODrive plugin for ros2_control. 7 | 8 | 9 | -------------------------------------------------------------------------------- /odrive_hardware_interface/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | odrive_hardware_interface 5 | 0.1.0 6 | ODrive hardware interface 7 | Borong Yuan 8 | Apache-2.0 9 | 10 | ament_cmake_auto 11 | 12 | hardware_interface 13 | pluginlib 14 | rclcpp 15 | 16 | ament_lint_auto 17 | ament_lint_common 18 | 19 | 20 | ament_cmake 21 | 22 | 23 | -------------------------------------------------------------------------------- /odrive_hardware_interface/src/odrive_hardware_interface.cpp: -------------------------------------------------------------------------------- 1 | // Copyright 2021 Factor Robotics 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include "odrive_hardware_interface/odrive_hardware_interface.hpp" 16 | 17 | #include "pluginlib/class_list_macros.hpp" 18 | 19 | namespace odrive_hardware_interface 20 | { 21 | CallbackReturn ODriveHardwareInterface::on_init(const hardware_interface::HardwareInfo & info) 22 | { 23 | if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) { 24 | return CallbackReturn::ERROR; 25 | } 26 | 27 | serial_numbers_.resize(2); 28 | 29 | hw_vbus_voltages_.resize(info_.sensors.size(), std::numeric_limits::quiet_NaN()); 30 | 31 | hw_positions_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 32 | hw_velocities_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 33 | hw_efforts_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 34 | hw_commands_positions_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 35 | hw_commands_velocities_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 36 | hw_commands_efforts_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 37 | 38 | hw_axis_errors_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 39 | hw_motor_errors_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 40 | hw_encoder_errors_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 41 | hw_controller_errors_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 42 | hw_fet_temperatures_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 43 | hw_motor_temperatures_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); 44 | 45 | for (const hardware_interface::ComponentInfo & sensor : info_.sensors) { 46 | serial_numbers_[0].emplace_back(std::stoull(sensor.parameters.at("serial_number"), 0, 16)); 47 | } 48 | 49 | for (const hardware_interface::ComponentInfo & joint : info_.joints) { 50 | serial_numbers_[1].emplace_back(std::stoull(joint.parameters.at("serial_number"), 0, 16)); 51 | axes_.emplace_back(std::stoi(joint.parameters.at("axis"))); 52 | enable_watchdogs_.emplace_back(std::stoi(joint.parameters.at("enable_watchdog"))); 53 | } 54 | 55 | odrive = new ODriveUSB(); 56 | CHECK_TS(odrive->init(serial_numbers_)); 57 | 58 | for (size_t i = 0; i < info_.joints.size(); i++) { 59 | float torque_constant; 60 | CHECK_TS(odrive->read( 61 | serial_numbers_[1][i], AXIS__MOTOR__CONFIG__TORQUE_CONSTANT + per_axis_offset * axes_[i], 62 | torque_constant)); 63 | torque_constants_.emplace_back(torque_constant); 64 | 65 | if (enable_watchdogs_[i]) { 66 | CHECK_TS(odrive->write( 67 | serial_numbers_[1][i], AXIS__CONFIG__WATCHDOG_TIMEOUT + per_axis_offset * axes_[i], 68 | std::stof(info_.joints[i].parameters.at("watchdog_timeout")))); 69 | } 70 | CHECK_TS(odrive->write( 71 | serial_numbers_[1][i], AXIS__CONFIG__ENABLE_WATCHDOG + per_axis_offset * axes_[i], 72 | (bool)enable_watchdogs_[i])); 73 | } 74 | 75 | control_level_.resize(info_.joints.size(), integration_level_t::UNDEFINED); 76 | return CallbackReturn::SUCCESS; 77 | } 78 | 79 | CallbackReturn ODriveHardwareInterface::on_activate(const rclcpp_lifecycle::State &) 80 | { 81 | for (size_t i = 0; i < info_.joints.size(); i++) { 82 | if (enable_watchdogs_[i]) { 83 | CHECK_TS( 84 | odrive->call(serial_numbers_[1][i], AXIS__WATCHDOG_FEED + per_axis_offset * axes_[i])); 85 | } 86 | CHECK_TS(odrive->call(serial_numbers_[1][i], CLEAR_ERRORS)); 87 | } 88 | 89 | return CallbackReturn::SUCCESS; 90 | } 91 | 92 | CallbackReturn ODriveHardwareInterface::on_deactivate(const rclcpp_lifecycle::State &) 93 | { 94 | int32_t requested_state = AXIS_STATE_IDLE; 95 | for (size_t i = 0; i < info_.joints.size(); i++) { 96 | CHECK_TS(odrive->write( 97 | serial_numbers_[1][i], AXIS__REQUESTED_STATE + per_axis_offset * axes_[i], requested_state)); 98 | } 99 | 100 | return CallbackReturn::SUCCESS; 101 | } 102 | 103 | std::vector ODriveHardwareInterface::export_state_interfaces() 104 | { 105 | std::vector state_interfaces; 106 | for (size_t i = 0; i < info_.sensors.size(); i++) { 107 | state_interfaces.emplace_back(hardware_interface::StateInterface( 108 | info_.sensors[i].name, "vbus_voltage", &hw_vbus_voltages_[i])); 109 | } 110 | 111 | for (size_t i = 0; i < info_.joints.size(); i++) { 112 | state_interfaces.emplace_back(hardware_interface::StateInterface( 113 | info_.joints[i].name, hardware_interface::HW_IF_EFFORT, &hw_efforts_[i])); 114 | state_interfaces.emplace_back(hardware_interface::StateInterface( 115 | info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_velocities_[i])); 116 | state_interfaces.emplace_back(hardware_interface::StateInterface( 117 | info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_positions_[i])); 118 | state_interfaces.emplace_back( 119 | hardware_interface::StateInterface(info_.joints[i].name, "axis_error", &hw_axis_errors_[i])); 120 | state_interfaces.emplace_back(hardware_interface::StateInterface( 121 | info_.joints[i].name, "motor_error", &hw_motor_errors_[i])); 122 | state_interfaces.emplace_back(hardware_interface::StateInterface( 123 | info_.joints[i].name, "encoder_error", &hw_encoder_errors_[i])); 124 | state_interfaces.emplace_back(hardware_interface::StateInterface( 125 | info_.joints[i].name, "controller_error", &hw_controller_errors_[i])); 126 | state_interfaces.emplace_back(hardware_interface::StateInterface( 127 | info_.joints[i].name, "fet_temperature", &hw_fet_temperatures_[i])); 128 | state_interfaces.emplace_back(hardware_interface::StateInterface( 129 | info_.joints[i].name, "motor_temperature", &hw_motor_temperatures_[i])); 130 | } 131 | 132 | return state_interfaces; 133 | } 134 | 135 | std::vector 136 | ODriveHardwareInterface::export_command_interfaces() 137 | { 138 | std::vector command_interfaces; 139 | for (size_t i = 0; i < info_.joints.size(); i++) { 140 | command_interfaces.emplace_back(hardware_interface::CommandInterface( 141 | info_.joints[i].name, hardware_interface::HW_IF_EFFORT, &hw_commands_efforts_[i])); 142 | command_interfaces.emplace_back(hardware_interface::CommandInterface( 143 | info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_commands_velocities_[i])); 144 | command_interfaces.emplace_back(hardware_interface::CommandInterface( 145 | info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_commands_positions_[i])); 146 | } 147 | 148 | return command_interfaces; 149 | } 150 | 151 | return_type ODriveHardwareInterface::prepare_command_mode_switch( 152 | const std::vector & start_interfaces, 153 | const std::vector & stop_interfaces) 154 | { 155 | for (std::string key : stop_interfaces) { 156 | for (size_t i = 0; i < info_.joints.size(); i++) { 157 | if (key.find(info_.joints[i].name) != std::string::npos) { 158 | control_level_[i] = integration_level_t::UNDEFINED; 159 | } 160 | } 161 | } 162 | 163 | for (std::string key : start_interfaces) { 164 | for (size_t i = 0; i < info_.joints.size(); i++) { 165 | switch (control_level_[i]) { 166 | case integration_level_t::UNDEFINED: 167 | if (key == info_.joints[i].name + "/" + hardware_interface::HW_IF_EFFORT) { 168 | control_level_[i] = integration_level_t::EFFORT; 169 | } 170 | 171 | case integration_level_t::EFFORT: 172 | if (key == info_.joints[i].name + "/" + hardware_interface::HW_IF_VELOCITY) { 173 | control_level_[i] = integration_level_t::VELOCITY; 174 | } 175 | 176 | case integration_level_t::VELOCITY: 177 | if (key == info_.joints[i].name + "/" + hardware_interface::HW_IF_POSITION) { 178 | control_level_[i] = integration_level_t::POSITION; 179 | } 180 | 181 | case integration_level_t::POSITION: 182 | break; 183 | } 184 | } 185 | } 186 | 187 | return return_type::OK; 188 | } 189 | 190 | return_type ODriveHardwareInterface::perform_command_mode_switch( 191 | const std::vector &, const std::vector &) 192 | { 193 | for (size_t i = 0; i < info_.joints.size(); i++) { 194 | float input_torque, input_vel, input_pos; 195 | int32_t requested_state; 196 | 197 | switch (control_level_[i]) { 198 | case integration_level_t::UNDEFINED: 199 | requested_state = AXIS_STATE_IDLE; 200 | CHECK_RW(odrive->write( 201 | serial_numbers_[1][i], AXIS__REQUESTED_STATE + per_axis_offset * axes_[i], 202 | requested_state)); 203 | break; 204 | 205 | case integration_level_t::EFFORT: 206 | hw_commands_efforts_[i] = hw_efforts_[i]; 207 | CHECK_RW(odrive->write( 208 | serial_numbers_[1][i], 209 | AXIS__CONTROLLER__CONFIG__CONTROL_MODE + per_axis_offset * axes_[i], 210 | (int32_t)control_level_[i])); 211 | input_torque = hw_commands_efforts_[i]; 212 | CHECK_RW(odrive->write( 213 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_TORQUE + per_axis_offset * axes_[i], 214 | input_torque)); 215 | requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL; 216 | CHECK_RW(odrive->write( 217 | serial_numbers_[1][i], AXIS__REQUESTED_STATE + per_axis_offset * axes_[i], 218 | requested_state)); 219 | break; 220 | 221 | case integration_level_t::VELOCITY: 222 | hw_commands_velocities_[i] = hw_velocities_[i]; 223 | hw_commands_efforts_[i] = 0; 224 | CHECK_RW(odrive->write( 225 | serial_numbers_[1][i], 226 | AXIS__CONTROLLER__CONFIG__CONTROL_MODE + per_axis_offset * axes_[i], 227 | (int32_t)control_level_[i])); 228 | input_vel = hw_commands_velocities_[i] / 2 / M_PI; 229 | CHECK_RW(odrive->write( 230 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_VEL + per_axis_offset * axes_[i], 231 | input_vel)); 232 | input_torque = hw_commands_efforts_[i]; 233 | CHECK_RW(odrive->write( 234 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_TORQUE + per_axis_offset * axes_[i], 235 | input_torque)); 236 | requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL; 237 | CHECK_RW(odrive->write( 238 | serial_numbers_[1][i], AXIS__REQUESTED_STATE + per_axis_offset * axes_[i], 239 | requested_state)); 240 | break; 241 | 242 | case integration_level_t::POSITION: 243 | hw_commands_positions_[i] = hw_positions_[i]; 244 | hw_commands_velocities_[i] = 0; 245 | hw_commands_efforts_[i] = 0; 246 | CHECK_RW(odrive->write( 247 | serial_numbers_[1][i], 248 | AXIS__CONTROLLER__CONFIG__CONTROL_MODE + per_axis_offset * axes_[i], 249 | (int32_t)control_level_[i])); 250 | input_pos = hw_commands_positions_[i] / 2 / M_PI; 251 | CHECK_RW(odrive->write( 252 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_POS + per_axis_offset * axes_[i], 253 | input_pos)); 254 | input_vel = hw_commands_velocities_[i] / 2 / M_PI; 255 | CHECK_RW(odrive->write( 256 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_VEL + per_axis_offset * axes_[i], 257 | input_vel)); 258 | input_torque = hw_commands_efforts_[i]; 259 | CHECK_RW(odrive->write( 260 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_TORQUE + per_axis_offset * axes_[i], 261 | input_torque)); 262 | requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL; 263 | CHECK_RW(odrive->write( 264 | serial_numbers_[1][i], AXIS__REQUESTED_STATE + per_axis_offset * axes_[i], 265 | requested_state)); 266 | break; 267 | } 268 | } 269 | 270 | return return_type::OK; 271 | } 272 | 273 | return_type ODriveHardwareInterface::read(const rclcpp::Time &, const rclcpp::Duration &) 274 | { 275 | for (size_t i = 0; i < info_.sensors.size(); i++) { 276 | float vbus_voltage; 277 | 278 | CHECK_RW(odrive->read(serial_numbers_[0][i], VBUS_VOLTAGE, vbus_voltage)); 279 | hw_vbus_voltages_[i] = vbus_voltage; 280 | } 281 | 282 | for (size_t i = 0; i < info_.joints.size(); i++) { 283 | float Iq_measured, vel_estimate, pos_estimate, fet_temperature, motor_temperature; 284 | uint8_t controller_error; 285 | uint16_t encoder_error; 286 | uint32_t axis_error; 287 | uint64_t motor_error; 288 | 289 | CHECK_RW(odrive->read( 290 | serial_numbers_[1][i], AXIS__MOTOR__CURRENT_CONTROL__IQ_MEASURED + per_axis_offset * axes_[i], 291 | Iq_measured)); 292 | hw_efforts_[i] = Iq_measured * torque_constants_[i]; 293 | 294 | CHECK_RW(odrive->read( 295 | serial_numbers_[1][i], AXIS__ENCODER__VEL_ESTIMATE + per_axis_offset * axes_[i], 296 | vel_estimate)); 297 | hw_velocities_[i] = vel_estimate * 2 * M_PI; 298 | 299 | CHECK_RW(odrive->read( 300 | serial_numbers_[1][i], AXIS__ENCODER__POS_ESTIMATE + per_axis_offset * axes_[i], 301 | pos_estimate)); 302 | hw_positions_[i] = pos_estimate * 2 * M_PI; 303 | 304 | CHECK_RW( 305 | odrive->read(serial_numbers_[1][i], AXIS__ERROR + per_axis_offset * axes_[i], axis_error)); 306 | hw_axis_errors_[i] = axis_error; 307 | 308 | CHECK_RW(odrive->read( 309 | serial_numbers_[1][i], AXIS__MOTOR__ERROR + per_axis_offset * axes_[i], motor_error)); 310 | hw_motor_errors_[i] = motor_error; 311 | 312 | CHECK_RW(odrive->read( 313 | serial_numbers_[1][i], AXIS__ENCODER__ERROR + per_axis_offset * axes_[i], encoder_error)); 314 | hw_encoder_errors_[i] = encoder_error; 315 | 316 | CHECK_RW(odrive->read( 317 | serial_numbers_[1][i], AXIS__CONTROLLER__ERROR + per_axis_offset * axes_[i], 318 | controller_error)); 319 | hw_controller_errors_[i] = controller_error; 320 | 321 | CHECK_RW(odrive->read( 322 | serial_numbers_[1][i], AXIS__MOTOR__FET_THERMISTOR__TEMPERATURE + per_axis_offset * axes_[i], 323 | fet_temperature)); 324 | hw_fet_temperatures_[i] = fet_temperature; 325 | 326 | CHECK_RW(odrive->read( 327 | serial_numbers_[1][i], 328 | AXIS__MOTOR__MOTOR_THERMISTOR__TEMPERATURE + per_axis_offset * axes_[i], motor_temperature)); 329 | hw_motor_temperatures_[i] = motor_temperature; 330 | } 331 | 332 | return return_type::OK; 333 | } 334 | 335 | return_type ODriveHardwareInterface::write(const rclcpp::Time &, const rclcpp::Duration &) 336 | { 337 | for (size_t i = 0; i < info_.joints.size(); i++) { 338 | float input_torque, input_vel, input_pos; 339 | 340 | switch (control_level_[i]) { 341 | case integration_level_t::POSITION: 342 | input_pos = hw_commands_positions_[i] / 2 / M_PI; 343 | CHECK_RW(odrive->write( 344 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_POS + per_axis_offset * axes_[i], 345 | input_pos)); 346 | 347 | case integration_level_t::VELOCITY: 348 | input_vel = hw_commands_velocities_[i] / 2 / M_PI; 349 | CHECK_RW(odrive->write( 350 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_VEL + per_axis_offset * axes_[i], 351 | input_vel)); 352 | 353 | case integration_level_t::EFFORT: 354 | input_torque = hw_commands_efforts_[i]; 355 | CHECK_RW(odrive->write( 356 | serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_TORQUE + per_axis_offset * axes_[i], 357 | input_torque)); 358 | 359 | case integration_level_t::UNDEFINED: 360 | if (enable_watchdogs_[i]) { 361 | CHECK_RW( 362 | odrive->call(serial_numbers_[1][i], AXIS__WATCHDOG_FEED + per_axis_offset * axes_[i])); 363 | } 364 | } 365 | } 366 | 367 | return return_type::OK; 368 | } 369 | } // namespace odrive_hardware_interface 370 | 371 | PLUGINLIB_EXPORT_CLASS( 372 | odrive_hardware_interface::ODriveHardwareInterface, hardware_interface::SystemInterface) 373 | -------------------------------------------------------------------------------- /odrive_hardware_interface/src/odrive_usb.cpp: -------------------------------------------------------------------------------- 1 | // Copyright 2021 Factor Robotics 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include "odrive_hardware_interface/odrive_usb.hpp" 16 | 17 | namespace odrive 18 | { 19 | ODriveUSB::ODriveUSB() { libusb_context_ = NULL; } 20 | 21 | ODriveUSB::~ODriveUSB() 22 | { 23 | for (auto it = odrive_map_.begin(); it != odrive_map_.end(); it++) { 24 | libusb_release_interface(it->second, 2); 25 | libusb_close(it->second); 26 | } 27 | odrive_map_.clear(); 28 | 29 | if (libusb_context_) { 30 | libusb_exit(libusb_context_); 31 | libusb_context_ = NULL; 32 | } 33 | } 34 | 35 | int ODriveUSB::init(const std::vector> & serial_numbers) 36 | { 37 | int ret = libusb_init(&libusb_context_); 38 | if (ret != LIBUSB_SUCCESS) { 39 | return ret; 40 | } 41 | 42 | libusb_device ** device_list; 43 | ssize_t device_count = libusb_get_device_list(libusb_context_, &device_list); 44 | if (device_count <= 0) { 45 | return device_count; 46 | } 47 | 48 | for (ssize_t i = 0; i < device_count; ++i) { 49 | libusb_device * device = device_list[i]; 50 | libusb_device_descriptor descriptor; 51 | 52 | if (libusb_get_device_descriptor(device, &descriptor) != LIBUSB_SUCCESS) { 53 | continue; 54 | } 55 | 56 | if ( 57 | descriptor.idVendor == ODRIVE_USB_VENDORID && descriptor.idProduct == ODRIVE_USB_PRODUCTID) { 58 | libusb_device_handle * device_handle; 59 | if (libusb_open(device, &device_handle) != LIBUSB_SUCCESS) { 60 | continue; 61 | } 62 | if ( 63 | (libusb_kernel_driver_active(device_handle, 2) != LIBUSB_SUCCESS) && 64 | (libusb_detach_kernel_driver(device_handle, 2) != LIBUSB_SUCCESS)) { 65 | libusb_close(device_handle); 66 | continue; 67 | } 68 | if ((libusb_claim_interface(device_handle, 2)) != LIBUSB_SUCCESS) { 69 | libusb_close(device_handle); 70 | continue; 71 | } 72 | uint64_t serial_number; 73 | if ((read(device_handle, SERIAL_NUMBER, serial_number)) != LIBUSB_SUCCESS) { 74 | libusb_release_interface(device_handle, 2); 75 | libusb_close(device_handle); 76 | continue; 77 | } 78 | odrive_map_.insert(std::pair(-serial_number, device_handle)); 79 | } 80 | } 81 | 82 | libusb_free_device_list(device_list, 1); 83 | if (!odrive_map_.size()) { 84 | return LIBUSB_ERROR_NO_DEVICE; 85 | } 86 | 87 | if (odrive_map_.size() == 1) { 88 | auto it = odrive_map_.begin(); 89 | odrive_map_.insert(std::pair(-it->first, it->second)); 90 | std::cout << "Connected to ODrive " << std::hex << -it->first << std::endl; 91 | odrive_map_.erase(it); 92 | } else { 93 | for (size_t i = 0; i < 2; i++) { 94 | for (size_t j = 0; j < serial_numbers[0].size(); j++) { 95 | if (!odrive_map_.count(serial_numbers[i][j])) { 96 | auto it = odrive_map_.find(-serial_numbers[i][j]); 97 | if (it != odrive_map_.end()) { 98 | odrive_map_.insert(std::pair(-it->first, it->second)); 99 | std::cout << "Connected to ODrive " << std::hex << -it->first << std::endl; 100 | odrive_map_.erase(it); 101 | } else { 102 | return LIBUSB_ERROR_NO_DEVICE; 103 | } 104 | } 105 | } 106 | } 107 | } 108 | 109 | for (auto it = odrive_map_.begin(); it != odrive_map_.end(); it++) { 110 | if (it->first < 0) { 111 | libusb_release_interface(it->second, 2); 112 | libusb_close(it->second); 113 | odrive_map_.erase(it); 114 | } 115 | } 116 | 117 | return LIBUSB_SUCCESS; 118 | } 119 | 120 | template 121 | int ODriveUSB::read(int64_t & serial_number, short endpoint_id, T & value) 122 | { 123 | if (serial_number) { 124 | return read(odrive_map_[serial_number], endpoint_id, value); 125 | } else { 126 | return read(odrive_map_.begin()->second, endpoint_id, value); 127 | } 128 | } 129 | 130 | template 131 | int ODriveUSB::read(libusb_device_handle * odrive_handle, short endpoint_id, T & value) 132 | { 133 | bytes request_payload; 134 | bytes response_payload; 135 | 136 | int ret = endpointOperation( 137 | odrive_handle, endpoint_id, sizeof(value), request_payload, response_payload, 1); 138 | if (ret != LIBUSB_SUCCESS) { 139 | return ret; 140 | } 141 | 142 | std::memcpy(&value, &response_payload[0], sizeof(value)); 143 | 144 | return LIBUSB_SUCCESS; 145 | } 146 | 147 | template 148 | int ODriveUSB::write(int64_t & serial_number, short endpoint_id, const T & value) 149 | { 150 | if (serial_number) { 151 | return write(odrive_map_[serial_number], endpoint_id, value); 152 | } else { 153 | return write(odrive_map_.begin()->second, endpoint_id, value); 154 | } 155 | } 156 | 157 | template 158 | int ODriveUSB::write(libusb_device_handle * odrive_handle, short endpoint_id, const T & value) 159 | { 160 | bytes request_payload; 161 | bytes response_payload; 162 | 163 | for (size_t i = 0; i < sizeof(value); i++) { 164 | request_payload.emplace_back(((unsigned char *)&value)[i]); 165 | } 166 | 167 | return endpointOperation(odrive_handle, endpoint_id, 0, request_payload, response_payload, 1); 168 | } 169 | 170 | int ODriveUSB::call(int64_t & serial_number, short endpoint_id) 171 | { 172 | if (serial_number) { 173 | return call(odrive_map_[serial_number], endpoint_id); 174 | } else { 175 | return call(odrive_map_.begin()->second, endpoint_id); 176 | } 177 | } 178 | 179 | int ODriveUSB::call(libusb_device_handle * odrive_handle, short endpoint_id) 180 | { 181 | bytes request_payload; 182 | bytes response_payload; 183 | 184 | return endpointOperation(odrive_handle, endpoint_id, 0, request_payload, response_payload, 1); 185 | } 186 | 187 | int ODriveUSB::endpointOperation( 188 | libusb_device_handle * odrive_handle, short endpoint_id, short response_size, 189 | bytes request_payload, bytes & response_payload, bool MSB) 190 | { 191 | int transferred = 0; 192 | bytes response_packet; 193 | unsigned char response_data[ODRIVE_MAX_PACKET_SIZE] = {0}; 194 | 195 | if (MSB) { 196 | endpoint_id |= 0x8000; 197 | } 198 | sequence_number_ = (sequence_number_ + 1) & 0x7fff; 199 | sequence_number_ |= LIBUSB_ENDPOINT_IN; 200 | short sequence_number = sequence_number_; 201 | 202 | bytes request_packet = encodePacket(sequence_number, endpoint_id, response_size, request_payload); 203 | 204 | int ret = libusb_bulk_transfer( 205 | odrive_handle, ODRIVE_OUT_ENDPOINT, request_packet.data(), request_packet.size(), &transferred, 206 | 0); 207 | if (ret != LIBUSB_SUCCESS) { 208 | return ret; 209 | } 210 | 211 | if (MSB) { 212 | ret = libusb_bulk_transfer( 213 | odrive_handle, ODRIVE_IN_ENDPOINT, response_data, ODRIVE_MAX_PACKET_SIZE, &transferred, 0); 214 | if (ret != LIBUSB_SUCCESS) { 215 | return ret; 216 | } 217 | 218 | for (int i = 0; i < transferred; i++) { 219 | response_packet.emplace_back(response_data[i]); 220 | } 221 | 222 | response_payload = decodePacket(response_packet); 223 | } 224 | 225 | return LIBUSB_SUCCESS; 226 | } 227 | 228 | bytes ODriveUSB::encodePacket( 229 | short sequence_number, short endpoint_id, short response_size, const bytes & request_payload) 230 | { 231 | bytes packet; 232 | 233 | packet.emplace_back((sequence_number >> 0) & 0xFF); 234 | packet.emplace_back((sequence_number >> 8) & 0xFF); 235 | packet.emplace_back((endpoint_id >> 0) & 0xFF); 236 | packet.emplace_back((endpoint_id >> 8) & 0xFF); 237 | packet.emplace_back((response_size >> 0) & 0xFF); 238 | packet.emplace_back((response_size >> 8) & 0xFF); 239 | 240 | for (uint8_t b : request_payload) { 241 | packet.emplace_back(b); 242 | } 243 | 244 | short crc = ((endpoint_id & 0x7fff) == 0) ? ODRIVE_PROTOCOL_VERSION : json_crc; 245 | packet.emplace_back((crc >> 0) & 0xFF); 246 | packet.emplace_back((crc >> 8) & 0xFF); 247 | 248 | return packet; 249 | } 250 | 251 | bytes ODriveUSB::decodePacket(bytes & response_packet) 252 | { 253 | bytes payload; 254 | 255 | for (bytes::size_type i = 2; i < response_packet.size(); ++i) { 256 | payload.emplace_back(response_packet[i]); 257 | } 258 | 259 | return payload; 260 | } 261 | 262 | template int ODriveUSB::read(int64_t &, short, bool &); 263 | template int ODriveUSB::read(int64_t &, short, float &); 264 | template int ODriveUSB::read(int64_t &, short, int32_t &); 265 | template int ODriveUSB::read(int64_t &, short, int64_t &); 266 | template int ODriveUSB::read(int64_t &, short, uint8_t &); 267 | template int ODriveUSB::read(int64_t &, short, uint16_t &); 268 | template int ODriveUSB::read(int64_t &, short, uint32_t &); 269 | template int ODriveUSB::read(int64_t &, short, uint64_t &); 270 | 271 | template int ODriveUSB::write(int64_t &, short, const bool &); 272 | template int ODriveUSB::write(int64_t &, short, const float &); 273 | template int ODriveUSB::write(int64_t &, short, const int32_t &); 274 | template int ODriveUSB::write(int64_t &, short, const int64_t &); 275 | template int ODriveUSB::write(int64_t &, short, const uint8_t &); 276 | template int ODriveUSB::write(int64_t &, short, const uint16_t &); 277 | template int ODriveUSB::write(int64_t &, short, const uint32_t &); 278 | template int ODriveUSB::write(int64_t &, short, const uint64_t &); 279 | } // namespace odrive 280 | -------------------------------------------------------------------------------- /odrive_ros2_control/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(odrive_ros2_control) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_package() 6 | -------------------------------------------------------------------------------- /odrive_ros2_control/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | odrive_ros2_control 5 | 0.1.0 6 | Metapackage for `odrive_ros2_control` packages 7 | Borong Yuan 8 | Apache-2.0 9 | 10 | ament_cmake_auto 11 | 12 | odrive_demo_bringup 13 | odrive_demo_description 14 | odrive_hardware_interface 15 | 16 | 17 | ament_cmake 18 | 19 | 20 | --------------------------------------------------------------------------------