<test> tag

The <test> tag is syntactically similar to the <node> tag. They both specify a ROS node to run, but the <test> tag indicates that the node is actually a test node to run. For more information about these test nodes, please see the rostest documentation.

Examples

<test test-name="test_1_2" pkg="mypkg" type="test_1_2.py" time-limit="10.0" args="--test1 --test2" />

Launches the "test_1_2" node using the test_1_2.py executable from the mypkg package with the command-line argument --test1 --test2. The test will be terminated as a failure if it takes longer than 10 seconds.

Attributes

<test> tags share most of the normal <node> attributes, except:

  • no respawn attribute (test nodes must terminate, so they are not respawnable)

  • no output attribute as tests use their own output logging mechanism

  • The machine attribute is ignored

It also adds several attributes, which are documented below.

Required attributes

pkg="mypackage"

Required

Package of node.

test-name="test_name"

Required

Name of test for recording in test results.

type="nodetype"

Required

Node type. There must be a corresponding executable with the same name.

Optional attributes

name="nodename"

(optional)

Node name. NOTE: name cannot contain a namespace. Use the ns attribute instead. If this attribute is not specified, value of test-name is used as node name

args="arg1 arg2 arg3"

(optional)

Pass arguments to node.

clear_params="true|false"

(optional)

Delete all parameters in the node's private namespace before launch.

cwd="ROS_HOME|node"

(optional)

If 'node', the working directory of the node will be set to the same directory as the node's executable. In C Turtle, the default is 'ROS_HOME'. In boxturtle (ROS 1.0.x), the default is 'ros-root'. The use of 'ros-root' is deprecated in cturtle.

launch-prefix="prefix arguments"

(optional)

Command/arguments to prepend to node's launch arguments. This is a powerful feature that enables you to enable gdb, valgrind, xterm, nice, or other handy tools. See Roslaunch Nodes in Valgrind or GDB for examples.

ns="foo"

(optional)

Start the node in the 'foo' namespace.

retry="0"

(optional)

Number of times to retry the test before it is considered a failure. Default is 0. This option is useful for stochastic processes that are sometimes expected to fail.

time-limit="60.0"

(optional)

Number of seconds before the test is considered a failure. Default is 60 seconds. The time limit is reset after every retry.

Elements

You can use the following XML tags inside of a <test> tag||||

Wiki: roslaunch/XML/test (last edited 2020-08-04 20:43:27 by Andre Schröder)