ODrive應用 #7 平衡車輪轂電機和遙控器設置指南

平衡車輪轂電機和遙控器設置指南

應大家的要求,這裏提供了有關如何設置ODrive以使用RC PWM輸入來驅動平衡車輪轂電機的詳細說明。
每個步驟都附帶說明,因此希望您可以順利的完成配置。此視頻演示了最終運行效果。

電機接線

電機具有三個較粗的電機相位線(通常爲黃色,藍色,綠色),以及一組5條較細的線,用於霍爾傳感器反饋(通常爲紅色,黃色,藍色,綠色,黑色)。
您可以以任何順序將電機的相線連接到ODrive的電機連接器中,因爲稍後我們仍將對其校準。 將霍爾反饋連接到ODrive J4連接器(確保和電機通道號匹配),如下所示:

霍爾反饋線 J4 連接器
Red 5V
Yellow A
Blue B
Green Z
Black GND

注意:爲了與編碼器輸入兼容,ODrive在霍爾傳感器連接的引腳上沒有任何濾波電容器。 因此,爲了獲得可靠的霍爾信號,建議在這些引腳上添加一些濾波電容。

電機配置

標準6.5英寸輪轂電動機有30個永磁極,因此極對數爲15。 如果您使用的是它電機,則需要數一下磁鐵個數或通過數據表以獲取此信息。

odrv0.axis0.motor.config.pole_pairs = 15

平衡車輪轂電機與普通的電機相比具有更高的相電阻,因此我們使用更高的電壓進行電機校準,並將電流感應設置的更敏感。同時,電機的電感也相當高,因此我們需要將電流控制器的帶寬從默認值減小以保持其穩定。

odrv0.axis0.motor.config.resistance_calib_max_voltage = 4
odrv0.axis0.motor.config.requested_current_range = 25 #需要重啓以使此項參數生效
odrv0.axis0.motor.config.current_control_bandwidth = 100

將編碼器設置爲霍爾模式(而不是編碼器增量模式)
霍爾反饋對於電動機中的每個極對都有6種狀態。 由於我們有15個極對,因此將cpr設置爲15 * 6 = 90。

odrv0.axis0.encoder.config.mode = ENCODER_MODE_HALL
odrv0.axis0.encoder.config.cpr = 90

由於霍爾反饋每轉僅具有90個計數,因此我們希望減少速度跟蹤帶寬以獲得更平滑的速度估計。
我們還可以適當的調低一些控制器的增益,使系統反應不那麼激進,當然也應該能夠適合您的應用。
因爲可能想要控制輪式機器人,所以我們選擇速度控制模式。 請注意,在速度模式下不使用pos_gain,但我還是給了您一個推薦值,以防您想運行位置控制模式。

odrv0.axis0.encoder.config.bandwidth = 100
odrv0.axis0.controller.config.pos_gain = 1
odrv0.axis0.controller.config.vel_gain = 0.02
odrv0.axis0.controller.config.vel_integrator_gain = 0.1
odrv0.axis0.controller.config.vel_limit = 1000
odrv0.axis0.controller.config.control_mode = CTRL_MODE_VELOCITY_CONTROL

在下一步中,我們將開始爲電機供電,因此我們要確保首先保存配置,然後需要重啓ODrive。

odrv0.save_configuration()
odrv0.reboot()

確保電動機可以自由轉動,然後執行電機校準。

odrv0.axis0.requested_state = AXIS_STATE_MOTOR_CALIBRATION

您可以通過以下指令讀取與電機有關的所有數據:

odrv0.axis0.motor

檢查是否出現錯誤,並且相電阻和電感值是合理的。 以下是我得到的結果:

  error = 0x0000 (int)
  phase_inductance = 0.00033594953129068017 (float)
  phase_resistance = 0.1793474406003952 (float)

如果一切看起來都正常,那麼您可以執行以下指令命令ODrive將校準的結果保存:

odrv0.axis0.motor.config.pre_calibrated = True

