Adding a unit test and fixing the player to parse ros command line opts
This commit is contained in:
parent
31aa377728
commit
912419a9a9
|
@ -32,8 +32,12 @@ INSTALL(TARGETS record play
|
|||
|
||||
rosbuild_download_test_data(http://pr.willowgarage.com/data/rosbag/slash.bag test/slash.bag 422e90f34482ece900fd2ac5d4f002de)
|
||||
rosbuild_download_test_data(http://pr.willowgarage.com/data/rosbag/test_indexed_1.2.bag test/test_indexed_1.2.bag 523cc0deb66269c84be4a7c605ff5eb3)
|
||||
rosbuild_download_test_data(http://pr.willowgarage.com/data/rosbag/chatter_50hz.bag test/chatter_50hz.bag 00844db3729b1b5f34e767dc691bd531)
|
||||
|
||||
rosbuild_add_gtest(test_bag test/test_bag.cpp)
|
||||
target_link_libraries(test_bag rosbag)
|
||||
|
||||
rosbuild_add_rostest(test/rosbag_play.test)
|
||||
rosbuild_add_rostest(test/play_play.test)
|
||||
|
||||
rosbuild_add_pyunit(test/test_bag.py)
|
||||
|
|
|
@ -84,6 +84,8 @@ rosbag::PlayerOptions parseOptions(int argc, char** argv) {
|
|||
}
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
ros::init(argc, argv, "play", ros::init_options::AnonymousName);
|
||||
|
||||
// Parse the command-line options
|
||||
rosbag::PlayerOptions opts;
|
||||
try {
|
||||
|
@ -94,8 +96,6 @@ int main(int argc, char** argv) {
|
|||
return 1;
|
||||
}
|
||||
|
||||
ros::init(argc, argv, "play", ros::init_options::AnonymousName);
|
||||
|
||||
rosbag::Player player(opts);
|
||||
|
||||
try {
|
||||
|
|
|
@ -64,7 +64,7 @@ PlayerOptions::PlayerOptions() :
|
|||
bag_time_frequency(0.0),
|
||||
time_scale(1.0),
|
||||
queue_size(0),
|
||||
advertise_sleep(200000),
|
||||
advertise_sleep(0.2),
|
||||
try_future(false),
|
||||
has_time(false),
|
||||
loop(false),
|
||||
|
|
|
@ -0,0 +1,9 @@
|
|||
<launch>
|
||||
<node name="player" pkg="rosbag" type="play" args="$(find rosbag)/test/chatter_50hz.bag"/>
|
||||
<test test-name="play_hztest" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="chatter"/>
|
||||
<param name="hz" value="50.0"/>
|
||||
<param name="hzerror" value="5"/>
|
||||
<param name="test_duration" value="7.0" />
|
||||
</test>
|
||||
</launch>
|
|
@ -0,0 +1,9 @@
|
|||
<launch>
|
||||
<node name="player" pkg="rosbag" type="rosbag" args="play $(find rosbag)/test/chatter_50hz.bag"/>
|
||||
<test test-name="rosbag_play_hztest" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="chatter"/>
|
||||
<param name="hz" value="50.0"/>
|
||||
<param name="hzerror" value="5"/>
|
||||
<param name="test_duration" value="7.0" />
|
||||
</test>
|
||||
</launch>
|
Loading…
Reference in New Issue