🦬

Steadywin-GIM8108-8を回す ROS 2編

2024/07/11に公開

概要

Nexis-Rというチームでロボカップレスキュー実機リーグに参加している者です。
今回Steadywin-GIM8108-8をROS 2を使って動かしてみたのでその動作方法を紹介します。
https://x.com/robohase01/status/1811339088878022799

動作環境

OdriveでCANを有効化する

"odrivetool"でodrivetoolを開始する。

odrivetool

CANで制御するためにモータの設定を以下のように変更する。

# CANの有効化
odrv0.config.enable_can_a = True

# 制御をアイドルにして動作を完全に止める
odrv0.axis0.requested_state = AXIS_STATE_IDLE

# CAN終端抵抗のオン/オフのGPIOピンの設定
odrv0.can.config.r120_gpio_num = 5

# CAN終端抵抗のオン/オフ
odrv0.can.config.enable_r120 = True

# 設定したファイルの保存
odrv0.save_configuration()
import can

def send_can_message(bus, can_id, data):
    message = can.Message(arbitration_id=can_id, data=data, is_extended_id=False)
    try:
        bus.send(message)
        print(f"Message sent on {bus.channel_info}")
    except can.CanError as e:
        print(f"Message NOT sent: {e}")

if __name__ == "__main__":
    # CANバスを初期化
    bus = can.interface.Bus(channel='can0', interface='socketcan')

    try:
        # node_idとcmd_idを設定
        node_id = 0x00  # 使用するノードIDを指定 0x?? -> ?の部分はノードIDの番号を記載する
        cmd_id = 0x01E  # Disable_CANのコマンドID
        can_id = (node_id << 5) | cmd_id

        # データは空の8バイト(コマンド送信のみでデータなし)
        data = [0x00] * 8

        # CANメッセージを送信
        send_can_message(bus, can_id, data)
    finally:
        # バスをシャットダウン
        bus.shutdown()

CANUSBの設定

今回Steadywin-GIM8108-8のデフォルトのデータレートが500Kbpsだったので、CANUSBも同じデータレートに合わせる

sudo apt-get install can-utils
sudo ip link set can0 type can bitrate 500000
sudo ifconfig can0 up

参考資料
https://docs.rs-online.com/5b40/A700000008257389.pdf

ODriveのROS2環境をインストールする

mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
git clone git@github.com:odriverobotics/ros_odrive.git
cd ~/ros2_ws
colcon build --packages-select odrive_can
source ./install/setup.bash

実行

ターミナル 1

ros2 launch odrive_can example_launch.yaml

ターミナル 2

# CLOSED_LOOP_CONTROLを実行する
ros2 service call /odrive_axis0/request_axis_state odrive_can/srv/AxisState "{axis_requested_state: 8}"

# 速度指令値で制御
ros2 topic pub /odrive_axis0/control_message odrive_can/msg/ControlMessage "{control_mode: 2, input_mode: 1, input_pos: 0.0, input_vel: 1.0, input_torque: 0.0}"
Nexis-R

Discussion