Skip to content

Commit

Permalink
TOPIC TOOLS: add tests for initial_topic param
Browse files Browse the repository at this point in the history
  • Loading branch information
kev-the-dev committed Oct 23, 2017
1 parent 92dca54 commit 0c072a2
Show file tree
Hide file tree
Showing 3 changed files with 43 additions and 0 deletions.
2 changes: 2 additions & 0 deletions tools/topic_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,8 @@ if(CATKIN_ENABLE_TESTING)
add_rostest(test/relay.test)
add_rostest(test/relay_stealth.test)
add_rostest(test/lazy_transport.test)
add_rostest(test/mux_initial_none.test)
add_rostest(test/mux_initial_other.test)
## Latched test disabled until underlying issue in roscpp is resolved,
## #3385, #3434.
#rosbuild_add_rostest(test/relay_latched.test)
Expand Down
20 changes: 20 additions & 0 deletions tools/topic_tools/test/mux_initial_none.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<launch>
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
args="pub -r 10 input1 std_msgs/String input1"/>
<node pkg="rostopic" type="rostopic" name="rostopic_pub2"
args="pub -r 5 input2 std_msgs/String input2"/>

<!-- Initial topic is __none -->
<node pkg="topic_tools" type="mux" name="mux_initial_none" output="screen"
args="output input1 input2">
<param name="initial_topic" value="__none" />
</node>

<!-- Test that mux initially has no input because initial_topic param is set to __none -->
<test test-name="mux_initial_topic_none_test" pkg="rostest" type="hztest">
<param name="topic" value="output"/>
<param name="hz" value="0"/>
<param name="hzerror" value="0"/>
<param name="test_duration" value="1.0" />
</test>
</launch>
21 changes: 21 additions & 0 deletions tools/topic_tools/test/mux_initial_other.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<launch>
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
args="pub -r 10 input1 std_msgs/String input1"/>
<node pkg="rostopic" type="rostopic" name="rostopic_pub2"
args="pub -r 5 input2 std_msgs/String input2"/>

<!-- Initial topic non default -->
<node pkg="topic_tools" type="mux" name="mux_explicit" output="screen"
args="output input1 input2">
<param name="initial_topic" value="input2" />
</node>

<!-- Test that initialy mux chooses input2 as specified in param -->
<test test-name="mux_hztest_explicit" pkg="rostest" type="hztest">
<param name="topic" value="output"/>
<param name="hz" value="5.0"/>
<param name="hzerror" value="0.5"/>
<param name="test_duration" value="1.0" />
</test>

</launch>

0 comments on commit 0c072a2

Please sign in to comment.