1.介绍
rostest工具是ROS提供的测试工具,该工具基于gtest框架,其实质是roslaunch工具的功能扩展,允许跨越多节点进行测试。rostest测试时文件格式可以是.test或.launch,且文件内包含<test>标签。注意:roslaunch工具可以运行扩展名为.test的文件但是不会执行<test>标签内的代码(即测试node不会启动)。rostest可以在两种层次上进行测试:一种是节点层级的测试,主要测试节点与节点之间的交互是否有效,如消息订阅,服务请求等;另一种是代码层级的测试,主要测试节点内部具体执行的程序的有效性,如特定算法。如需了解更多,可参考如下链接:
1. http://wiki.ros.org/rostest
2. https://github.com/ros/ros_comm
3.https://industrial-training-master.readthedocs.io/en/melodic/_source/session6/Unit-Testing.html
4. https://jingyan.baidu.com/article/359911f5248acb17fe0306a1.html
5. https://blog.csdn.net/x_r_su/article/details/53184871
2.测试实例
2.1 编写cpp文件
在pkg包中创建test文件夹用于存放测试所用的cpp文件,本例cpp文件名为test_log.cpp,详细的代码实现如下所示:
#include <gtest/gtest.h> #include "micros_log/log_rec_store.h" void testCallback(const micros_log::MicRosLog msg); /** * @brief Construct a new TEST object * 测试用例1-普通函数 * 断言:单元测试函数返回值与给定的值是否相同 * @param LogRecStore 测试用例名 * @param test_levelNumToStr 测试名称 */ TEST(LogRecStore,test_levelNumToStr) { EXPECT_EQ("info",micros_log::levelNumToStr(2)); }
/** * @brief Construct a new TEST object * 测试用例2-类中成员函数 * 断言:因函数是void类型,用异常的方式断言是否正确 * @param LogRecStore 测试用例名 * @param test_levelNumToStr 测试名称 */ TEST(LogRecStore,test_CreateFileMkdir) { micros_log::LogRecStore log_instance; EXPECT_NO_THROW(log_instance.createFileMkdir("/home/yyt/micros_log/")); }
/** * @brief Construct a new TEST object * 测试用例3-类中成员函数并且为消息sub的回调函数 * 断言:构造发布msg数据通过类中方法发布后再构造接收信息判断信息数据是否一致 * @param LogRecStore 测试用例名 * @param test_levelNumToStr 测试名称 */ TEST(LogRecStore,test_callback) { //1.生成pub对象并注册到类对象中 micros_log::LogRecStore log_instance; ros::NodeHandle nh; ros::Publisher pub = nh.advertise<micros_log::MicRosLog>("test",10); log_instance.setLogsPub(pub); //2.构造智能指针数据并调用待测试的函数信息 //boost::shared_ptr<rosgraph_msgs::Log> ConstPtr;//智能指针未实例化会报错 boost::shared_ptr<rosgraph_msgs::Log> ConstPtr(new rosgraph_msgs::Log());//智能指针实例化 ConstPtr->name = "YYT"; log_instance.rosoutRecCallback(ConstPtr); //3.构造sub对象接收待测回调函数中pub的数据信息 ros::Subscriber sub = nh.subscribe<micros_log::MicRosLog>("test",1,&testCallback); } /** * @brief 上面测试用例中调用的回调函数 * * @param msg */ void testCallback(const micros_log::MicRosLog msg){ std::string result_name = msg.name; std::string expected_str = "YYT"; EXPECT_STREQ(expected_str.c_str(),result_name.c_str()); } /** * @brief 主函数 * @param argc * @param argv * @return int */ int main(int argc, char **argv){ testing::InitGoogleTest(&argc, argv);// gtest 的初始化 ros::init(argc, argv, "test_micros_log");//ros 节点的初始化 ros::NodeHandle nh;// ros 节点句柄 return RUN_ALL_TESTS();//调用 GTest 测试用例 } |
2.2 修改CMakelist.txt 和package.xml 文件
修改package.xml文件增加rosunit依赖包,如下所示:
<package format="2"> <test_depend>rosunit</test_depend> </package> |
修改CMakelist.txt,如下所示:
## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) find_package(rostest REQUIRED)
########### ## Test ## ###########
## Add gtest based cpp test target and link libraries ## catkin_add_gtest(test_micros_log test/log_test.cpp ) catkin_add_gtest(test_micros_log test/log_test.cpp src/log_rec_store.cpp) target_link_libraries(test_micros_log ${catkin_LIBRARIES}) |
2.3 运行
运行有两种方式(命令方式和launch方式):
第一种:命令方式catkin_make run_tests_<tab>_<tab>
启动两个终端:
终端一:启动roscore
终端二:输入 catkin_make run_tests_<tab>_<tab>
截图如下:
第二种:launch方式 使用rostest调用launch文件或test文件
编写rostest的启动的launch文件,建议用.test为后缀文件名,格式如下(左边为.test的launch文件,右图为正常的launch文件启动节点信息):
启动和查看输出,终端执行命令:
rostest --text pkg_name(包名) **.test(文件名)
截图如下:
2.4 节点发布消息频率测试实例
rostest工具包自带hztest节点,用于测试某个节点的发布话题的频率,如果话题匹配成功,默认测试话题发布的平均频率。编写launch文件可参考如下(启动使用roslaunch方式):
<!-- 文件名 hztest.test--> <launch> <!--节点信息发布话题,用于启动pub发送话题,便于test节点使用 --> <!--例:该节点会发布话题/yyt/test_pub_hz,频率 10Hz --> <node name="test_pub" pkg="micros_log" type="test_pub" /> <!--本次hz所要测试话题名称 --> <param name="hztest_yyt/topic" value="/yyt/test_pub_hz" /> <!--本次hz所要测试话题的频率 --> <param name="hztest_yyt/hz" value="12.0" /> <!--本次hz所要测试话题频率可接收的范围偏差(最低-最高)--> <param name="hztest_yyt/hzerror" value="2.0" /> <!--本次hz所要测试话题运行采集时间周期,单位s)--> <param name="hztest_yyt/test_duration" value="15.0" /> <!--本次hz测试所启动的测试节点,pkg和type系统自带的--> <test test-name="hztest_test" pkg="rostest" type="hztest" name="hztest_yyt" /> </launch> |
2.5 参数服务器测试实例
rostest工具包自带paramtest节点,用于测试注册到参数服务器的参数是否符合规范。编写launch文件可参考如下(启动使用roslaunch方式):
<launch> <param name="namespace" type="string" value="$(env NAMESPACE)"/> <param name="robot_id" value=""/> <param name="file_dir" type="string" value="/home/$(env USER)/micros_log/" />
<!--判断参数是否为空 ,主要看参数是否为NONE,只要不为NODE,则说明存在 --> <test name="test_param_empty_name" pkg="rostest" type="paramtest" test-name="test_param_exist1"> <param name="param_name_target" value="namespace_00"/><!--参数不存在则测试用例失败 --> <param name="test_duration" value="5.0"/> <!--默认是5 --> <param name="wait_time" value="30.0"/><!--默认是20 --> </test> <test name="test_param_nonempty_name" pkg="rostest" type="paramtest" test-name="test_param_exist2"> <param name="param_name_target" value="namespace"/><!--参数存在则测试用例通过 --> <param name="test_duration" value="10.0"/> <!--默认是5 --> <param name="wait_time" value="30.0"/><!--默认是20 --> </test> <!--判断参数的值是否与期望的值相同,相同则通过 --> <test pkg="rostest" type="paramtest" name="paramtest_value_specific_correct" test-name="paramtest_value_specific_correct1"> <param name="param_name_target" value="file_dir"/><!--参数存在,值为下面的值,则测试用例通过 --> <param name="param_value_expected" value="/home/$(env USER)/micros_log/" /> <param name="test_duration" value="5.0" /> <!--默认是5 --> <param name="wait_time" value="30.0" /><!--默认是20 --> </test> <test pkg="rostest" type="paramtest" name="paramtest_value_specific_correct" test-name="paramtest_value_specific_correct2"> <param name="param_name_target" value="file_dir"/><!--参数存在,值不是下面的值,则测试用例失败 --> <param name="param_value_expected" value="/home/$(env USER)/micros_log00/" /> <param name="test_duration" value="5.0" /> <!--默认是5 --> <param name="wait_time" value="30.0" /><!--默认是20 --> </test> </launch> |
2.6 节点publisher测试实例
rostest工具包自带publishtest节点,用于测试发布消息话题是否发送正确。编写launch文件可参考如下(启动使用roslaunch方式):
<launch> <!--节点信息发布话题,用于启动pub发送话题,便于test节点使用 --> <!--例:该节点会发布话题/yyt/test_pub_hz,频率 10Hz --> <node name="test_pub" pkg="micros_log" type="test_pub" />
<test name="publishtest" test-name="publishtest00" pkg="rostest" type="publishtest"> <rosparam> topics: - name: /yyt/test_pub_hz #测试的话题名称 timeout: 10 #默认值是10 negative: False #默认值是False </rosparam> </test> </launch> |