The following are some functions that can be used to manage rosbags.

  • rosbag_inspect
      Displays rosbag information
  • rosbag_croptime
      Creates a new bag with time between tstart and tend
  • rosbag_concatenate
      Fuses two bags into a single one with no time gap between bags nor odometry displacement on the TF topic. This can be used to emulate the kidnapped robot problem.

rosbag_inspect(input_bag)

Displays rosbag information

Parameters:
  input_bag: str - Rosbag name. Bag should be in the current directory.

def rosbag_inspect(input_bag):
    
    bag_path = cwd+'/'+input_bag
    info_dict = yaml.load(rosbag.bag.Bag(bag_path, 'r')._get_yaml_info())
    print(bag_path)
    print('Start    \t: '+str(info_dict['start']))
    print('End      \t: '+str(info_dict['end']))
    duration = info_dict['end']-info_dict['start']
    print('Messages \t: '+str(info_dict['messages']))
    topics = info_dict['topics']
    #Uncomment the following if you want to see information about the topics 
    #print('(#messages) \ttopic')
    #for topic in topics:
    #    print('  ('+str(topic['messages'])+')    \t'+topic['topic'])

Example

from subprocess import check_output
import rosbag
import yaml

Check available rosbags in currect directory

cwd = check_output('pwd')[:-1]
#retrieve all .bag files
rosbag_files = [f for f in os.listdir(cwd) if (f.split('.')[-1]=='bag')] 
print(rosbag_files)
['b3test2.bag']

Inspect bag contents

rosbag_inspect(rosbag_files[0])
b3test2.bag
Start    	: 1464420259.65
End      	: 1464421250.42
Messages 	: 189935
top

rosbag_croptime(input_bag,output_bag,tstart=0,tend=2e9)

Creates a new bag with time between tstart and tend
Equivalent to

$ rosbag filter [input bag] [output bag] '(tstart <= t.secs) and (t.secs < tend)'

Parameters:
  input_bag : str - Name of the original bag.
  output_bag: str - Name of the output bag.
  tstart: float (optional) - start time.
  tend: float (optional) - end time.

def rosbag_croptime(input_bag, output_bag, tstart=0, tend=2e9):
    filter_cmd = "({}<=t.secs)and(t.secs<{})".format(tstart,tend)
    call(['rosbag','filter',input_bag,output_bag,filter_cmd])

Example

To create a new rosbag that ends at time 1464420407

t1 = 1464420407
rosbag_croptime('b3test2.bag','b3test2-1.bag',tend=t1)

Note: This may take some time if rosbags are large.

rosbag_inspect('b3test2-1.bag')
b3test2-1.bag
Start    	: 1464420259.65
End      	: 1464420407.0
Messages 	: 27615
top

rosbag_concatenate(input_bag1,input_bag2,output_bag)

Fuses two bags into a single one so that there is no time gap between bags and there is no odometry displacement on the TF topics. This can be used to emulate the kidnapped robot problem.

Parameters:
  input_bag1 : str - Name of the first original bag.
  input_bag2 : str - Name of the second original bag.
  output_bag: str - Name of the output bag that results from merging input_bag1 and 2.
Requires:
  [transform_fix](#transformfixt1t2tn)

def rosbag_concatenate(input_bag1,input_bag2,output_bag):
    #Find end of the first bag and beginning of the second
    #First bag must end before the beginning of the second
    info_dict = yaml.load(rosbag.bag.Bag(input_bag1, 'r')._get_yaml_info())
    bag1_tend = info_dict['end']
    info_dict = yaml.load(rosbag.bag.Bag(input_bag2, 'r')._get_yaml_info())
    bag2_tstart = info_dict['start']
    offset_time = bag2_tstart-bag1_tend+0.01
    offset_time = rospy.rostime.Time.from_sec(offset_time)

    pr = 1
    seq = 0
    with rosbag.bag.Bag(output_bag, 'w') as outbag:
        #The first input bag is directly copied into output bag
        for topic, msg, t in rosbag.bag.Bag(input_bag1):
            outbag.write(topic, msg, t)
            if topic=='/rosout':
                seq = msg.header.seq

            if topic=='/tf':
                if t.to_sec()>bag1_tend-1.:
                    tr1 = msg.transforms[0].transform
            outbag.write(topic, msg, t)

        #The second input bag's time is modified as well as its odometry TF
        for topic, msg, t in rosbag.bag.Bag(input_bag2):
            #new time
            tnew = rospy.rostime.Time.from_sec((t-offset_time).to_sec())
            if topic=='/tf':
                # considerations: only odometry is corrected and 
                #                 odometry is the only transform,
                if pr:
                    # first tf
                    tr2 = msg.transforms[0].transform
                    pr = 0
                trn = msg.transforms[0].transform
                msg.transforms[0].transform = transform_fix(tr1,tr2,trn)

                for transform in msg.transforms:
                    transform.header.stamp = tnew
            else:
                try:
                    msg.header.stamp = tnew
                except:
                    pass

            if topic=='/rosout':
                seq += 1
                msg.header.seq = seq
            if topic=='/rss':
                msg.time_start_ns = msg.time_start_ns-long(offset_time.to_nsec())

            outbag.write(topic, msg, tnew)

Examples

First we create two new rosbag from times t0 to t1 and from t2 to t3. t2 > t1

t1 = 1464420407
t2 = 1464420517
t3 = 1464420682

rosbag_croptime('b3test2.bag','b3test2-1.bag',tend=t1)
rosbag_croptime('b3test2.bag','b3test2-2.bag',tstart=t2,tend=t3)

Now, we create a new bag that has all messages from the start until t1, then skips without noticeable time gap nor odometry displacement to t2 and continues until t3

rosbag_concatenate('b3test2-1.bag','b3test2-2.bag','b3test2-krp.bag')

This bag emulates a kidnapped robot problem where the robot was kidnapped from its location at t1 to its location at t2.

rosbag_inspect('b3test2-krp.bag')
b3test2-krp.bag
Start    	: 1464420259.65
End      	: 1464420571.97
Messages 	: 87635
top

transform_fix(t1,t2,tn)

Computes the new time of tn if two bags are combined without time gaps.

Parameters:
  t1 : float - End time of first bag.
  t2 : float - Start time of second bag. t2 has to be higher than t1.
  tn : float - time at the second bag.
Returns:
  tout : str - time tn if the two bags are combined without time gaps.

def transform_fix(t1,t2,tn):
    """
    t1,t2,tn
    """
    #translation
    dx = tn.translation.x - t2.translation.x
    dy = tn.translation.y - t2.translation.y
    
    #rotation
    euler1 = tf.transformations.euler_from_quaternion([t1.rotation.x, t1.rotation.y, t1.rotation.z, t1.rotation.w])
    euler2 = tf.transformations.euler_from_quaternion([t2.rotation.x, t2.rotation.y, t2.rotation.z, t2.rotation.w])
    eulern = tf.transformations.euler_from_quaternion([tn.rotation.x, tn.rotation.y, tn.rotation.z, tn.rotation.w])

    dyaw = euler2[2]-euler1[2]
    
    ndx = dx*np.cos(dyaw)+dy*np.sin(dyaw)
    ndy = -dx*np.sin(dyaw)+dy*np.cos(dyaw)
    
    tout = Transform()
    tout.translation.x = ndx+t1.translation.x
    tout.translation.y = ndy+t1.translation.y

    qout = tf.transformations.quaternion_from_euler(0,0,eulern[2]-euler2[2]+euler1[2])
    tout.rotation = Quaternion(*qout)
    
    return tout
top