ROSをCUDA対応してみる
こんにちは、和田です。
最近、プロジェクトでちょいちょいROSを利用することが増えてきました。
ROSってノードをちょいちょい組み合わせるだけでそれなりに動く物つくれるんで便利なんですよね。
そんな中、独自のノードを作ることも多々あるんですが、PointCloudの整形とかってCUDAを使った並列処理に向いているんだよなと。
nVidiaのJetsonTX2などを使う場合は特に、GPUを有効に使うことが大事ですし。
http://www.nvidia.co.jp/object/embedded-systems-dev-kits-modules-jp.html
そして、案外調べてみると日本語でROS+CUDAの環境構築を記事にしている人少ないんで、とりあえず書いてみようかなと言う流れです。
(英語で調べると結構出てきますが。。。)
構築の流れとしては、catkin_makeによるノードのビルド手順にCUDAのcmakeマクロを組み込むと言うだけです。
また事前準備として、CUDA Toolkitと、ROSのインストールは済ませて、
catckin_workspaceが作成されている状態にしておいて下さい。
まずは、完成形のフォルダ構成になります。
${catckin_ws}/ + deval/ + build/ + src/ + min_cuda_node/ + include/ | + hello.h + src/ | + hello.cu | + main.cpp + CMakeLists.txt + package.xml
基本的には、通常のROSノードを作成する構成と変わりありません。
srcフォルダに .cuファイル が存在しているくらいです。
次に、package.xmlの構成になります。
<?xml version="1.0"?> <package format="2"> <name>min_cuda_node</name> <version>0.0.1</version> <description>min cuda node package</description> <maintainer email="t-wada@ipx.co.jp">Takayuki Wada</maintainer> <license>MIT</license> <buildtool_depend>catkin</buildtool_depend> <build_depend>message_generation</build_depend> <build_depend>roscpp</build_depend> <build_depend>std_msgs</build_depend> <build_export_depend>roscpp</build_export_depend> <build_export_depend>std_msgs</build_export_depend> <exec_depend>roscpp</exec_depend> <exec_depend>std_msgs</exec_depend> <export> </export> </package>
こちらも、特別何か弄るような必要はありません。
catkin_create_pkgを行ったままでも問題なく動作します。
そして、ここが完全に肝になる CMakeList.txtです。
cmake_minimum_required(VERSION 2.8.3) project(min_cuda_node) add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS roscpp std_msgs ) find_package(CUDA 9.1 REQUIRED) catkin_package( CATKIN_DEPENDS roscpp std_msgs ) set(MIN_CUDA_SRC src/main.cpp src/hello.cu ) include_directories( ${PROJECT_SOURCE_DIR}/include ${catkin_INCLUDE_DIRS} ${CUDA_INCLUDE_DIRS} ) cuda_add_executable(min_cuda_node ${MIN_CUDA_SRC} ) target_link_libraries(min_cuda_node ${catkin_LIBRARIES} ${CUDA_LIBRARIES} )
ポイントになる箇所はいくつか。
① find_package で CUDAのライブラリを検索する
② include_directories に ${CUDA_INCLUDE_DIRS} を追加する
③ add_executable の代わりに cuda_add_executable を利用する
④ target_link_libraries に ${CUDA_LIBRARIES} を追加する
ちなみに、CUDAのCMake設定はFindCUDAを参照すると細かいことが書いてあります。
以下が呼び出しのサンプルコードになります。
ここでは単純に10Hzでループを回して、CUDAコードの呼び出しを行っています。
実践的なコードでは、SubscriberのcallbackからCUDAを呼び出して、受信したTopicのメッセージを並列処理で加工するようなケースが多いです。
main.cpp
#include <ros/ros.h> #include "hello.h" int main(int argc, char **argv) { ros::init(argc, argv, "min_cuda"); ros::NodeHandle nh; ros::Rate rate(10.f); while (nh.ok()) { callHello(); rate.sleep(); } return 0; }
次がCUDA呼び出しのヘッダファイルです。
CUDA側のTipsとして、ヘッダに .cu ファイルで実装された関数を宣言する場合は、extern宣言をしないとリンク時にエラーになるので注意してください。
hello.h
#ifndef HELLO_H #define HELLO_H extern void callHello(void); #endif
最後にCUDAの実装ファイルです。
この処理自体はHello Worldでしかないので意味はありません。
hello.cu
#include <stdio.h> #include "hello.h" __global__ void hello(void) { printf("hello cuda !! thredIdx=%d\n", threadIdx.x); } void callHello(void) { hello<<<1, 4>>>(); cudaDeviceSynchronize(); }
この状態で、catkin_makeを実行すると、devalディレクトリ配下のLibに実行ファイルが作成されると思います。
あとはrosrunするなりlaunchファイル作成するなり、いつも通り実行するだけです。
と、まぁ振り返ってみればCMakeの使い方知ってれば当たり前すぎる事なんですが、
初学だと案外躓いたりするのでまとめてみました。