Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Release fixups #72

Merged
merged 7 commits into from
Dec 14, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions ros2bag/ros2bag/verb/info.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
# limitations under the License.

import os
import sys

from ros2bag.verb import VerbExtension

Expand All @@ -30,6 +29,6 @@ def add_arguments(self, parser, cli_name): # noqa: D102
def main(self, *, args): # noqa: D102
bag_file = args.bag_file
if not os.path.exists(bag_file):
return "Error: bag file '{}' does not exist!".format(bag_file)
return "[ERROR] [ros2bag]: bag file '{}' does not exist!".format(bag_file)

rosbag2_transport_py.info(uri=bag_file)
16 changes: 13 additions & 3 deletions ros2bag/ros2bag/verb/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
# limitations under the License.

import os
import sys

from ros2bag.verb import VerbExtension

Expand All @@ -26,10 +25,21 @@ class PlayVerb(VerbExtension):
def add_arguments(self, parser, cli_name): # noqa: D102
parser.add_argument(
'bag_file', help='bag file to replay')
parser.add_argument(
'-s', '--storage', default='sqlite3',
help='storage identifier to be used, defaults to "sqlite3"')
parser.add_argument(
'-r', '--read-ahead-queue-size', type=int, default=1000,
help='size of message queue rosbag tries to hold in memory to help deterministic '
'playback. Larger size will result in larger memory needs but might prevent '
'delay of message playback.')

def main(self, *, args): # noqa: D102
bag_file = args.bag_file
if not os.path.exists(bag_file):
return "Error: bag file '{}' does not exist!".format(bag_file)
return "[ERROR] [ros2bag] bag file '{}' does not exist!".format(bag_file)

rosbag2_transport_py.play(uri=bag_file, storage_id='sqlite3')
rosbag2_transport_py.play(
uri=bag_file,
storage_id=args.storage,
read_ahead_queue_size=args.read_ahead_queue_size)
13 changes: 5 additions & 8 deletions ros2bag/ros2bag/verb/record.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

import datetime
import os
import sys

from ros2bag.verb import VerbExtension

Expand All @@ -28,11 +27,9 @@ class RecordVerb(VerbExtension):
"""ros2 bag record."""

def add_arguments(self, parser, cli_name): # noqa: D102
self._subparser = parser

add_arguments(parser)
parser.add_argument(
'-a', '--all', action='store_true', help='recording all topics')
'-a', '--all', action='store_true',
help='recording all topics, required if no topics are listed explicitly.')
parser.add_argument(
'topics', nargs='*', help='topics to be recorded')
parser.add_argument(
Expand All @@ -59,8 +56,8 @@ def add_arguments(self, parser, cli_name): # noqa: D102
def create_bag_directory(self, uri):
try:
os.makedirs(uri)
except:
return "Error: Could not create bag folder '{}'.".format(uri)
except OSError:
return "[ERROR] [ros2bag]: Could not create bag folder '{}'.".format(uri)

def main(self, *, args): # noqa: D102
if args.all and args.topics:
Expand All @@ -69,7 +66,7 @@ def main(self, *, args): # noqa: D102
uri = args.output if args.output else datetime.datetime.now().strftime("rosbag2_%Y_%m_%d-%H_%M_%S")

if os.path.isdir(uri):
return "Error: Output folder '{}' already exists.".format(uri)
return "[ERROR] [ros2bag]: Output folder '{}' already exists.".format(uri)

self.create_bag_directory(uri)

Expand Down
8 changes: 5 additions & 3 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ void Player::wait_for_filled_queue(const PlayOptions & options) const
{
while (
message_queue_.size_approx() < options.read_ahead_queue_size &&
!is_storage_completely_loaded())
!is_storage_completely_loaded() && rclcpp::ok())
{
std::this_thread::sleep_for(queue_read_wait_period_);
}
Expand All @@ -90,7 +90,7 @@ void Player::load_storage_content(const PlayOptions & options)
static_cast<size_t>(options.read_ahead_queue_size * read_ahead_lower_bound_percentage_);
auto queue_upper_boundary = options.read_ahead_queue_size;

while (reader_->has_next()) {
while (reader_->has_next() && rclcpp::ok()) {
if (message_queue_.size_approx() < queue_lower_boundary) {
enqueue_up_to_boundary(time_first_message, queue_upper_boundary);
} else {
Expand Down Expand Up @@ -122,7 +122,9 @@ void Player::play_messages_from_queue()
ReplayableMessage message;
if (message_queue_.try_dequeue(message)) {
std::this_thread::sleep_until(start_time + message.time_since_start);
publishers_[message.message->topic_name]->publish(message.message->serialized_data);
if (rclcpp::ok()) {
publishers_[message.message->topic_name]->publish(message.message->serialized_data);
}
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,8 @@ void Rosbag2Transport::print_bag_info(const std::string & uri)
} catch (std::runtime_error & e) {
(void) e;
ROSBAG2_TRANSPORT_LOG_ERROR_STREAM("Could not read metadata for " << uri << ". Please specify "
"the path to the folder containing an existing 'metadata.yaml' file");
"the path to the folder containing an existing 'metadata.yaml' file and make sure that the "
"file 'metadata.yaml' exists and has the correct format.");
return;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ rosbag2_transport_play(PyObject * Py_UNUSED(self), PyObject * args, PyObject * k
storage_options.uri = std::string(uri);
storage_options.storage_id = std::string(storage_id);

play_options.read_ahead_queue_size = read_ahead_queue_size ? read_ahead_queue_size : 1000;
play_options.read_ahead_queue_size = read_ahead_queue_size;

rosbag2_transport::Rosbag2Transport transport;
transport.init();
Expand Down