ユニットテスト

この演習ではユニットテストを myworkcell_core パッケージに記述します.

モチベーション

ROS の Scan-N-Plan アプリケーションを完成し,文書化もしました. プログラムをテストして意図したとおりに動作することを確認します.

情報とリソース

演習問題

Scan-N-Plan プログラムを完成して文書化しました. ビルドした後にプログラムが意図したとおりに動作することを確認するために, テストフレームワークを作成します. ユニットテストでは コードが意図したとおりに実行されることを確認することに加えて 新しいコードが意図しない機能変更を生じるか否かを 簡単に確認することが可能になります.

目標はユニットテストのフレームワークを作成して, いくつかのテストを書くことです.

ガイダンス

ユニットテスト・フレームワークの作成

  1. test フォルダを myworkcell_core/src の下に作成します. そしてワークスペース・ディレクトリで次のことを行ってください.

    catkin build
    source devel/setup.bash
    roscd myworkcell_core
    mkdir src/test
    
  2. utest.cpp というファイルを myworkcell_core/src/test フォルダ内に作成します.

    touch src/test/utest.cpp
    
  3. utest.cpp を QT などで編集して ros と gtest をインクルードします.

    #include <ros/ros.h>
    #include <gtest/gtest.h>
    
  4. 実行すると true を返すダミーテストを作成します. これは後でフレームワークをテストし,より有用なテストに置き換えます.

    TEST(TestSuite, myworkcell_core_framework)
    {
      ASSERT_TRUE(true);
    }
    
  5. 次に一般的な main 関数を書き込みます.

    この main 関数は後で記述するユニットテストを実行します.

    int main(int argc, char **argv)
    {
      testing::InitGoogleTest(&argc, argv);
      return RUN_ALL_TESTS();
    }
    
  6. myworkcell_core の CMakeLists.txt を編集して, u_test.cppファイルをビルドします.

    CMakeLists.txt に次を追加してください.

    if(CATKIN_ENABLE_TESTING)
      find_package(rostest REQUIRED)
      add_rostest_gtest(utest_node test/utest_launch.test src/test/utest.cpp)
      target_link_libraries(utest_node ${catkin_LIBRARIES})
    endif()
    
  7. myworkcell_core の下に test フォルダを作成してください.

    mkdir test
    
  8. テスト launch ファイルを作成します.

    touch test/utest_launch.test
    
  9. utest_launch.test ファイルを QT などで編集して, 次のコードを書き入れてください.

    <?xml version="1.0"?>
    <launch>
        <node pkg="fake_ar_publisher" type="fake_ar_publisher_node" name="fake_ar_publisher"/>
        <test test-name="unit_test_node" pkg="myworkcell_core" type="utest_node"/>
    </launch>
    
  10. ビルドして,フレームワークをテストします.

    catkin run_tests myworkcell_core
    

    コンソール出力では次のように表示されるはずです. ( 多くのビルドメッセージの中に埋もれています.)

    [ROSTEST]-----------------------------------------------------------------------
    
    [myworkcell_core.rosunit-unit_test_node/myworkcell_core_framework][passed]
    
    SUMMARY
     * RESULT: SUCCESS
     * TESTS: 1
     * ERRORS: 0
     * FAILURES: 0
    

    これはフレームワークが機能し,ユニットテストを追加することができる状態であることを意味します.

    注釈

    上記の launch ファイルを使用して, コマンドラインから直接テストを実行することもできます. rostest myworkcell_core utest_launch.test テストファイルは通常の catkin build コマンドを使って作られていないので, 代わりに catkin run_tests myworkcell_core を使ってください.

ストック・パブリッシャ・テストの追加

  1. rostest パッケージには基本的なトピックの特性を検査するためのいくつかのツールがあります. hztestparamtestpublishtest です. fake_ar_publisher ノードが 期待するトピックを出力していることを検証するための 基本的なテストをいくつか追加します。

  2. 次のテストの記述を utest_launch.test ファイルに追加してください.

    <test name="publishtest" test-name="publishtest" pkg="rostest" type="publishtest">
        <rosparam>
          topics:
            - name: "/ar_pose_marker"
              timeout: 10
              negative: False
            - name: "/ar_pose_visual"
              timeout: 10
              negative: False
        </rosparam>
    </test>
    
  3. テストを実行します.

    catkin run_tests myworkcell_core
    

    次のような表示がされるはずです.

    Summary: 2 tests, 0 errors, 0 failures
    

特定のユニットテストの記述

  1. fake_ar_publisher パッケージから取得したメッセージをテストしたいので, 関連するヘッダファイルを( utest.cpp に )インクルードしてください.

    #include <fake_ar_publisher/ARMarker.h>
    
  2. グローバル変数の宣言

    fake_ar_publisher::ARMarkerConstPtr test_msg_;
    
  3. 受信したメッセージをグローバル変数にコピーするためのサブスクライバ・コールバックを追加します.

    void testCallback(const fake_ar_publisher::ARMarkerConstPtr &msg)
    {
      test_msg_ = msg;
    }
    
  4. ar_pose_marker の参照フレームをチェックするユニットテストの記述

    TEST(TestSuite, myworkcell_core_fake_ar_pub_ref_frame)
    {
        ros::NodeHandle nh;
        ros::Subscriber sub = nh.subscribe("/ar_pose_marker", 1, &testCallback);
    
        EXPECT_NE(ros::topic::waitForMessage<fake_ar_publisher::ARMarker>("/ar_pose_marker", ros::Duration(10)), nullptr);
        EXPECT_EQ(1, sub.getNumPublishers());
        EXPECT_EQ(test_msg_->header.frame_id, "camera_frame");
    }
    
  5. ユニットテストが実行中の ROS システムとやりとりするので, main() 関数にノード初期化用定型文を追加してください. 現在の main() 関数を次の新しいコードに置き換えます.

    int main(int argc, char **argv)
    {
      testing::InitGoogleTest(&argc, argv);
      ros::init(argc, argv, "MyWorkcellCoreTest");
    
      ros::AsyncSpinner spinner(1);
      spinner.start();
      int ret = RUN_ALL_TESTS();
      spinner.stop();
      ros::shutdown();
      return ret;
    }
    
  6. テストを実行します.

    catkin run_tests myworkcell_core
    
  7. テスト結果の表示

    catkin_test_results build/myworkcell_core
    

    次のように表示されるはずです.

    Summary: 3 tests, 0 errors, 0 failures