Making rosplay print usage cleanly even with no master and adding trivial tests that all 4 exe variants at least print usage instructions.

This commit is contained in:
Jeremy Leibs 2009-10-02 21:39:24 +00:00
parent 80e00d36ce
commit a732065b46
6 changed files with 115 additions and 21 deletions

View File

@ -21,3 +21,4 @@ rospack_add_executable(rosplay src/rosplay/rosplay.cpp src/rosplay/time_publishe
INSTALL(TARGETS rosrecord rosplay
RUNTIME DESTINATION $ENV{ROS_ROOT}/bin)
rospack_add_pyunit(test/test_rosrecord_offline.py)

View File

@ -60,7 +60,9 @@ private:
ros::Time getSysTime();
void doPublish(std::string name, ros::Message* m, ros::Time play_time, ros::Time record_time, void* n);
ros::NodeHandle node_handle;
// This is a pointer to allow player to start before node handle
// exists since this is where argument parsing happens.
ros::NodeHandle* node_handle;
bool bag_time_initialized_, at_once_, quiet_, paused_, shifted_, bag_time_;
double time_scale_;
@ -71,7 +73,8 @@ private:
unsigned int advertise_sleep_;
termios orig_flags_;
TimePublisher bag_time_publisher_;
// This internall containers a nodehandle so we make a pointer for the same reason
TimePublisher* bag_time_publisher_;
double bag_time_frequency_;
fd_set stdin_fdset_;

View File

@ -11,6 +11,7 @@ deserialization and reserialization of the messages.
<depend package="roscpp"/>
<depend package="rospy"/>
<depend package="topic_tools"/>
<depend package="rostest"/>
<export>
<cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lrosrecorder"/>
</export>

View File

@ -65,6 +65,7 @@ void print_help()
RosPlay::RosPlay(int i_argc, char **i_argv) :
node_handle(NULL),
bag_time_initialized_(false),
at_once_(false),
quiet_(false),
@ -72,7 +73,8 @@ RosPlay::RosPlay(int i_argc, char **i_argv) :
shifted_(false),
bag_time_(false),
time_scale_(1.0),
queue_size_(0)
queue_size_(0),
bag_time_publisher_(NULL)
{
const int fd = fileno(stdin);
@ -129,9 +131,12 @@ RosPlay::RosPlay(int i_argc, char **i_argv) :
fprintf(stderr, "You can only play one single bag when using bag time [-b].\n");
print_usage(); ros::shutdown(); return;
}
node_handle = new ros::NodeHandle;
bag_time_publisher_ = new TimePublisher;
if (bag_time_)
bag_time_publisher_.initialize(bag_time_frequency_, time_scale_);
bag_time_publisher_->initialize(bag_time_frequency_, time_scale_);
start_time_ = getSysTime();
requested_start_time_ = start_time_;
@ -162,6 +167,16 @@ RosPlay::RosPlay(int i_argc, char **i_argv) :
RosPlay::~RosPlay()
{
if (node_handle)
{
// This sleep shouldn't be necessary
usleep(1000000);
delete node_handle;
}
if (bag_time_publisher_)
delete bag_time_publisher_;
// Fix terminal settings.
const int fd = fileno(stdin);
tcsetattr(fd,TCSANOW,&orig_flags_);
@ -171,12 +186,12 @@ RosPlay::~RosPlay()
bool RosPlay::spin()
{
if (node_handle.ok()){
if (node_handle && node_handle->ok()){
if(!quiet_)
puts("");
ros::WallTime last_print_time(0.0);
ros::WallDuration max_print_interval(0.1);
while (node_handle.ok()){
while (node_handle->ok()){
if (!player_.nextMsg())
break;
ros::WallTime t = ros::WallTime::now();
@ -216,17 +231,17 @@ void RosPlay::doPublish(string name, ros::Message* m, ros::Time play_time, ros::
if (!bag_time_initialized_){
// starting in paused mode
if (paused_)
bag_time_publisher_.stepTime(record_time);
bag_time_publisher_->stepTime(record_time);
// starting in play mode
else
bag_time_publisher_.startTime(record_time);
bag_time_publisher_->startTime(record_time);
bag_time_initialized_ = true;
}
// at once
if (at_once_)
bag_time_publisher_.startTime(record_time);
bag_time_publisher_->startTime(record_time);
else
bag_time_publisher_.setHorizon(play_time);
bag_time_publisher_->setHorizon(play_time);
}
@ -238,11 +253,11 @@ void RosPlay::doPublish(string name, ros::Message* m, ros::Time play_time, ros::
if (pub_token == g_publishers.end())
{
AdvertiseOptions opts(name, queue_size_, m->__getMD5Sum(), m->__getDataType(), m->__getMessageDefinition());
ros::Publisher pub = node_handle.advertise(opts);
ros::Publisher pub = node_handle->advertise(opts);
g_publishers.insert(g_publishers.begin(), std::pair<std::string, ros::Publisher>(name, pub));
pub_token = g_publishers.find(name);
if (bag_time_) bag_time_publisher_.freezeTime();
if (bag_time_) bag_time_publisher_->freezeTime();
Time paused_time_ = getSysTime();
ROS_INFO("Sleeping %.3f seconds after advertising %s...",
advertise_sleep_ / 1e6, name.c_str());
@ -250,7 +265,7 @@ void RosPlay::doPublish(string name, ros::Message* m, ros::Time play_time, ros::
ROS_INFO("Done sleeping.\n");
Duration shift = getSysTime() - paused_time_;
player_.shiftTime(shift);
if (bag_time_) bag_time_publisher_.startTime(record_time);
if (bag_time_) bag_time_publisher_->startTime(record_time);
}
if (!at_once_){
@ -258,10 +273,10 @@ void RosPlay::doPublish(string name, ros::Message* m, ros::Time play_time, ros::
ros::Time now = getSysTime();
ros::Duration delta = play_time - getSysTime();
while ( (paused_ || delta > ros::Duration(0,100000)) && node_handle.ok()){
while ( (paused_ || delta > ros::Duration(0,100000)) && node_handle->ok()){
bool charsleftorpaused = true;
while (charsleftorpaused && node_handle.ok()){
while (charsleftorpaused && node_handle->ok()){
//Read from stdin:
char c = EOF;
@ -288,12 +303,12 @@ void RosPlay::doPublish(string name, ros::Message* m, ros::Time play_time, ros::
case ' ':
paused_ = !paused_;
if (paused_) {
if (bag_time_) bag_time_publisher_.freezeTime();
if (bag_time_) bag_time_publisher_->freezeTime();
paused_time_ = getSysTime();
std::cout << std::endl << "Hit space to resume, or 's' to step.";
std::cout.flush();
} else {
if (bag_time_) bag_time_publisher_.startTime(record_time);
if (bag_time_) bag_time_publisher_->startTime(record_time);
ros::Duration shift;
if (shifted_){
shift = getSysTime() - play_time;
@ -311,7 +326,7 @@ void RosPlay::doPublish(string name, ros::Message* m, ros::Time play_time, ros::
case 's':
if (paused_){
shifted_ = true;
if (bag_time_) bag_time_publisher_.stepTime(record_time);
if (bag_time_) bag_time_publisher_->stepTime(record_time);
(pub_token->second).publish(*m);
return;
}
@ -329,7 +344,7 @@ void RosPlay::doPublish(string name, ros::Message* m, ros::Time play_time, ros::
delta = play_time - getSysTime();
}
if (!paused_ && delta > ros::Duration(0, 5000) && node_handle.ok())
if (!paused_ && delta > ros::Duration(0, 5000) && node_handle->ok())
usleep(delta.toNSec()/1000 - 5); // Should this be a ros::Duration::Sleep?
}
(pub_token->second).publish(*m);
@ -478,7 +493,6 @@ int main(int argc, char **argv)
return 1;
}
usleep(1000000);
return 0;
}

View File

@ -78,7 +78,7 @@ boost::condition_variable_any g_queue_condition;
//! Helper function to print executable usage
void print_usage() {
fprintf (stderr, "usage: rosrecord [options] TOPIC1 [TOPIC2 TOPIC3...]\n"
fprintf (stderr, "USAGE: rosrecord [options] TOPIC1 [TOPIC2 TOPIC3...]\n"
" rosrecord logs ROS message data to a file.\n"
);
}

View File

@ -0,0 +1,75 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2009, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
# Revision $Id: test_rostopic_command_line_offline.py 5710 2009-08-20 03:11:04Z sfkwc $
from __future__ import with_statement
NAME = 'test_rosrecord_offline'
import roslib; roslib.load_manifest('rosrecord')
import os
import sys
import unittest
import cStringIO
import time
import rostest
from subprocess import Popen, PIPE, check_call, call
class TestRosrecordOffline(unittest.TestCase):
def setUp(self):
pass
## test that the rosmsg command works
def test_rosrecord_help(self):
self.do_test_help('rosrecord');
def test_rosplay_help(self):
self.do_test_help('rosplay');
def test_rosrecord_pkg_help(self):
self.do_test_help('rosrun rosrecord rosrecord');
def test_rosplay_pkg_help(self):
self.do_test_help('rosrun rosrecord rosplay');
def do_test_help(self, cmd):
rosrecord = Popen(cmd.split() + ['-h'], stdout=PIPE, stderr=PIPE)
output = rosrecord.communicate()
self.assert_('USAGE' in output[0] or 'USAGE' in output[1])
if __name__ == '__main__':
rostest.unitrun('rosrecord', NAME, TestRosrecordOffline, sys.argv, coverage_packages=[])