下一步是檢查電機和霍爾傳感器之間的校準情況。
由於先前接線步驟,您可以按隨機順序連接電機相線,並且霍爾信號也是隨機的。 所以校準後不要再更改它。
確保電動機可以自由旋轉:

odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION

檢查校準後的狀態:

odrv0.axis0.encoder

檢查是否有錯誤出現。 如果您的霍爾傳感器安裝角度還算標準,則offset_float應接近0.5。

  error = 0x0000 (int)
  offset_float = 0.5126956701278687 (float)

如果一切看起來都正常,那麼您可以執行以下指令,這樣在下次啓動後就不用再次進行編碼器校準了:

odrv0.axis0.encoder.config.pre_calibrated = True

好的,我們現在完成了電機配置! 是時候保存,重新啓動然後進行測試了。
ODrive啓動後會進入空閒狀態(我們將在稍後進行切換),我們之後可以啓動閉環控制。

odrv0.save_configuration()
odrv0.reboot()
odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis0.controller.vel_setpoint = 120
# Your motor should spin here
odrv0.axis0.controller.vel_setpoint = 0
odrv0.axis0.requested_state = AXIS_STATE_IDLE

希望您的電機能正常旋轉! 如果不正常,請仔細覈對上述所有操作。

PWM 信號輸入

如果要使用RC遙控器來控制電機,則可以使用PWM輸入
讓我們使用GPIO 3/4作爲速度控制信號的輸入,這樣我們就不必禁用UART。
然後,將這些搖桿輸入範圍映射到某個合適的速度設定範圍。
我們還必須重新啓動以使PWM輸入生效。

odrv0.config.gpio3_pwm_mapping.min = -200
odrv0.config.gpio3_pwm_mapping.max = 200
odrv0.config.gpio3_pwm_mapping.endpoint = odrv0.axis0.controller._remote_attributes['vel_setpoint']

odrv0.config.gpio4_pwm_mapping.min = -200
odrv0.config.gpio4_pwm_mapping.max = 200
odrv0.config.gpio4_pwm_mapping.endpoint = odrv0.axis1.controller._remote_attributes['vel_setpoint']

odrv0.save_configuration()
odrv0.reboot()

現在我們可以檢查搖桿是否正確控制電機轉速了。 移動遙控器搖桿,打印vel_setpoint,移動到其他位置,然後再次檢查。

In [1]: odrv0.axis1.controller.vel_setpoint
Out[1]: 0.1904754638671875

In [2]: odrv0.axis1.controller.vel_setpoint
Out[2]: 0.1904754638671875

In [3]: odrv0.axis1.controller.vel_setpoint
Out[3]: 28.152389526367188

In [4]: odrv0.axis1.controller.vel_setpoint
Out[4]: 61.21905517578125

In [5]: odrv0.axis1.controller.vel_setpoint
Out[5]: -52.990474700927734

好的,現在我們應該能夠使用遙控器來控制電機的轉速了!

odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL

安全提醒

確保在RC接收器上設置故障保護功能,以便在遙控器和接收器之間失去連接時,接收器將爲兩個軸的速度設定值輸出0(或對您的設備來說安全的設定)。 另請注意,如果接收器關閉(電源丟失等),或者從接收器到ODrive的信號丟失(電線拔出等),則ODrive將繼續執行上一個命令的速度設定值。 ODrive中的PWM輸入當前沒有超時保護功能。

啓動後自動進入閉環控制模式

嘗試重新啓動,然後在兩個軸上激活AXIS_STATE_CLOSED_LOOP_CONTROL。 檢查一切正常,並按預期工作。
現在可以使ODrive啓動後自動進入閉環控制模式。 這樣在沒有PC或其它控制主機的情況下運行ODrive將會很方便。

odrv0.axis0.config.startup_closed_loop_control = True
odrv0.axis1.config.startup_closed_loop_control = True
odrv0.save_configuration()
odrv0.reboot()

如果您有任何問題或疑問,歡迎您加入ODrive社區或QQ羣 851421965 進行交流。

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章