Online Bagger

class nodes.online_bagger.OnlineBagger[source]

Node that maintains a list of bagged information relating to the specified topics.

Subscribes to a list of ROS topics, and maintains a buffer of the most recent n seconds. Parts or all of these buffered topics can be written to a bag file by sending a new goal to the /online_bagger/bag action server. When run with the -c flag, instead runs an action client which connects to online bagger, triggering a bag write and displaying a progress bar as it writes.

successful_subscription_count

The number of successful subscriptions to topics.

Type

int

iteration_count

The number of iterations.

Type

int

streaming

Indicates whether the bagger is streaming.

Type

bool

subscriber_list

The list of topics subscribed to the OnlineBagger.

Type

list[str]

Make dictionary of dequeues. Subscribe to set of topics defined by the yaml file in directory Stream topics up to a given stream time, dump oldest messages when limit is reached Set up service to bag n seconds of data default to all of available data

bagger_callback(msg: genpy.Message, topic: str)[source]

Adds incoming messages to the appropriate topic and removes older messages if necessary.

Streaming callback function, stops streaming during bagging process and pops off msgs from dequeue if stream size is greater than specified stream_time. Stream, callback function does nothing if streaming is not active.

Parameters
  • msg (genpy.Message) – The incoming message.

  • topic (str) – The topic to which the incoming message will be added.

get_bag_name(filename: str = '')[source]

Create ros bag save directory If no bag name is provided, the current date/time is used as default.

Parameters

filename (str) – The save directory for the ros bag. The default value is an empty string, which will result in the default filename being used.

Returns

A string representing the path of the ros bag file.

Return type

str

get_header_time(msg: genpy.Message)[source]

Retrieve header time if available

Parameters

msg (genpy.Message) – The ROS message from which to extract the time.

Returns

The timestamp of the topic’s header if the topic

has a header. Otherwise, the current time is returned.

Return type

rospy.Time

get_params()[source]

Retrieve parameters from param server.

get_subscriber_list(status)[source]

Get string of all topics, if their subscribe status matches the input (True / False) Outputs each topics: time_buffer(float in seconds), subscribe_statue(bool), topic(string)

Parameters

status (bool) – The subscription status used to search for topics with a matching subscription status.

Returns

The list of topics that match the desired subscribe status. Each

line in the list contains the buffer time (in seconds) of the topic, the subscrition status of the topic, and the topic name.

Return type

string

get_time_index(topic, requested_seconds)[source]

Returns the index for the time index for a topic at ‘n’ seconds from the end of the dequeue.

For example, to bag the last 10 seconds of data, the index for 10 seconds back from the most recent message can be obtained with this function. The number of requested seconds should be the number of seoncds desired from the end of deque. (ie. requested_seconds = 10 ) If the desired time length of the bag is greater than the available messages it will output a message and return how ever many seconds of data are available at the moment. Seconds is of a number type (not a rospy.Time type) (ie. int, float)

Parameters
  • topic (str) – The name of the topic for which to get the time index.

  • requested_seconds (int/float) – The number of seconds from the end of the dequeue to search for the topic.

Returns

The index for the time index of the topic at requested_seconds seconds from the end of the dequeue.

Return type

int

get_topic_duration(topic: str)[source]

Returns the current time duration of topic

Parameters

topic (str) – The topic for which the duration will be calculated.

Returns

The time duration of the topic.

Return type

Duration

get_topic_message_count(topic: str)[source]

Return number of messages available in a topic

Parameters

topic (str) – The name of the topic for which to calculate the number of messages.

Returns

The number of messages available in the specified topic.

Return type

int

get_total_message_count()[source]

Returns total number of messages across all topics

Returns

The total number of messages available in all topics.

Return type

int

make_dicts()[source]

Make dictionary with sliceable dequeues() that will be filled with messages and time stamps.

Subscriber list contains all of the topics, their stream time and their subscription status: A True status for a given topic corresponds to a successful subscription A False status indicates a failed subscription.

Stream time for an individual topic is specified in seconds.

For Example: self.subscriber_list[0:1] = [[‘/odom’, 300 ,False], [‘/absodom’, 300, True]]

Indicates that ‘/odom’ has not been subscribed to, but ‘/absodom’ has been subscribed to

self.topic_messages is a dictionary of dequeues containing a list of tuples. Dictionary Keys contain topic names Each value for each topic contains a deque Each deque contains a list of tuples Each tuple contains a message and its associated time stamp

For example: ‘/odom’ is a potential topic name self.topic_message[‘/odom’] is a deque self.topic_message[‘/odom’][0] is the oldest message available in the deque and its time stamp if available. It is a tuple with each element: (time_stamp, msg) self.topic_message[‘/odom’][0][0] is the time stamp for the oldest message self.topic_message[‘/odom’][0][1] is the message associated with the oldest topic

start_bagging(req: BagOnlineGoal)[source]

Writes collected data to a bag file.

Dump all data in dictionary to bags, temporarily stops streaming during the bagging process, resumes streaming when over. If bagging is already false because of an active call to this service.

Parameters

req (BagOnlineGoal) – The bagging request information.

Raises

IOError – A problem occurs when opening or closing the bag file.

subscribe(_: rospy.timer.TimerEvent | None = None)[source]

Subscribe to the topics defined in the yaml configuration file

Function checks subscription status True/False of each topic if True: topic has already been successfully subscribed to if False: topic still needs to be subscribed to and subscriber will be run.

Each element in self.subscriber list is a list [topic, Bool] where the Bool tells the current status of the subscriber (success/failure).

subscribe_loop()[source]

Continue to subscribe until at least one topic is successful, then break out of loop and be called in the callback function to prevent the function from locking up.