ROS開発キット/クローラロボット開発プラットフォームに付属するマイコンに対して制御指令を送り、エンコーダの読み取り結果を受け取るノードです。ROS topicの/cmd_vel
をSubscribeし、/odom
をPublishします。セットでcugo_ros_motorcontroller使用します。
ROS 2 Humbleでディレクトリ構成が変わりました。Humbleをお使いの方はhumble_devel branchをご参照ください。
Subscribeした/cmd_vel
の速度ベクトルになるような仮想車輪L/Rの回転数を計算します。計算した回転数をマイコンに送信します。また、cugo_ros_motorcontrollerが書き込まれたマイコンからエンコーダのカウント数を受け取ります。カウント数からロボットのオドメトリを計算し、/odom
を生成しPublishします。
CuboRex製品では、
- ROS開発キット CuGo V3
- クローラロボット開発プラットフォーム CuGo V4
- クローラロボット開発プラットフォーム CuGo V3i
でお使いいただけます。それぞれ使用するコードが異なることがありますので、下記表からご参照ください。
ここでは、“クローラロボット開発プラットフォーム CuGo V4”と“クローラロボット開発プラットフォーム CuGo V3i”は“クローラロボット開発プラットフォーム”と総称します。
製品名 | ROSパッケージ | マイコンスケッチ |
---|---|---|
ROS開発キット | このページ | ArduinoUNO用 |
クローラロボット開発プラットフォーム | このページ | RaspberryPiPico用 |
ご購入時点でセットアップ済みですので、そのままROSパッケージの実行をしてください。
このパッケージは付属のArduinoUNOとUDP通信します。ロボット内のEdgeルータに対して、有線Ethernetケーブルまたは、WiFiに接続することでArduinoUNOと通信することができます。cugo_ros_motorcontrollerでマイコン側のIPアドレスを指定し、そのIPアドレスに対してUDP信号を送信します。マイコン側のスケッチでは、192.168.11.216をデフォルトにしています。必要に応じてlaunchファイルを変更してください。
付属のArduinoUNOを書き換えてしまった場合はこちらのスケッチを書き込んでください。
スケッチの書き換えはROS PCである必要性はありません。
付属のRaspberryPiPicoと通信します。 付属のRaspberryPiPicoにこちらのスケッチを書き込み、ROS PCとRaspberryPiPicoをUSBケーブルで接続してください。 その後ROSパッケージを実行してください。自動で通信開始します。
スケッチの書き換えはROS PCである必要性はありません。
- OS: Ubuntu 20.04.4 LTS
- ROS Distribution: ROS 2 Foxy Fitzroy
ROS 2環境がない場合はROS 2 Documentationを参照しROS 2をインストールしてください。
IMUのデータ取得に使用しているwitmotion_IMU_rosのbuildにはver3.19以上のCMakeが必要です。バージョンが低い場合は、Installing CMakeを参考にCMakeをインストールしてください。
ROS 2のワークスペース内でgit cloneしたのち、colcon buildしてください。
$ cd ~/your/ros_workspace/ros2_ws/src
$ git clone https://github.com/CuboRex-Development/cugo_ros_control.git
$ cd ../..
$ colcon build --symlink-install
$ source ~/your/ros_workspace/ros2_ws/install/local_setup.bash
下記のコマンドでcugo_ros_controlノードが起動します。ros2 launchを用いて起動する際、いくつかのパラメータを指定することができます。詳細はParametersの項目を参照してください。
$ ros2 launch cugo_ros2_control cugov3_ros2_control_launch.py
付属のRaspberryPiPicoとUSBケーブルで接続をしたのち、お客様環境にあった権限設定をしてからlaunchファイルを実行してください。
# RaspberryPiPicoの権限付与例
# お客様環境に合わせてコマンドを実行してください。
$ sudo chmod 777 /dev/ttyACM0
# launch ファイルを実行
$ ros2 launch cugo_ros2_control cugov4_ros2_control_launch.py
付属のRaspberryPiPicoとUSBケーブルで接続をしたのち、お客様環境にあった権限設定をしてからlaunchファイルを実行してください。
# RaspberryPiPicoの権限付与例
# お客様環境に合わせてコマンドを実行してください。
$ sudo chmod 777 /dev/ttyACM0
# launch ファイルを実行
$ ros2 launch cugo_ros2_control cugov3i_ros2_control_launch.py
/odom
(nav_msgs/msg/Odometry)/tf
(tf2_msgs/msg/TFMessage)
/cmd_vel
(geometry_msgs/msg/Twist)
ODOMETRY_DISPLAY (boolean, default: true)
- オドメトリ表示の有無(trueで表示)
PARAMETERS_DISPLAY (boolean, default: false)
- 設定したパラメータを起動時に表示(trueで表示)
TARGET_RPM_DISPLAY (boolean, default: true)
- 目標RPM表示の有無(trueで表示)
SENT_PACKET_DISPLAY (boolean, default: false)
- 送信パケットのデバッグ表示の有無(trueで表示)
RECV_PACKET_DISPLAY (boolean, default: true)
- 受信パケットのデバッグ表示の有無(trueで表示)
READ_DATA_DISPLAY (boolean, default: true)
- 受信パケットからデコードした数値の表示の有無(trueで表示)
arduino_addr (string, default: 192.168.11.216)
- Arduinoドライバの通信受付IPアドレス
arduino_port (int, default: 8888)
- Arduinoドライバの通信受付ポート番号
encoder_max (int, default: 2147483647)
- エンコーダ最大カウント
- マイコン側のカウンタがオーバーフローする値を設定
encoder_resolution (int, default: 2048)
- エンコーダ分解能
odom_child_frame_id (string, default: base_link)
- オドメトリ子フレームID
odom_frame_id (string, default: odom)
- オドメトリフレームID
reduction_ratio (float, default: 1.0)
- モータ軸端からの減速比
source_port (int, default: 8888)
- ROSノードの通信受付ポート番号
timeout (float, default: 0.05)
- 通信タイムアウトまでの時間[sec]
tread (float, default: 0.380)
- トレッド幅[m]
wheel_radius_l (float, default: 0.03858)
- 左クローラの仮想タイヤ半径[m]
wheel_radius_r (float, default: 0.03858)
- 右クローラの仮想タイヤ半径[m]
comm_type (string, default: UDP)
- 通信をUDPでするかUSBでするか
serial_port (string, default: /dev/ttyACM0)
- USB-Serialで通信するポートを指定
serial_baudrate (int, default: 115200)
- USB-Serial通信のボーレートを設定
上記のパラメータはlaunchファイルで設定されています。
cugo_ros_motorcontrollerと、ヘッダ8バイト・ボディ64バイトの合計72バイトから構成されるデータを通信しています。 ボディデータに格納されるデータの一覧は以下の通りになります。 なお、扱うデータは今後拡張する予定です。
Data Name | Data Type | Data Size(byte) | Start Address in PacketBody | Data Abstract |
---|---|---|---|---|
TARGET_RPM_L | float | 4 | 0 | RPM指令値(左モータ) |
TARGET_RPM_R | float | 4 | 4 | RPM指令値(右モータ) |
Data Name | Data Type | Data Size(byte) | Start Address in PacketBody | Data Abstract |
---|---|---|---|---|
RECV_ENCODER_L | float | 4 | 0 | 左エンコーダのカウント数 |
RECV_ENCODER_R | float | 4 | 4 | 右エンコーダのカウント数 |
ご不明点がございましたら、issuesにてお問い合わせください。回答いたします。
このプロジェクトはApache License 2.0のもと、公開されています。詳細はLICENSEをご覧ください。