#概要
前回,ROSを使ってUnityの仮想車両をマイコンシミュレータで制御してみました.
ただ,ここでわかった課題は『シミュレーションが重い,遅い・・』でした.
Unityだけでも結構重いのですが,それに加えてマイコンシミュレータも動かすため,1マシンでシミュレーションするのは限界を感じていました.
そこで,マイコンシミュレータ上で動作させていた組込み向けROSライブラリ(mROSをマイコンシミュレータに組み込んでみたらどうか?というのが今回の記事の内容です.
この成果は,SWEST21でご紹介しますので,もし参加される方いらっしゃいましたら,ぜひインタラクティブセッション/athrill・箱庭のセッションにお立ち寄りください!
#今回の取り組み内容
既存のマイコンシミュレータで,ROSトピックの出版・購読できるようなものはあまり聞いたことがないので,TOPPERS/athrill を改造しました.
具体的には,以下の3点の改造を実施しました.
- mROSの athrill移植
- mROSソースを x86用にビルドし直して,ターゲット依存部(RTOSやLWIP)を汎用OSの機能に差し替えるだけ
- mROS機能の抜き差し機構の追加
- mROS は athrill のプラグインという位置づけが良いかと思ったので,抜き差しできるようにインタフェースを切りました.
- athrillのデバイスレジスタへ I/O することで,トピックデータを読み書きができます
- mROS機能のパラメータ
- ROSトピックは athrill のパラメータファイルに任意のものを定義できるようにしました.
- ただし,トピックのデータ型は,std_msgs/String のみとしています.
#スタック構成
よくわからない?と思われる方に向けて,今回実施したことをスタック構成で図解したいと思います.
まず,これまで mROS がどこにいたかというと,組み込みソフトウェアの一部(ミドルウェア)として配置されており,athrillの仮想空間上で動作していました.
これに対して,今回の取り組みにより,mROSは athrill の内部に組み込まれました.
#サンプルアプリ
athrill上で動作するベアメタルアプリを以下で公開しました.
https://github.com/tmori/athrill-sample/tree/master/baremetal/dev-sample/dev-mros
※main.c を参照ください.
トピック出版は以下のように行います.
static const char *sample_publish_data = "Hello World!!";
int main(void)
{
int datalen = strlen(sample_publish_data);
/*
* 送信用バッファのアドレスを athrill のデバイスレジスタ(VCAN_TX_DATA_0)に登録
*/
sil_wrw_mem((void*)(VCAN_TX_DATA_0(0)), (uint32)sample_publish_data);
/*
* 送信データ長を athrill のデバイスレジスタ(VCAN_TX_DATA_1)に登録
*/
sil_wrw_mem((void*)(VCAN_TX_DATA_1(0)), datalen);
}
void timer_interrupt_handler(void)
{
/*
* 送信フラグレジスタに 1 を書き込むとトピックデータが送信されます
*/
sil_wrb_mem((void*)(VCAN_TX_FLAG(0) + 0), 1);
}
トピック購読は以下のように行います.
static char subscribe_buffer0[1024];
int main(void)
{
/*
* 受信用バッファのアドレスを athrill のデバイスレジスタ(VCAN_RX_DATA_0)に登録
*/
sil_wrw_mem((void*)(VCAN_RX_DATA_0(0)), (uint32)subscribe_buffer0);
/*
* 受信バッファサイズを athrill のデバイスレジスタ(VCAN_RX_DATA_1)に登録
*/
sil_wrw_mem((void*)(VCAN_RX_DATA_1(0)), sizeof(subscribe_buffer0));
}
void timer_interrupt_handler(void)
{
uint8 is_rcv = 0;
/*
* 受信データの到着判定はVCAN_RX_FLAGの値で判断(0:データなし,1:データあり)
*/
is_rcv = sil_reb_mem((void*)(VCAN_RX_FLAG(0)));
if (is_rcv != 0) {
test_print("RECV CAN_DATA:");
test_print(subscribe_buffer0);
test_print_one("\n");
sil_wrb_mem((void*)(VCAN_RX_FLAG(0)), 0);
}
}
出版/購読するトピックデータは,athrillのパラメータ定義ファイル(device_config.txt)で以下のように行います.
DEBUG_FUNC_ENABLE_MROS 1
DEBUG_FUNC_MROS_TOPIC_PUB_NUM 2
DEBUG_FUNC_MROS_TOPIC_PUB_0 CANID_0x100
DEBUG_FUNC_MROS_TOPIC_PUB_1 CANID_0x101
DEBUG_FUNC_MROS_TOPIC_SUB_NUM 2
DEBUG_FUNC_MROS_TOPIC_SUB_0 CANID_0x400
DEBUG_FUNC_MROS_TOPIC_SUB_1 CANID_0x404
以下,各パラメータの説明です.
- DEBUG_FUNC_ENABLE_MROS
- athrillのROS機能を使う場合は 1 を設定します
- DEBUG_FUNC_MROS_TOPIC_PUB_NUM
- 出版するトピック数を定義します.最大で1024個まで定義可能.
- DEBUG_FUNC_MROS_TOPIC_PUB_<0からの連番値>
- 出版するトピック名を定義します.DEBUG_FUNC_MROS_TOPIC_PUB_NUMで定義した個分だけ定義します.
- DEBUG_FUNC_MROS_TOPIC_SUB_NUM
- 購読するトピック数を定義します.最大で1024個まで定義可能.
- DEBUG_FUNC_MROS_TOPIC_SUB_<0からの連番値>
- 購読するトピック名を定義します.DEBUG_FUNC_MROS_TOPIC_SUB_NUMで定義した個分だけ定義します.
#デモ
上記はあくまで単純な動作確認用のサンプルアプリなのですが,前回作成したアプリをこのathrill用に移植したアプリケーションソースを以下に公開しました(RTOS(asp3)上で動作しています).
また,このアプリケーションを使ったデモをお見せします.
なお,前回はこのデモを動画を録画すると,マシンに負荷がかかりすぎて,障害物判定が間に合わなかったのですが,今回は見つけてくれています.
#ROS対応版のathrillのインストール手順
##動作環境
ROS対応版 athrill は,以下の環境で動作します.
- OS
- windows 10/WSL(Ubuntu 16.04.5 LTS), Linux(Ubuntu 16.04.5 LTS)
- 今回は Windows 10/WSLで動作確認しています.
- ROS
- kinetic
##athrillのチェックアウト
$ git clone https://github.com/tmori/athrill.git
##athrill-targetのチェックアウト
$ git clone https://github.com/tmori/athrill-target.git
##athrillのビルド
athrill と athrill-targetを以下のフォルダ構成にしてください.
.
├── athrill
└── athrill-target
ビルド実行場所である以下のフォルダに移動してください.
athrill-target/v850e2m/build_linux
以下のコマンドを実行し,ビルドしてください.
※make/gcc は事前にインストールしておいてください.
make clean;make
ビルド成功すると,以下のログが出力されます.
ranlib libmain.a libcui.a libcpu.a libbus.a libmpu.a libdevice.a libloader.a libstd.a libmros.a
gcc -O3 -Wl,--allow-multiple-definition libmain.a libcui.a libcpu.a libbus.a libmpu.a libdevice.a libloader.a libstd.a libmros.a -o athrill2 -lpthread
/bin/cp athrill2 ../../../athrill/trunk/src/../../bin/linux/
chmod +x ../../../athrill/trunk/src/../../bin/linux/athrill2
##athrillのバイナリパスの設定
作成されたバイナリは,athrillの方のフォルダ内の bin/linux 配下に配置されますので,このパスを .bashrcに登録してください.
$ ls athrill/bin/linux
athrill athrill_extfunc.sh athrill-run athrill_terminal variable_conflict_check.groovy
athrill2 athrill_remote athrill-run-remote geany.sh variable_conflict_check.sh
以下,設定例です.
export PATH=<athrill配置フォルダパス>/athrill/bin/linux:${PATH}
##インストール確認
任意のフォルダ上で,athrill2と叩いて,以下のメッセージが出力されていれば成功です.
$ athrill2
Usage:athrill -c<core num> -m <memory config file> [OPTION]... <load_file>
-c : set core num. if -c is not set, core num = 2.
-i : execute on the interaction mode. if -i is not set, execute on the background mode.
-r : execute on the remote mode. this option is valid on the interaction mode.
-t<timeout> : set program end time using <timeout> clocks. this option is valid on the background mode.
-m<memory config file> : set athrill memory configuration. rom, ram region is configured on your system.
-d<device config file> : set device parameter.
#何に使えるか?
えいやっと作ってみましたが,ここで冷静になって,これって何に使えるか考察してみます.
まず,マイコンシミュレータでROSを利用するというだけでしたら mROS だけで十分だと思います.
マイコンシミュレータである athrill が mROS を組み込んだ意義は,実は,仮想デバイスの通信手段が増えるという点にあると考えます.
※とうぜんですが,動作も早くなります.
たとえば,CANデバイスを考えてみましょう.CANデバイスをマイコンシミュレータに組み込んだ場合,その通信路をどうするか?という問題がでてきます.
TCPやUDP,はたまた,本物のCANバスという選択肢がありますが,ここにROS通信という選択肢が出てくるわけです.
ROSであれば,標準でさまざまなコマンドが用意されていますので,扱いが非常に楽です.
CANデータをROSトピックとして購読・出版できるようになりますから,rostopic echo
を使えば流れているデータを簡単に参照できます.
また,テストデータを流したい場合は,rostopic pub
を使えば好きなデータを流せます.
さらに通信構成は,rqt_graph
を使えばこんな風にビジュアライズもしてくれます.
さらに,自分の宿題である ETロボコン向けシミュレータの取り組みに対しても,性能面・環境面で重要な位置づけとなることでしょう.今後にご期待ください!