Skip to content

Commit

Permalink
Revert "Revert "Upgrades default ODriveFirmware to 0.5.4""
Browse files Browse the repository at this point in the history
This reverts commit eb13576.
  • Loading branch information
tobbelobb committed May 13, 2022
1 parent 9e637ff commit 722ee51
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 835 deletions.
36 changes: 12 additions & 24 deletions firmware/ODrive/README.md
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
## ODrive Usage On Hangprinter

Use stock ODrive Firmware version 0.5.1.
I have not been able to make anti-cogging calibration work in later versions.
I have tested 0.5.2 and 0.5.4.
Use stock ODrive Firmware version 0.5.4 or later.

Use a <a href="https://odriverobotics.com/shop/usb-isolator">USB isolator</a> between your laptop and your ODrive.

Expand All @@ -23,30 +21,20 @@ $ odrivetool restore-config odrive-config-AB.json # With AB ODrive connected
$ odrivetool restore-config odrive-config-CD.json # With CD ODrive connected
```

I haven't tried this myself, but at least one user has reported saving time by doing ODrive config this way.
Be aware that some lower level config will be slightly off/wrong in your ODrive after you "restore" from my backup.
I know at least these config values will be slightly off:

```
odrv0.axis0.encoder.config.offset_float
odrv0.axis0.encoder.config.offset
odrv0.axis1.encoder.config.offset_float
odrv0.axis1.encoder.config.offset
odrv0.axis0.motor.config.phase_inductance
odrv0.axis0.motor.config.phase_resistance
odrv0.axis1.motor.config.phase_inductance
odrv0.axis1.motor.config.phase_resistance
After those commands, you need to confirm that your break resistance matches the configured one.
You also need to do a calibration sequence and set a couple of variables:
odrivetool:
```

My guess is that they can get fixed up by a few commands in the odrivetool:
```
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH
# wait...
odrv0.axis1.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH
odrv0.config.brake_resistance = your_measured_value
odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE
# wait...
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
odrv0.axis1.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE
# wait...
odrv0.axis1.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
odrv0.axis0.encoder.config.pre_calibrated = True
odrv0.axis1.encoder.config.pre_calibrated = True
odrv0.axis0.requested_state = AXIS_STATE_IDLE
odrv0.axis1.requested_state = AXIS_STATE_IDLE
odrv0.save_configuration()
# wait...
```

Expand Down
41 changes: 22 additions & 19 deletions firmware/ODrive/configure_odrive.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,13 @@
# Hangprinter version 4 configures its ODrives like is described in this file

# WARNING: Use ODriveFirmware version 0.5.1.
# I have not been able to make later versions work
# I have tested 0.5.2 and 0.5.4
# These instructions work for ODriveFirmware version 0.5.4.
# Some comments in here might help you if you use earlier versions as well.

#odrv0.config.brake_resistance = 0.4699999988079071 # Or 2.0. You need to check this with a multimeter

# Later ODrive Firmware versions (0.5.2 onwards) might disable break resistor by default
# So you need to set a boolean to true to enable it again:
#odrv0.config.enable_brake_resistor = True;
odrv0.config.enable_brake_resistor = True;

#odrv0.axis0.motor.config.pole_pairs = 7 # Default
#odrv0.axis0.controller.torque_setpoint = 0 # Default. Torque mode with zero torque
Expand Down Expand Up @@ -47,9 +46,6 @@
odrv0.axis0.encoder.config.use_index = True
odrv0.axis1.encoder.config.use_index = True

odrv0.save_configuration()
odrv0.reboot() # Reboot is automatic upon save_configuration() for newer fw versions

odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE
odrv0.axis1.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

Expand Down Expand Up @@ -79,30 +75,35 @@
odrv0.axis1.config.startup_closed_loop_control = True

# Interface
odrv0.config.enable_uart = False # enable_uart_a = False in fw 0.5.4
#odrv0.config.enable_uart = False # before fw 0.5.2
odrv0.config.enable_uart_a = False # in fw 0.5.2 onwards

#odrv0.can.set_baud_rate(250000) # Default
odrv0.can.config.protocol = 0 # This changes to 0x1 somewhere between 0.5.1 and 0.5.4. So if you have a late firmware, it should be 1.
# odrv0.axis0.config.can_node_id = 40 # A. config.can.node_id in later fw versions
# odrv0.axis1.config.can_node_id = 41 # B
odrv0.can.config.protocol = 1 # This changes to 0x1 somewhere between 0.5.1 and 0.5.4. So if you have an older firmware, it should be 0.
# odrv0.axis0.config.can.node_id = 40 # A. config.can_node_id in fw versions older than 0.5.2
# odrv0.axis1.config.can.node_id = 41 # B
# For the other board
odrv0.axis0.config.can_node_id = 42 # C
odrv0.axis1.config.can_node_id = 43 # D
odrv0.axis0.config.can.node_id = 42 # C
odrv0.axis1.config.can.node_id = 43 # D

odrv0.axis0.config.step_gpio_pin = 1
odrv0.axis0.config.dir_gpio_pin = 2
#odrv0.axis0.controller.config.steps_per_circular_range = 400 # 25*16 (on newer fw versions)
odrv0.axis0.config.turns_per_step = 0.0025 # 1/(25*16) = 0.0025
odrv0.axis0.controller.config.steps_per_circular_range = 400 # 25*16 (on newer fw versions)
#odrv0.axis0.config.turns_per_step = 0.0025 # 1/(25*16) = 0.0025 # on older fw versions
odrv0.axis0.config.enable_step_dir = True

#odrv0.axis1.config.step_gpio_pin = 7 # Default
#odrv0.axis1.config.dir_gpio_pin = 8 # Default
#odrv0.axis1.controller.config.steps_per_circular_range = 400 # 25*16
odrv0.axis1.config.turns_per_step = 0.0025 # 1/(25*16) = 0.0025
odrv0.axis1.controller.config.steps_per_circular_range = 400 # 25*16
#odrv0.axis1.config.turns_per_step = 0.0025 # 1/(25*16) = 0.0025
odrv0.axis1.config.enable_step_dir = True

odrv0.save_configuration()
odrv0.reboot() # Reboot is automatic upon save_configuration() for newer fw versions
# If the ODrive says "False",
# you have to tell your motors to be idle before you're allowed to save:
# odrv0.axis0.requested_state = AXIS_STATE_IDLE
# odrv0.axis1.requested_state = AXIS_STATE_IDLE
#odrv0.reboot() # Reboot is automatic upon save_configuration() for newer fw versions

# WARNING: Anticogging calibration can be finicky
# Save configuration and reboot (if you're on newer fw reboot is automatic) before you start calibrating anticogging
Expand All @@ -111,6 +112,7 @@
# Calibrate anticogging like this
#
# odrv0.axis0.controller.config.anticogging.anticogging_enabled = False
# odrv0.axis0.config.enable_step_dir = False # Needed on fw 0.5.2 and later
# odrv0.axis0.controller.start_anticogging_calibration()

# Check progress with:
Expand All @@ -122,7 +124,8 @@
# When anticogging calibration is done:
# odrv0.axis0.controller.config.anticogging.pre_calibrated = True
# odrv0.axis0.controller.config.anticogging.anticogging_enabled = True
# odrv0.axis0.config.enable_step_dir = True
# Then save and reboot

odrv0.save_configuration()
odrv0.reboot() # Reboot is automatic upon save_configuration() for newer fw versions
#odrv0.reboot() # Reboot is automatic upon save_configuration() for newer fw versions
Loading

0 comments on commit 722ee51

Please sign in to comment.