>
== Standard Test Nodes ==
=== hztest ===
`hztest` allows you test the publishing rate of a node. It reads in parameters that specify the topic name, rate, and error bounds of the test, and will succeed if the topic matches that specification. It can also be used to test for no publication, i.e. 0Hz. By default, `hztest` only tests the overall, average publication rate. This can be changed by setting the `~check_intervals` parameter.
Here is a sample configuration:
{{{
}}}
{{{#!clearsilver CS/NodeAPI
sub {
0.name =
0.type = any/any
0.desc = Topic to measure.
}
param {
0.name = ~topic
0.type = str
0.desc = Name of topic to monitor.
0.default = None
1.name = ~hz
1.type = float
1.desc = Expected rate of topic. Can be zero.
1.default = None
2.name = ~hzerror
2.type = float
2.desc = Allowed error of publication rate. Required if hz != 0.0.
2.default = None
3.name = ~test_duration
3.type = float
3.desc = Number of seconds to measure publication for.
3.default = None
4.name = ~check_intervals
4.type = bool
4.desc = Check message-to-message interval, instead of just average overall publication rate.
4.default = False
5.name = ~wait_time
5.type = float
5.desc = ('''ROS 1.1''') Number of seconds to allow node to initialize before receiving first message. If a message is not received from the node before the wait time is up, the test fails.
5.default = 20.0
6.name = ~wall_clock
6.type = bool
6.desc = ('''ROS 1.5''') If True, then perform all rate measurements against wall clock time, regardless of whether simulation / log time is in effect.
6.default = False
}
}}}
=== selftest_test ===
`selftest_test`, in the [[self_test]] package, runs a self-test and checks that it passes. Please see the [[self_test]] package for more documentation.
=== paramtest ===
<> (? Addition to prior distros is [[https://github.com/ros/ros_comm/pull/859#issuecomment-247233126|discussed]])
Similar to [[#hztest|hztest]], `paramtest` allows you test if certain parameters are registered at the [[Parameter Server]]. It reads in parameters that specify the parameter name, and optionally its value, and then will succeed if the parameter matches that specification.
Here 3 different configurations samples; :
{{{
}}}
=== publishtest ===
<>
`publishtest` is a node to test if specified topics are published at least once. This can be used for testing topics that are latched or those of which publish rate is uneven, and also supports testing multiple topics with a single testcase.
Here is a sample of testing some nodes:
{{{
msg_name: std_msgs/String
topics:
- name: talker_0/output
timeout: 10
negative: False
- name: talker_1/output
timeout: 3
negative: True # means it is not published until the timeout
}}}
Note:
* "`topics`" element in `` is required, as well as its child elements (`name`, `timeout`, `negative`).
* You can still substitute values in `` by using [[roslaunch/XML/arg|arg]] tag but along with [[roslaunch/XML/rosparam#Attributes|"subst_value" attribute]] (as [[http://answers.ros.org/question/39085/what-is-the-correct-way-to-set-args-in-rosparam/|required in tag]]).
=== advertisetest ===
<>
`advertisetest` is a node that checks if the specified topics or services are advertised,
the below parameters must be set. This node supports testing multiple topics and services with a single testcase.
Here is a sample of testing some nodes:
{{{
topics:
- name: /chatter
timeout: 2.
- name: /once_topic
type: std_msgs/Bool
timeout: 2.
- name: /advertised_topic
timeout: 2.
negative: true
services:
- name: /empty
timeout: 2.
- name: /set_bool
type: std_srvs/SetBool
timeout: 2.
- name: /unadvertised_service
timeout: 2.
negative: true
}}}
Note:
This example came from the unit_test of this node, check the [[roslaunch/XML/rosparam#Attributes|test link]] (as [[https://github.com/ros/ros_comm/blob/noetic-devel/tools/rostest/test/advertisetest.test| advertisetest testcase]])
=== Execution of rostest tests ===
As first step to get familiar with writing rostest tests it is helpful to execute and investigate the tests of `rostest`'s own tests.
==== Preconditions to run the tests ====
To being able to run the tests of `rostest` the following steps are required.
Clone ros_comm into the catkin workspace:
{{{
cd /src
git clone https://github.com/ros/ros_comm.git
}}}
Build `ros_comm`:
{{{
cd
catkin_make --pkg ros_comm
}}}
Get a list of all make targets of `rostest` (they will be used later):
{{{
catkin_make run_tests_rostest_ (and invoke tab-completion)
run_tests_rostest_gtest
run_tests_rostest_gtest_test_permuter
run_tests_rostest_rostest
run_tests_rostest_rostest_test_clean_master.test
run_tests_rostest_rostest_test_distro_version.test
run_tests_rostest_rostest_test_hztest0.test
run_tests_rostest_rostest_test_hztest.test
run_tests_rostest_rostest_test_param.test
run_tests_rostest_rostest_test_publishtest.test
}}}
==== Execute hztest tests ====
The `hztest` node implementation is located in `/src/ros_comm/tools/rostest/nodes/hztest`. The tests of the `hztest` node are implemented in `/src/ros_comm/tools/rostest/test/hztest0.test` and in `/src/ros_comm/tools/rostest/test/hztest.test`. W.r.t. to usual taxonomy in software testing `hztest` acts as a "mock topic subscriber node" and verifies if `talker.py`, the "node under test" (topic publisher) publishes the topics as expected. The implementation of `talker.py` is located in `/src/ros_comm/clients/rospy/test_nodes/talker.py`.
Running the `hztest` tests gives you a first idea about how the node has to be used in own tests. You can run the `hztest` tests in `rostest` as follows:
{{{
cd
catkin_make run_tests_rostest_rostest_test_hztest.test
catkin_make run_tests_rostest_rostest_test_hztest0.test
}}}
[[https://github.com/ros/ros_comm/blob/lunar-devel/tools/rostest/nodes/hztest|Implementation of hztest in the ros_comm package (lunar)]]
==== Execute paramtest tests ====
The `paramtest` node implementation is located in `/src/ros_comm/tools/rostest/nodes/paramtest`. The test of the `paramtest` node is implemented in `/src/ros_comm/tools/rostest/test/param.test`. Running the `paramtest` test gives you a first idea about how the node has to be used in own tests. You can run the `paramtest` test in `rostest` as follows:
{{{
cd
catkin_make run_tests_rostest_rostest_test_param.test
}}}
[[https://github.com/ros/ros_comm/blob/lunar-devel/tools/rostest/nodes/paramtest|Implementation of paramtest in the ros_comm package (lunar)]]
=== ROS node integration testing ===
The [[https://github.com/steup/Ros-Test-Example|GitHub repository "Ros-Test-Example" (branch: master)]] contains an example for rostest, gtest and rviz based ROS node integration testing. The `hztest` test node is used to [[https://github.com/steup/Ros-Test-Example/blob/master/src/cars/launch/carHz.test|verify the publishing of car related data]] and to [[https://github.com/steup/Ros-Test-Example/blob/master/src/cars/launch/simHz.test|verify the publishing of simulated car related data]]. The example is described in [[https://github.com/steup/Ros-Test-Example/blob/master/src/cars/doc/slides/slides.pdf|PDF slides]]. The same repository shows how to use gmock based mocks for the car and the road in [[https://github.com/steup/Ros-Test-Example/blob/mocking/src/cars/src/Mock.cpp|"Ros-Test-Example" (branch: mocking)]].