-
Notifications
You must be signed in to change notification settings - Fork 1.5k
/
odrive-interface.yaml
1741 lines (1653 loc) · 77.4 KB
/
odrive-interface.yaml
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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
---
version: 0.0.1
ns: com.odriverobotics
summary: ODrive Interface Definitions
dictionary: [ODrive] # Prevent the word 'ODrive' from being detected as two words 'O' and 'Drive'
userdata:
c_preamble: |
#include <tuple>
using float2D = std::pair<float, float>;
struct Iph_ABC_t { float phA; float phB; float phC; };
interfaces:
ODrive:
c_is_class: True
brief: Toplevel interface of your ODrive.
doc: |
The odrv0, odrv1, ... objects that appear in odrivetool implement this
toplevel interface.
attributes:
error:
nullflag: NONE
flags:
CONTROL_ITERATION_MISSED:
brief: At least one control iteration was missed.
doc: |
The main control loop is supposed to runs at a fixed frequency.
If the device is computationally overloaded (e.g. too many active
components) it's possible that one or more control iterations
are skipped.
DC_BUS_UNDER_VOLTAGE:
brief: The DC voltage fell below the limit configured in `config.dc_bus_undervoltage_trip_level`.
doc: |
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.
You can monitor your PSU voltage using liveplotter in odrivetool
by entering `start_liveplotter(lambda: [odrv0.vbus_voltage])`. If
you see your votlage drop below `config.dc_bus_undervoltage_trip_level`
(default: ~ 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 `Axis:controller.config.vel_limit` and
`Axis:motor.config.current_lim`.
DC_BUS_OVER_VOLTAGE:
brief: The DC voltage exceeded the limit configured in `config.dc_bus_overvoltage_trip_level`.
doc: |
Confirm that you have a brake resistor of the correct value
connected securely and that `config.brake_resistance` is set to
the value of your brake resistor.
You can monitor your PSU voltage using liveplotter in odrivetool
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 brake resistance set too low. This
may happen if you are using long wires or small gauge wires to
connect your brake 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 brake resistance by
~ 0.01 ohm at a time to a maximum of 0.05 greater than your brake
resistor value.
DC_BUS_OVER_REGEN_CURRENT:
doc: |
Current flowing back into the power supply exceeded `config.dc_max_negative_current`.
This can happen if your brake resistor is disabled or unable to handle the braking current.
Check that `config.enable_brake_resistor` is `True` and that
`(V_power_supply / Brake_resistance) > (total motor.config.current_lim + total motor.config.current_lim_margin)`.
DC_BUS_OVER_CURRENT:
doc: |
Too much current was pulled from the power supply. `ibus` exceeded `config.dc_max_positive_current`.
BRAKE_DEADTIME_VIOLATION:
BRAKE_DUTY_CYCLE_NAN:
INVALID_BRAKE_RESISTANCE: {doc: '`config.brake_resistance` is non-positive or NaN. Make sure that `config.brake_resistance` is a positive number.'}
# BRAKE_RESISTOR_DISARMED:
# doc: The brake resistor was unexpectedly disarmed.
vbus_voltage:
type: readonly float32
unit: V
brief: Voltage on the DC bus as measured by the ODrive.
ibus:
type: readonly float32
unit: A
brief: Current on the DC bus as calculated by the ODrive.
doc: |
A positive value means that the ODrive is consuming power from the power supply,
a negative value means that the ODrive is sourcing power to the power supply.
This value is equal to the sum of the motor currents and the brake resistor currents.
The motor currents are measured, the brake resistor current is calculated based on
`config.brake_resistance`.
ibus_report_filter_k:
type: float32
doc: |
Filter gain for the reported `ibus`. Set to a value below 1.0 to get a smoother
line when plotting `ibus`. Set to 1.0 to disable. This filter is only applied to
the reported value and not for internal calculations.
serial_number: readonly uint64
hw_version_major: readonly uint8
hw_version_minor: readonly uint8
hw_version_variant: readonly uint8
fw_version_major: readonly uint8
fw_version_minor: readonly uint8
fw_version_revision: readonly uint8
fw_version_unreleased:
type: readonly uint8
doc: 0 for official releases, 1 otherwise
brake_resistor_armed: readonly bool
brake_resistor_saturated: readonly bool
brake_resistor_current:
type: readonly float32
doc: Commanded brake resistor current
# Diagnostics & performance monitoring
n_evt_sampling: {type: readonly uint32, doc: Number of input sampling events since startup (modulo 2^32)}
n_evt_control_loop: {type: readonly uint32, doc: Number of control loop iterations since startup (modulo 2^32)}
task_timers_armed:
type: bool
doc: |
Set by a profiling application to trigger sampling of a single
control iteration. Cleared by the device as soon as the sampling
is complete.
task_times:
c_is_class: False
attributes:
sampling: TaskTimer
control_loop_misc: TaskTimer
control_loop_checks: TaskTimer
dc_calib_wait: TaskTimer
system_stats:
c_is_class: False
attributes:
uptime: readonly uint32
min_heap_space: readonly uint32
max_stack_usage_axis: readonly uint32
max_stack_usage_usb: readonly uint32
max_stack_usage_uart: readonly uint32
max_stack_usage_can: readonly uint32
max_stack_usage_startup: readonly uint32
max_stack_usage_analog: readonly uint32
stack_size_axis: readonly uint32
stack_size_usb: readonly uint32
stack_size_uart: readonly uint32
stack_size_startup: readonly uint32
stack_size_can: readonly uint32
stack_size_analog: readonly uint32
prio_axis: readonly int32
prio_usb: readonly int32
prio_uart: readonly int32
prio_startup: readonly int32
prio_can: readonly int32
prio_analog: readonly int32
usb:
c_is_class: False
attributes:
rx_cnt: readonly uint32
tx_cnt: readonly uint32
tx_overrun_cnt: readonly uint32
i2c:
c_is_class: False
attributes:
addr: readonly uint8
addr_match_cnt: readonly uint32
rx_cnt: readonly uint32
error_cnt: readonly uint32
user_config_loaded: readonly uint32
misconfigured:
# TODO: make this a system error
type: readonly bool
doc: |
If this property is true, something is bad in the configuration. The
ODrive can still be used in this state but the user should investigate
which setting is problematic. This variable does not cover all
misconfigurations.
Possible causes:
- A GPIO was set to a mode that it doesn't support
- A GPIO was set to a mode for which the corresponding feature was
not enabled. Example: `GPIO_MODE_UART_A` was used without enabling
`config.enable_uart_a`.
- A feature was enabled which is not supported on this hardware.
Example: `config.enable_uart_c` set to true on ODrive v3.x.
- A GPIO was used as an interrupt input for two internal components
or two GPIOs that are mutually exclusive in their interrupt
capability were both used as interrupt input.
Example: `Axis:config.step_gpio_pin` of both axes were set to the same GPIO.
oscilloscope: {type: Oscilloscope}
can: {type: Can}
test_property: uint32
otp_valid: readonly bool
functions:
test_function: {in: {delta: int32},out: {cnt: int32}}
get_adc_voltage:
in: {gpio: uint32}
out: {voltage: float32}
doc: Reads the ADC voltage of the specified GPIO. The GPIO should be in `GPIO_MODE_ANALOG_IN`.}
save_configuration: {out: {success: bool}, doc: Saves the current configuration to non-volatile memory and reboots the board.}
erase_configuration:
doc: Resets all `config` variables to their default values and reboots the controller
reboot:
doc: Reboots the controller without saving the current configuraiton
enter_dfu_mode:
doc: Enters the Device Firmware Update mode
get_interrupt_status:
in: {irqn: {type: int32, doc: '-12...-1: processor interrupts, 0...239: NVIC interrupts'}}
out:
status:
type: uint32
doc: |
bit 31: enabled (1) or disabled (0)
bits 30:8: number of times the interrupt fired (modulo 0x800000)
bits 7:0: priority (0 is highest priority)
0xffffffff if the specified number is not a valid interrupt number.
doc: Returns information about the specified interrupt number.
get_dma_status:
in: {stream_num: {type: uint8, doc: '0...7: DMA1 streams, 8...15: DMA2 streams'}}
out:
status:
type: uint32
doc: |
bit 31: zero if the stream's configuration is equal to the reset state
bits 4:2: channel
bits 1:0: priority (3 is highest priority)
0xffffffff if the specified number is not a valid DMA stream number.
doc: Returns information about the specified DMA stream.
get_gpio_states:
out: {status: {type: uint32}}
doc: Returns the logic states of all GPIOs. Bit i represents the state of GPIOi.
get_drv_fault: {out: {drv_fault: uint64}}
clear_errors:
doc: Clear all the errors of this device including all contained submodules.
ODrive.Config:
c_is_class: False
attributes:
enable_uart_a:
type: bool
brief: Enables/disables UART_A.
doc: |
You also need to set the corresponding GPIOs to GPIO_MODE_UART_A.
Refer to [interfaces](interfaces.md) to see which pins support UART_A.
Changing this requires a reboot.
enable_uart_b:
type: bool
brief: Enables/disables UART_B.
doc: |
You also need to set the corresponding GPIOs to GPIO_MODE_UART_B.
Refer to [interfaces](interfaces.md) to see which pins support UART_B.
Changing this requires a reboot.
enable_uart_c: {type: bool, doc: Not supported on ODrive v3.x.}
uart_a_baudrate:
type: uint32
unit: baud/s
brief: Defines the baudrate used on the UART interface.
doc: |
Some baudrates will have a small timing error due to hardware limitations.
Here's an (incomplete) list of baudrates for ODrive v3.x:
+-------------+---------------+-----------+
| Configured | Actual | Error [%] |
+=============+===============+===========+
| 1.2 KBps | 1.2 KBps | 0 |
+-------------+---------------+-----------+
| 2.4 KBps | 2.4 KBps | 0 |
+-------------+---------------+-----------+
| 9.6 KBps | 9.6 KBps | 0 |
+-------------+---------------+-----------+
| 19.2 KBps | 19.195 KBps | 0.02 |
+-------------+---------------+-----------+
| 38.4 KBps | 38.391 KBps | 0.02 |
+-------------+---------------+-----------+
| 57.6 KBps | 57.613 KBps | 0.02 |
+-------------+---------------+-----------+
| 115.2 KBps | 115.068 KBps | 0.11 |
+-------------+---------------+-----------+
| 230.4 KBps | 230.769 KBps | 0.16 |
+-------------+---------------+-----------+
| 460.8 KBps | 461.538 KBps | 0.16 |
+-------------+---------------+-----------+
| 921.6 KBps | 913.043 KBps | 0.93 |
+-------------+---------------+-----------+
| 1.792 MBps | 1.826 MBps | 1.9 |
+-------------+---------------+-----------+
| 1.8432 MBps | 1.826 MBps | 0.93 |
+-------------+---------------+-----------+
For more information refer to Section 30.3.4 and Table 142 (the column with f_PCLK = 42 MHz) in the
`STM datasheet <https://www.st.com/content/ccc/resource/technical/document/reference_manual/3d/6d/5a/66/b4/99/40/d4/DM00031020.pdf/files/DM00031020.pdf/jcr:content/translations/en.DM00031020.pdf>`__.
uart_b_baudrate:
type: uint32
unit: baud/s
brief: Defines the baudrate used on the UART interface.
doc: See `uart_a_baudrate` for details.
uart_c_baudrate: {type: uint32, doc: Not supported on ODrive v3.x.}
enable_can_a:
type: bool
doc: |
Enables CAN. Changing this setting requires a reboot.
enable_i2c_a:
type: bool
doc: |
Enables I2C. The I2C pins on ODrive v3.x are in conflict with CAN.
This setting has no effect if `enable_can_a` is also true.
This setting has no effect on ODrive v3.2 or earlier.
Changing this setting requires a reboot.
usb_cdc_protocol:
type: StreamProtocolType
doc: |
The protocol that's being run on the device's virtual COM port on
USB.
Note that the ODrive has two independent interfaces on USB: One
is the virtual COM port (affected by this option) and the other
one is a vendor specific interface which always runs Fibre.
So changing this option does not affect the working of odrivetool.
uart0_protocol: StreamProtocolType
uart1_protocol: StreamProtocolType
uart2_protocol: StreamProtocolType
max_regen_current:
type: float32
unit: Amps
doc: |
The bus current allowed to flow back to the power supply before the brake resistor module will start shunting current.
brake_resistance:
type: float32
unit: ohm
brief: Value of the brake resistor connected to the ODrive.
doc: |
If you set this to a lower value than the true brake resistance
then the ODrive will not meed the `max_regen_current` constraint
during braking, that is it will sink more than `max_regen_current`
into the power supply. Some power supplies don't like this.
If you set this to a higher value than the true brake resistance
then the ODrive will unnecessarily burn more power than required
during braking.
enable_brake_resistor:
type: bool
brief: Enable/disable the use of a brake resistor.
doc: |
Setting this to False even though a brake resistor is connected is
harmless. Setting this to True even though no brake resistor is
connected can break the power supply.
Changes to this value require a reboot to take effect.
dc_bus_undervoltage_trip_level:
type: float32
unit: V
brief: Minimum voltage below which the motor stops operating.
dc_bus_overvoltage_trip_level:
type: float32
unit: V
brief: Maximum voltage above which the motor stops operating.
doc: |
This protects against cases in which the power supply fails to dissipate
the brake power if the brake resistor is disabled.
The default is 26V for the 24V board version and 52V for the 48V board version.
enable_dc_bus_overvoltage_ramp:
type: bool
status: experimental
brief: Enables the DC bus overvoltage ramp feature.
doc: |
If enabled, if the measured DC voltage exceeds `dc_bus_overvoltage_ramp_start`,
the ODrive will sink more power than usual into the the brake resistor
in an attempt to bring the voltage down again.
The brake duty cycle is increased by the following amount:
* `ODrive:vbus_voltage` == `dc_bus_overvoltage_ramp_start` => brake_duty_cycle += 0%
* `ODrive:vbus_voltage` == `dc_bus_overvoltage_ramp_end` => brake_duty_cycle += 100%
Remarks:
- This feature is active even when all motors are disarmed.
- This feature is disabled if `brake_resistance` is non-positive.
dc_bus_overvoltage_ramp_start:
type: float32
status: experimental
brief: See `enable_dc_bus_overvoltage_ramp`.
doc: Do not set this lower than your usual `ODrive:vbus_voltage`,
unless you like fried brake resistors.
dc_bus_overvoltage_ramp_end:
type: float32
status: experimental
brief: See `enable_dc_bus_overvoltage_ramp`.
doc: Must be larger than `dc_bus_overvoltage_ramp_start`,
otherwise the ramp feature is disabled.
dc_max_positive_current:
type: float32
unit: A
brief: Max current the power supply can source.
dc_max_negative_current:
type: float32
unit: A
brief: Max current the power supply can sink.
doc: |
You most likely want a non-positive value here. Set to -INFINITY to disable.
Note: This should be greater in magnitude than `max_regen_current`
error_gpio_pin: {type: uint32}
gpio3_analog_mapping: {type: Endpoint, c_name: 'analog_mappings[3]', doc: Make sure the corresponding GPIO is in `GPIO_MODE_ANALOG_IN`.}
gpio4_analog_mapping: {type: Endpoint, c_name: 'analog_mappings[4]', doc: Make sure the corresponding GPIO is in `GPIO_MODE_ANALOG_IN`.}
ODrive.Can:
c_is_class: True
attributes:
error:
nullflag: NONE
flags: {DUPLICATE_CAN_IDS: }
config:
c_is_class: False
attributes:
baud_rate: {type: uint32, c_setter: 'set_baud_rate'}
protocol:
type: Protocol
ODrive.Endpoint:
c_is_class: False
attributes:
endpoint: endpoint_ref
min: float32
max: float32
ODrive.Axis:
c_is_class: True
attributes:
error:
nullflag: NONE
flags:
INVALID_STATE:
brief: An invalid state was requested.
doc: |
You tried to run a state before you are allowed to. Typically you
tried to run encoder calibration or closed loop control before the
motor was calibrated, or you tried to run closed loop control
before the encoder was calibrated.
MOTOR_FAILED:
bit: 6
doc: Check `motor.error` for more information.
SENSORLESS_ESTIMATOR_FAILED:
ENCODER_FAILED:
doc: Check `encoder.error` for more information.
CONTROLLER_FAILED:
WATCHDOG_TIMER_EXPIRED:
bit: 11
brief: The axis watchdog timer expired.
doc: |
An amount of time greater than `config.watchdog_timeout` passed
without the watchdog being fed.
MIN_ENDSTOP_PRESSED:
brief: The min endstop was pressed
MAX_ENDSTOP_PRESSED:
brief: The max endstop was pressed
ESTOP_REQUESTED:
brief: The estop message was sent over CAN
HOMING_WITHOUT_ENDSTOP:
bit: 17
doc: the min endstop was not enabled during homing
OVER_TEMP:
# unused
doc: Check `motor.error` for more details.
UNKNOWN_POSITION:
doc: There isn't a valid position estimate available.
step_dir_active: readonly bool
last_drv_fault: readonly uint32
steps:
type: readonly int64
brief: The current commanded position, in steps, while in `step_dir` mode
current_state:
type: readonly AxisState
brief: The current state of the axis
requested_state:
type: AxisState
brief: The user's commanded axis state
doc: |
This is used to command the axis to change state or perform certain routines.
Values input here will be "consumed" and queued by the state machine handler. Thus, reading this value back will usually show `UNDEFINED` (0).
is_homed:
type: bool
c_name: homing_.is_homed
brief: Whether or not the axis has been successfully homed.
config:
c_is_class: False
attributes:
startup_motor_calibration:
type: bool
doc: Run motor calibration at startup, skip otherwise
startup_encoder_index_search:
type: bool
doc: Run encoder index search after startup, skip otherwise this only has an effect if encoder.config.use_index is also true
startup_encoder_offset_calibration:
type: bool
doc: Run encoder offset calibration after startup, skip otherwise
startup_closed_loop_control:
type: bool
doc: Enable closed loop control after calibration/startup
startup_homing:
type: bool
doc: Enable homing after calibration/startup
enable_step_dir:
type: bool
doc: |
Enable step/dir input after calibration.
Make sure to set the corresponding GPIO's mode to `GPIO_MODE_DIGITAL`.
step_dir_always_on:
type: bool
doc: |
Keep step/dir enabled while the motor is disabled.
This is ignored if enable_step_dir is false.
This setting only takes effect on a state transition
into idle or out of closed loop control.
enable_sensorless_mode: bool
watchdog_timeout:
type: float32
unit: s
enable_watchdog: bool
step_gpio_pin: {type: uint16, c_setter: 'set_step_gpio_pin'}
dir_gpio_pin: {type: uint16, c_setter: 'set_dir_gpio_pin'}
calibration_lockin: # TODO: this is a subset of lockin state
c_is_class: False
attributes:
current: float32
ramp_time: float32
ramp_distance: float32
accel: float32
vel: float32
sensorless_ramp: LockinConfig
general_lockin: LockinConfig
can: CanConfig
motor: Motor
controller: Controller
encoder: Encoder
acim_estimator: AcimEstimator
sensorless_estimator: SensorlessEstimator
trap_traj: TrapezoidalTrajectory
min_endstop: Endstop
max_endstop: Endstop
mechanical_brake: MechanicalBrake
task_times:
c_is_class: False
attributes:
thermistor_update: TaskTimer
encoder_update: TaskTimer
sensorless_estimator_update: TaskTimer
endstop_update: TaskTimer
can_heartbeat: TaskTimer
controller_update: TaskTimer
open_loop_controller_update: TaskTimer
acim_estimator_update: TaskTimer
motor_update: TaskTimer
current_controller_update: TaskTimer
dc_calib: TaskTimer
current_sense: TaskTimer
pwm_update: TaskTimer
functions:
watchdog_feed:
doc: Feed the watchdog to prevent watchdog timeouts.
ODrive.Axis.LockinConfig:
c_is_class: False
attributes:
current:
type: float32
unit: A
ramp_time:
type: float32
unit: s
ramp_distance:
type: float32
unit: rad
accel:
type: float32
unit: rad/s^2
vel:
type: float32
unit: rad/s
finish_distance:
type: float32
unit: rad
finish_on_vel: bool
finish_on_distance: bool
finish_on_enc_idx: bool
ODrive.Axis.CanConfig:
c_is_class: False
attributes:
node_id: uint32
is_extended: bool
heartbeat_rate_ms: uint32
encoder_rate_ms: uint32
motor_error_rate_ms: uint32
encoder_error_rate_ms: uint32
controller_error_rate_ms: uint32
sensorless_error_rate_ms: uint32
encoder_count_rate_ms: uint32
iq_rate_ms: uint32
sensorless_rate_ms: uint32
bus_vi_rate_ms: uint32
ODrive.ThermistorCurrentLimiter:
c_is_class: False
ODrive.OnboardThermistorCurrentLimiter:
c_is_class: True
attributes:
temperature:
type: readonly float32
unit: °C
config:
c_is_class: False
attributes:
temp_limit_lower:
type: float32
doc: The lower limit when the controller starts limiting current.
temp_limit_upper:
type: float32
doc: The upper limit when current limit reaches 0 Amps and an over temperature error is triggered.
enabled: {type: bool, doc: Whether this thermistor is enabled. }
ODrive.OffboardThermistorCurrentLimiter:
c_is_class: True
attributes:
temperature:
type: readonly float32
unit: °C
config:
c_is_class: False
attributes:
gpio_pin: {type: uint16, c_setter: set_gpio_pin}
poly_coefficient_0: {type: float32, c_name: 'thermistor_poly_coeffs[0]'}
poly_coefficient_1: {type: float32, c_name: 'thermistor_poly_coeffs[1]'}
poly_coefficient_2: {type: float32, c_name: 'thermistor_poly_coeffs[2]'}
poly_coefficient_3: {type: float32, c_name: 'thermistor_poly_coeffs[3]'}
temp_limit_lower:
type: float32
doc: The lower limit when the controller starts limiting current.
temp_limit_upper:
type: float32
doc: The upper limit when current limit reaches 0 Amps and an over temperature error is triggered.
enabled: {type: bool, doc: Whether this thermistor is enabled. }
ODrive.Motor:
c_is_class: True
attributes:
last_error_time: float32
error:
nullflag: NONE
flags:
PHASE_RESISTANCE_OUT_OF_RANGE:
brief: The measured motor phase resistance is outside of the plausible range.
doc: |
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.
The measured values can be viewed using odrivetool as is shown below:
```
In [2]: odrv0.axis0.motor.config.phase_inductance
Out[2]: 1.408751450071577e-05
In [3]: odrv0.axis0.motor.config.phase_resistance
Out[3]: 0.029788672924041748
```
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 `config.resistance_calib_max_voltage` from
its default value of 1 using odrivetool and repeat the motor
calibration process. If your motor has a small peak current draw
(e.g. < 20A) you can also try decreasing
`config.calibration_current` from its default value of 10A.
In general, you need
```text
resistance_calib_max_voltage > calibration_current * phase_resistance
resistance_calib_max_voltage < 0.5 * vbus_voltage
```
PHASE_INDUCTANCE_OUT_OF_RANGE:
brief: The measured motor phase inductance is outside of the plausible range.
doc: |
See `PHASE_RESISTANCE_OUT_OF_RANGE` for details.
DRV_FAULT:
bit: 3
brief: The gate driver chip reported an error.
doc: |
The ODrive v3.4 is known to have a hardware issue whereby the
motors would stop operating when applying high currents to M0. The
reported error of both motors in this case is `ERROR_DRV_FAULT`.
The conjecture is that the high switching current creates large
ripples in the power supply of the DRV8301 gate driver chips, thus
tripping its under-voltage fault detection.
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.
CONTROL_DEADLINE_MISSED:
MODULATION_MAGNITUDE:
bit: 7
doc: |
The bus voltage was insufficent to push the requested current
through the motor.
If you are getting this during motor calibration, make sure that
`config.resistance_calib_max_voltage` is no more than half
your bus voltage.
For gimbal motors, it is recommended to set the
`config.calibration_current` and `config.current_lim`
to half your bus voltage, or less.
CURRENT_SENSE_SATURATION:
bit: 10
doc: |
The current sense circuit saturated the current sense amplifier.
This can be caused by setting `config.current_lim` higher than
`config.requested_current_range`. If this happens, increase the
requested current range, save the configuration, and reboot the controller.
CURRENT_LIMIT_VIOLATION:
bit: 12
doc: |
The motor current exceeded `motor.config.current_lim + motor.config.current_lim_margin`.
The current controller is a PI controller, so it can experience overshoot. The PI gains
are automatically calculated based on `config.current_control_bandwidth` and the
motor resistance and inductance (pole placement). Some overshoot is normal, so a sensible
solution is to increase the current limit margin if your current limit is large.
MODULATION_IS_NAN: {bit: 16}
MOTOR_THERMISTOR_OVER_TEMP: {doc: The motor thermistor measured a temperature above motor.motor_thermistor.config.temp_limit_upper}
FET_THERMISTOR_OVER_TEMP: {doc: The inverter thermistor measured a temperature above motor.fet_thermistor.config.temp_limit_upper}
TIMER_UPDATE_MISSED: {doc: A timer update event was missed. Perhaps the previous timer update took too much time. This is not expected in official release firmware.}
CURRENT_MEASUREMENT_UNAVAILABLE: {doc: The phase current measurement is not available. The ADC failed to sample the current sensor in time. This is not expected in official release firmware.}
CONTROLLER_FAILED: {doc: The motor was disarmed because the underlying controller failed. Usually this is the FOC controller.}
I_BUS_OUT_OF_RANGE:
doc: |
The DC current sourced/sunk by this motor exceeded the configured
hard limits. More specifically `I_bus` fell outside of the range
`config.I_bus_hard_min` ... `config.I_bus_hard_max`.
BRAKE_RESISTOR_DISARMED:
doc: |
An attempt was made to run the motor PWM while the brake resistor was configured as enabled
(`config.enable_brake_resistor`) but disarmed.
The most common cause is that you just set `config.enable_brake_resistor` to `True` but didn't
arm the brake resistor yet (by either rebooting or running `odrvX.clear_errors()`).
Otherwise, the brake resistor can be disarmed due to various system-wide errors.
The root cause will usually show up under `system` when you run `dump_errors(odrvX)`.
To re-arm the brake resistor reboot the ODrive or run `odrvX.clear_errors()`.
SYSTEM_LEVEL:
doc: |
The motor had to be disarmed because of a system level error.
See `ODrive:error` for more details.
BAD_TIMING: {doc: The main control loop got out of sync with the motor control loop. This could indicate that the main control loop got stuck.}
UNKNOWN_PHASE_ESTIMATE: {doc: The current controller did not get a valid angle input. Maybe you didn't calibrate the encoder.}
UNKNOWN_PHASE_VEL: {doc: The motor controller did not get a valid phase velocity input.}
UNKNOWN_TORQUE: {doc: The motor controller did not get a valid torque input.}
UNKNOWN_CURRENT_COMMAND: {doc: The current controller did not get a valid current setpoint. Maybe you didn't configure the controller correctly.}
UNKNOWN_CURRENT_MEASUREMENT: {doc: The current controller did not get a valid current measurement.}
UNKNOWN_VBUS_VOLTAGE: {doc: 'The current controller did not get a valid `ODrive:vbus_voltage` measurement.'}
UNKNOWN_VOLTAGE_COMMAND: {doc: The current controller did not get a valid feedforward voltage setpoint.}
UNKNOWN_GAINS: {doc: The current controller gains were not configured. Run motor calibration or set `config.phase_resistance` and `config.phase_inductance` manually.}
CONTROLLER_INITIALIZING: {doc: Internal value used while the controller is not yet ready to generate PWM timings.}
UNBALANCED_PHASES: {doc: The motor phases are not balanced.}
is_armed: readonly bool
is_calibrated: readonly bool
current_meas_phA: {type: readonly float32, c_getter: 'current_meas_.value_or(Iph_ABC_t{0.0f, 0.0f, 0.0f}).phA'}
current_meas_phB: {type: readonly float32, c_getter: 'current_meas_.value_or(Iph_ABC_t{0.0f, 0.0f, 0.0f}).phB'}
current_meas_phC: {type: readonly float32, c_getter: 'current_meas_.value_or(Iph_ABC_t{0.0f, 0.0f, 0.0f}).phC'}
DC_calib_phA: {type: float32, c_name: DC_calib_.phA}
DC_calib_phB: {type: float32, c_name: DC_calib_.phB}
DC_calib_phC: {type: float32, c_name: DC_calib_.phC}
I_bus: {type: readonly float32, unit: A, doc: The current in the ODrive DC bus. This is also the current seen by the power supply in most systems.}
phase_current_rev_gain: float32
effective_current_lim:
type: readonly float32
unit: A
doc: |
This value is the internally-limited value of phase current allowed according to the set current limit and the FET and Motor thermistor limits.
max_allowed_current:
type: readonly float32
unit: A
doc: |
Indicates the maximum current that can be measured by the current
sensors in the current hardware configuration. This value depends on
`config.requested_current_range`.
max_dc_calib: {type: readonly float32, unit: A}
fet_thermistor: OnboardThermistorCurrentLimiter
motor_thermistor: OffboardThermistorCurrentLimiter
current_control:
c_is_class: True
attributes:
p_gain: {type: readonly float32, c_getter: 'pi_gains_.value_or(float2D{0.0f, 0.0f}).first'}
i_gain: {type: readonly float32, c_getter: 'pi_gains_.value_or(float2D{0.0f, 0.0f}).second'}
I_measured_report_filter_k: float32
Id_setpoint: {type: readonly float32, c_getter: 'Idq_setpoint_.value_or(float2D{0.0f, 0.0f}).first'}
Iq_setpoint: {type: readonly float32, c_getter: 'Idq_setpoint_.value_or(float2D{0.0f, 0.0f}).second'}
Vd_setpoint: {type: readonly float32, c_getter: 'Vdq_setpoint_.value_or(float2D{0.0f, 0.0f}).first'}
Vq_setpoint: {type: readonly float32, c_getter: 'Vdq_setpoint_.value_or(float2D{0.0f, 0.0f}).second'}
phase: {type: readonly float32, c_getter: 'phase_.value_or(0.0f)'}
phase_vel: {type: readonly float32, c_getter: 'phase_vel_.value_or(0.0f)'}
Ialpha_measured: {type: readonly float32, c_getter: 'Ialpha_beta_measured_.value_or(float2D{0.0f, 0.0f}).first'}
Ibeta_measured: {type: readonly float32, c_getter: 'Ialpha_beta_measured_.value_or(float2D{0.0f, 0.0f}).second'}
Id_measured:
type: readonly float32
unit: A
doc: |
The phase current measured along the "d" axis in the FOC control loop. This should be close to 0 for typical surface permanent magnet motors.
Iq_measured:
type: readonly float32
unit: A
doc: |
The phase current measured along the "q" axis in the FOC control loop. This is the torque-generating current, so motor torque is approx. `torque_constant * Iq_measured`
power:
type: readonly float32
unit: W
doc: |
The electrical power being delivered to the motor
v_current_control_integral_d: float32
v_current_control_integral_q: float32
final_v_alpha: readonly float32
final_v_beta: readonly float32
n_evt_current_measurement: {type: readonly uint32, doc: Number of current measurement events since startup (modulo 2^32)}
n_evt_pwm_update: {type: readonly uint32, doc: Number of PWM update events since startup (modulo 2^32)}
config:
c_is_class: False
attributes:
pre_calibrated:
type: bool
c_setter: set_pre_calibrated
doc: |
Indicates to the ODrive that the parameters `config.phase_resistance` and `config.phase_inductance` are valid at system start.
If these are valid and `pre_calibrated` is set to `True`, motor calibration can be skipped.
pole_pairs:
type: int32
doc: |
The number of pole pairs in the motor.
Note this is equal to 1/2 of the number of magnets (not coils!) in a typical hobby motor.
calibration_current:
type: float32
doc: The current used to measure resistance during `AXIS_STATE_MOTOR_CALIBRATION`.
resistance_calib_max_voltage:
type: float32
doc: |
The maximum voltage allowed during `AXIS_STATE_MOTOR_CALIBRATION`.
This should be set to less than `(0.5 * vbus_voltage)`, but high enough to satisfy V=IR during motor calibration, where I is `config.calibration_current` and R is `config.phase_resistance`
phase_inductance: {type: float32, unit: henry, c_setter: set_phase_inductance}
phase_resistance: {type: float32, unit: ohm, c_setter: set_phase_resistance}
torque_constant: {type: float32, unit: N·m/A}
motor_type: MotorType
current_lim:
type: float32
unit: A
doc: Maximum commanded current allowed
current_lim_margin:
type: float32
unit: A
doc: Maximum measured current allowed above `current_lim`. Any value above `current_lim + curren_lim_margin` will throw a `CURRENT_LIMIT_VIOLATION` error.
torque_lim:
type: float32
unit: N·m
doc: Maximum commanded torque allowed in the torque loop.
inverter_temp_limit_lower:
type: float32
unit: °C
doc: Not implemented.
inverter_temp_limit_upper:
type: float32
unit: °C
doc: Not implemented.
requested_current_range:
type: float32
unit: A
doc: |
The minimum phase current range expected to be measured. This is used to set the current shunt amplifier gains.
This should be set > `current_lim + curren_lim_margin`, but as low as possible to maximize precision and accuracy of the controller.
current_control_bandwidth:
type: float32
c_setter: set_current_control_bandwidth
unit: rad/s
doc: |
Sets the PI gains of the Q and D axis FOC control according to `phase_resistance` and `phase_inductance` to create a critically-damped controller with a -3dB
bandwidth at this frequency.
acim_gain_min_flux: float32
acim_autoflux_min_Id: float32
acim_autoflux_enable: bool
acim_autoflux_attack_gain: float32
acim_autoflux_decay_gain: float32
R_wL_FF_enable:
type: bool
doc: Enables automatic feedforward of the R*wL term in the current controller.
bEMF_FF_enable:
type: bool
doc: Enables automatic feedforward of the bEMF term in the current controller.
I_bus_hard_min:
type: float32
unit: A
doc: |
If the controller fails to keep this motor's DC current (`ODrive.Motor:I_bus`)
above this value the motor gets disarmed immediately. Most likely
you want a negative value here. Set to -inf to disable. Take noise
into account when chosing a value.
I_bus_hard_max:
type: float32
unit: A
doc: |
If the controller fails to keep this motor's DC current (`ODrive.Motor:I_bus`)
below this value the motor gets disarmed immediately. Usually this
is set in conjunction with `I_bus_hard_min`. Set to inf to disable.
Take noise into account when chosing a value.
I_leak_max:
type: float32
unit: A
doc: |
In almost all scenarios, the currents on phase A, B and C should
add up to zero. A small amount of measurement noise is expected.
However if the sum of A, B, C currents exceeds this configuration
value, the motor gets disarmed immediately.
Note that this feature is only works on devices with three current
sensors (e.g. ODrive v4).
dc_calib_tau: float32
ODrive.Oscilloscope:
c_is_class: True
attributes:
size: readonly uint32
functions:
get_val: {in: {index: uint32}, out: {val: float32}}
ODrive.AcimEstimator:
c_is_class: True
attributes:
rotor_flux: {type: readonly float32, unit: A, doc: estimated magnitude of the rotor flux}
slip_vel:
type: readonly float32
unit: rad/s
doc: estimated slip between physical and electrical angular velocity}
c_getter: slip_vel_.any().value_or(0.0f)
phase_offset:
type: readonly float32
unit: rad
doc: estimate offset between physical and electrical angular position}
stator_phase_vel:
type: readonly float32
unit: rad/s
doc: calculated setpoint for the electrical velocity}
c_getter: stator_phase_vel_.any().value_or(0.0f)
stator_phase:
type: readonly float32
unit: rad
doc: calculated setpoint for the electrical phase}
c_getter: stator_phase_.any().value_or(0.0f)
config:
c_is_class: False
attributes:
slip_velocity: float32
ODrive.Controller:
c_is_class: True
attributes:
error:
nullflag: NONE
flags:
OVERSPEED:
brief: Motor speed exceeded `config.vel_limit * config.vel_limit_tolerance` and `config.enable_overspeed_error` was enabled.
doc: |
Try increasing `config.vel_limit`. The default of 2 turns per second
gives a motor speed of only 120 RPM. Note: Even if
you do not command your motor to exceed `config.vel_limit`,
sudden changes in the load placed on a motor may cause this speed
to be temporarily exceeded, resulting in this error.
You can also try increasing `config.vel_limit_tolerance`. The
default value of 1.2 means it will only allow a 20% violation of
the speed limit. You can set `config.enable_overspeed_error` to False
to disable this error.
INVALID_INPUT_MODE:
brief: The `config.input_mode` setting was set to an invalid value. See InputMode for available values
doc: |
Input modes and control modes are separate concepts. A control mode sets the type of control to be used,
like position, velocity, or torque control. Input modes modify the input given (`input_pos`, etc) to
give desired behavior. For example, in position *control mode*, the position filter *input mode* will
smooth out `input_pos` commands to give smoother motion.
UNSTABLE_GAIN: