You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: docs/commands.md
+11-1Lines changed: 11 additions & 1 deletion
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -2,6 +2,16 @@
2
2
3
3
We will use the `<odrv>` as a placeholder for any ODrive object. Every ODrive controller is an ODrive object. In `odrivetool` this is usually `odrv0`. Furthermore we use `<axis>` as a placeholder for any axis, which is an attribute of an ODrive object (for example `odrv0.axis0`). An axis represents where the motors are connected. (axis0 for M0 or axis1 for M1)
Copy file name to clipboardExpand all lines: docs/control.md
+24-3Lines changed: 24 additions & 3 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -4,6 +4,27 @@ The motor controller is a cascaded style position, velocity and current control
4
4
5
5

6
6
7
-
* The position controller is a P loop with a single proportional gain.
8
-
* The velocity controller is a PI loop.
9
-
* The current controller is a PI loop.
7
+
### Position loop:
8
+
The position controller is a P loop with a single proportional gain.
-[Position control of M0](#position-control-of-m0)
19
18
-[What's next?](#whats-next)
20
19
21
-
<!-- /MarkdownTOC-->
20
+
<!-- /TOC-->
22
21
23
22
## Hardware Requirements
24
23
@@ -123,9 +122,9 @@ Try step 5 again
123
122
2. Install the ODrive tools by opening a terminal and typing `pip install odrive` <kbd>Enter</kbd>
124
123
3.__Linux__: set up USB permissions
125
124
```bash
126
-
echo'SUBSYSTEM=="usb", ATTR{idVendor}=="1209", ATTR{idProduct}=="0d[0-9][0-9]", MODE="0666"'| sudo tee /etc/udev/rules.d/50-odrive.rules
125
+
echo'SUBSYSTEM=="usb", ATTR{idVendor}=="1209", ATTR{idProduct}=="0d[0-9][0-9]", MODE="0666"'| sudo tee /etc/udev/rules.d/91-odrive.rules
127
126
sudo udevadm control --reload-rules
128
-
sudo udevadm trigger# until you reboot you may need to do this everytime you reset the ODrive
127
+
sudo udevadm trigger
129
128
```
130
129
131
130
## Start `odrivetool`
@@ -175,7 +174,7 @@ For instance, to set the current limit of M0 to 10A you would type: `odrv0.axis0
175
174
176
175
### 2. Set other hardware parameters:
177
176
178
-
*`odrv0.config.brake_resistance`[Ohm]: This is the resistance of the brake resistor. If you are not using it, you may set it to `0`.
177
+
*`odrv0.config.brake_resistance`[Ohm]: This is the resistance of the brake resistor. If you are not using it, you may set it to `0`. Note that there may be some extra resistance in your wiring and in the screw terminals, so if you are getting issues while braking you may want to increase this parameter by around 0.05 ohm.
179
178
*`odrv0.axis0.motor.config.pole_pairs`: This is the number of **magnet poles** in the rotor, **divided by two**. You can simply count the number of permanent magnets in the rotor, if you can see them. _Note: this is not the same as the number of coils in the stator._
180
179
*`odrv0.axis0.motor.config.motor_type`: This is the type of motor being used. Currently two types of motors are supported: High-current motors (`MOTOR_TYPE_HIGH_CURRENT`) and Gimbal motors (`MOTOR_TYPE_GIMBAL`).
181
180
@@ -229,7 +228,7 @@ Let's get motor 0 up and running. The procedure for motor 1 is exactly the same,
229
228
### Other control modes
230
229
The ODrive also supports velocity control and current (torque) control.
231
230
***Velocity control**: Set `odrv0.axis0.controller.config.control_mode = CTRL_MODE_VELOCITY_CONTROL`. You can now control the velocity with `odrv0.axis0.controller.vel_setpoint = 5000`. Units are counts/s.
232
-
***Current control**: Set `odrv0.axis0.controller.config.control_mode = CTRL_MODE_CURRENT_CONTROL`. You can now control the current with `odrv0.axis0.controller.vel_setpoint = 3`. Units are A. **NOTE**: There is no velocity limiting in current control mode. Make sure that you don't overrev the motor, or exceed the max speed for your encoder.
231
+
***Current control**: Set `odrv0.axis0.controller.config.control_mode = CTRL_MODE_CURRENT_CONTROL`. You can now control the current with `odrv0.axis0.controller.current_setpoint = 3`. Units are A. **NOTE**: There is no velocity limiting in current control mode. Make sure that you don't overrev the motor, or exceed the max speed for your encoder.
Copy file name to clipboardExpand all lines: docs/interfaces.md
+4-7Lines changed: 4 additions & 7 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -5,19 +5,16 @@
5
5
The ODrive can be controlled over various ports and protocols. If you're comfortable with embedded systems development, you can also run custom code directly on the ODrive. For that refer to the [developer documentation](developer-guide.md).
Copy file name to clipboardExpand all lines: docs/odrivetool.md
+13-1Lines changed: 13 additions & 1 deletion
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -2,6 +2,18 @@
2
2
3
3
The ODrive Tool is the accompanying PC program for the ODrive. It's main purpose is to provide an interactive shell to control the device manually, as well as some supporting functions like firmware update.
-[Flashing with an STLink](#flashing-with-an-stlink)
13
+
-[Liveplotter](#liveplotter)
14
+
15
+
<!-- /TOC -->
16
+
5
17
## Installation
6
18
7
19
Refer to the [Getting Started guide](getting-started#downloading-and-installing-tools).
@@ -62,7 +74,7 @@ Note that this command will connect to GitHub servers to retrieve the latest fir
62
74
If you have a non-default configuration saved on the device, ODrive Tool will try to carry over the configuration across the firmware update. If any of the settings are removed or renamed, you will get warning messages.
63
75
64
76
<details><summarymarkdown="span">How to flash a custom firmware</summary><divmarkdown="block">
65
-
If you want to flash a specific firmware file instead of automatically downloading one, you can run `odrivetool dfu [path/to/firmware/file.hex]`.
77
+
If you want to flash a specific firmware file instead of automatically downloading one, you can run `odrivetool dfu path/to/firmware/file.hex`
66
78
67
79
You can download one of the officially released firmware files from [here](https://github.com/madcowswe/ODrive/releases). You will need one of the __.hex__ files (not the __.elf__ file). Make sure you select the file that matches your board version.
-[Other issues that may not produce an error code](#other-issues-that-may-not-produce-an-error-code)
13
+
14
+
<!-- /TOC -->
15
+
3
16
## Error codes
4
17
If your ODrive is not working as expected, run `odrivetool` and type `hex(<axis>.error)` <kbd>Enter</kbd> where `<axis>` is the axis that isn't working. This will display a [hexadecimal](https://en.wikipedia.org/wiki/Hexadecimal) representation of the error code. Each bit represents one error flag.
5
18
@@ -21,18 +34,64 @@ The axis error may say that some other component has failed. Say it reports `ERR
21
34
* Encoder error flags defined [here](../Firmware/MotorControl/encoder.hpp).
22
35
* Sensorless estimator error flags defined [here](../Firmware/MotorControl/sensorless_estimator.hpp).
23
36
24
-
## DRV fault
37
+
## Common Axis Errors
38
+
39
+
*`ERROR_INVALID_STATE = 0x01`
40
+
41
+
Typically returned along with another error. Resolve that error and then reboot using `odrv0.reboot()` or remoivng power, waiting 5 seconds and restoring power to return to normal operating.
42
+
43
+
*`ERROR_DC_BUS_UNDER_VOLTAGE = 0x02`
44
+
45
+
Confirm that your power leads are connected securely. For initial testing a 12V PSU which can supply a couple of amps should be sufficient while the use of low current 'wall wart' plug packs may lead to inconsistent behaviour and is not recommended.
46
+
47
+
You can monitor your PUS voltage using liveplotter in odrive tool by entering `start_liveplotter(lambda: [odrv0.vbus_voltage])`. If you see your votlage drop below ~ 8V then you will trip this error. Even a relatively small motor can draw multiple kW momentary and so unless you have a very large PSU or are running of a battery you may encounter this error when executing high speed movements with a high current limit. To limit your PSU power draw you can limit your motor current and/or velocity limit `odrv0.axis0.controller.config.vel_limit` and `odrv0.axis0.motor.config.current_lim`.
48
+
49
+
*`ERROR_DC_BUS_OVER_VOLTAGE = 0x04`
50
+
51
+
Confirm that you have a break resistor of the correct value connected securly and that `odrv0.config.brake_resistance` is set to the value of your break resistor.
52
+
53
+
You can monitor your PUS voltage using liveplotter in odrive tool by entering `start_liveplotter(lambda: [odrv0.vbus_voltage])`. If during a move you see the voltage rise above your PSU's nominal set voltage then you have your break resistance set too low. This may happen if you are using long wires or small gauge wires to connect your break resistor to your odrive which will added extra resistance. This extra resistance needs to be accounted for to prevent this voltage spike. If you have checked all your connections you can also try increasing your break resistance by ~ 0.01 Ohm at a time to a maximum of 0.05 greater than your break resistor value.
54
+
55
+
## Common Motor Errors
56
+
57
+
*`ERROR_PHASE_RESISTANCE_OUT_OF_RANGE = 0x0001` and `ERROR_PHASE_INDUCTANCE_OUT_OF_RANGE = 0x0002`
58
+
59
+
During calibration the motor resistance and [inductance](https://en.wikipedia.org/wiki/Inductance) is measured. If the measured motor resistance or inductance falls outside a set range this error will be returned. Check that all motor leads are connected securely.
60
+
61
+
The measured values can be viewed using odrivetool as is shown below:
62
+
```
63
+
In [2]: odrv0.axis0.motor.config.phase_inductance
64
+
Out[2]: 1.408751450071577e-05
65
+
66
+
In [3]: odrv0.axis0.motor.config.phase_resistance
67
+
Out[3]: 0.029788672924041748
68
+
```
69
+
Some motors will have a considerably different phase resistance and inductance than this. For example, gimbal motors, some small motors (e.g. < 10A peak current). If you think this applies to you try increasing `odrv0.axis0.motor.config.resistance_calib_max_voltage` from its default value of 1 using odrive tool and repeat the motor calibration process. If your motor has a small peak current draw (e.g. < 20A) you can also try decreasing `odrv0.axis0.motor.config.calibration_current` from its default value of 10A.
70
+
71
+
*`ERROR_DRV_FAULT = 0x0008`
25
72
26
73
The ODrive v3.4 is known to have a hardware issue whereby the motors would stop operating
27
74
when applying high currents to M0. The reported error of both motors in this case
28
75
is `ERROR_DRV_FAULT`.
29
76
30
77
The conjecture is that the high switching current creates large ripples in the
31
-
power supply of the DRV8301 gate driver chips, thus tripping its undervoltage
32
-
fault detection.
78
+
power supply of the DRV8301 gate driver chips, thus tripping its under-voltage fault detection.
33
79
34
-
* Limit the M0 current to 40A. The lowest current at which the DRV fault was observed is 45A on one test motor and 50A on another test motor.
35
-
* Refer to [this post](https://discourse.odriverobotics.com/t/drv-fault-on-odrive-v3-4/558) for instructions for a hardware fix
80
+
To resolve this issue you can limit the M0 current to 40A. The lowest current at which the DRV fault was observed is 45A on one test motor and 50A on another test motor. Refer to [this post](https://discourse.odriverobotics.com/t/drv-fault-on-odrive-v3-4/558) for instructions for a hardware fix.
81
+
82
+
## Common Encoder Errors
83
+
84
+
*`ERROR_CPR_OUT_OF_RANGE = 0x02`
85
+
86
+
Confirm you have entered the correct count per rotation (CPR) for [your encoder](https://docs.odriverobotics.com/encoders). Note that the AMT encoders are configurable using the micro-switches on the encoder PCB and so you may need to check that these are in the right positions. If your encoder lists its pulse per rotation (PPR) multiply that number by four to get CPR.
87
+
88
+
*`ERROR_NO_RESPONSE = 0x04`
89
+
90
+
Confirm that your encoder is plugged into the right pins on the odrive board.
91
+
92
+
*`ERROR_INDEX_NOT_FOUND_YET = 0x20`
93
+
94
+
Check that your encoder is a model that has an index pulse. If your encoder does not have a wire connected to pin Z on your odrive then it does not output an index pulse.
36
95
37
96
38
97
## USB Connectivity Issues
@@ -47,3 +106,42 @@ fault detection.
47
106
* Run `odrivetools` with the `--verbose` option.
48
107
* Run `PYUSB_DEBUG=debug odrivetools` to get even more log output.
49
108
* If you're a developer you can use Wireshark to capture USB traffic.
109
+
* Try a different USB cable
110
+
* Try routing your USB cable so that it is far away from the motor and PSU cables to reduce EMI
111
+
112
+
## Firmware Issues
113
+
114
+
### Failure to build the firmware when running `make`
115
+
- Clear out temporary files from previous compiles by first running `make clean` to prevent conflicts.
116
+
-**Windows users**: Confirm that tup has been correctly added to path by running `env|grep PATH` in Git Bash. If you see no mention of tup then you must [add its location to your PATH environment variable.](https://docs.alfresco.com/4.2/tasks/fot-addpath.html). Note that you may need to restart for the added path to take effect.
117
+
118
+
### Failure to flash the firmware when running `make flash`
119
+
- If using an ST-link, confirm that the ST-link is connected the correct pins and that you have power supplied to the board. This can be by the 5V pin on the ST link or the main DC power jack. No power is supplied over the USB connection.
120
+
121
+
## Other issues that may not produce an error code
122
+
123
+
### Motor cuts off or spins uncontrollably at high rotational speeds (ie: > 5000 RPM)
124
+
- You may be approaching the limit of your encoder. The 2400 count/rotation encoders that were initially included with odrive are realistically limited to around 5000 RPM. Exceeding this speed causes the odrive to lose track of position. This can only be fixed by using an alternative encoder or gearing down the output of your motor onto your encoder so that it still sees < 5000RPM at full speed. If using the gearing options be sure to change your counts/rotation accordingly.
125
+
126
+
### Motor vibrates when stationary or makes constant noise
127
+
128
+
- Likely due to incorrect gains, specifically `vel_gain` may be set too high. Try following the [tuning procedure](https://docs.odriverobotics.com/commands).
129
+
- Check encoder shaft connection. Grub screws may vibrate lose with time. If using a CUI shaft encoder try remounting the plastic retaining ring and confirm that it is not coming into contact with the encoder housing. Also confirm that the encoder is securely mounted.
130
+
- If you are using a high resolution encoder (>4000 counts/rotation) then increasing encoder_pll_bandwidth may help reduce vibration.
131
+
- If you connect your motor to an object with a large moment of inertia (such as a flywheel) this will help reduce vibrations at high gians. However, make sure that all connections are ridged. Cheap shaft couplers or belts under low tension can introduce enough flex into a system that the motor may still vibrate independently.
132
+
133
+
### Motor overshoots target position or oscillates back and forth
134
+
- Likely due to incorrect gains for a given motor current limit. Specifically `pos_gain` is set too high. Try following the [tuning procedure](https://docs.odriverobotics.com/commands).
135
+
- Increase the current limit of your motor for more torque.
136
+
137
+
### Motor slowly starts to increase in speed
138
+
- Encoder has likely slipped. This may occur when your motor makes a hard stop or violently vibrates causing something to come lose. Power the board off and on again so that it undertakes a new calibration. If you are using an index search on startup then you will need to repeat the index calibration process.
139
+
140
+
### Motor feels like it has less torque than it should and/or gets hot sitting still while under no load.
141
+
- Encoder has likely slipped causing the motor controller to commutate the wrong windings slightly which reduces output torque and produces excess heat as the motor 'fights itself'.
142
+
143
+
### False steps or direction changes when using step/dir
144
+
- Prior to Odrive board V3.5 no filtering is present on the GPIO pins used for step/dir interface and so inductively coupled noise may causes false steps to be detected. Odrive V3.5 and has onboard filtering to resolve this issue.
145
+
- If you experience this issue use a twisted pair cable between your microcontroller that’s generating the step/dir signals and your odrive board. A section cut from cat-5 cable works well as does just twisting some normal insulated wire together.
146
+
- Ensure that the step/dir signal cables are not draped over the odrive board, are not running in parallel to the motor or power supply cables.
147
+
- If the above does not resolve your issue on V3.4 boards and lower try adding a ~22 Ohm resistor in series with the step and direction pins along with a ~ 4.7 nF capacitor between the ground pin and the step and dir pins such as shown [here](https://cdn.discordapp.com/attachments/369667319280173069/420811057431445504/IMG_20180306_211224.jpg).
0 commit comments