Skip to content

Instantly share code, notes, and snippets.

@RhinoBlindado
Last active September 5, 2024 10:43
Show Gist options
  • Select an option

  • Save RhinoBlindado/4550691ded75570d6d0ee82d8f90229d to your computer and use it in GitHub Desktop.

Select an option

Save RhinoBlindado/4550691ded75570d6d0ee82d8f90229d to your computer and use it in GitHub Desktop.
Trim RealSense generated bags
"""
Trim bag files compatible with the RealSense API
"""
import argparse
import rosbag
import rospy
parser = argparse.ArgumentParser()
parser.add_argument("--in-bag", type=str, required=True, help="Input RealSense bag to be cut")
parser.add_argument("--out-bag", type=str, default="./trimmed.bag", help="Path and filename of output trimmed bag. Default is './trimmed.bag'")
parser.add_argument("--start", type=int, default=None, help="RGB frame number where to start trimming the bag. If not set, begins at the start of original recording.")
parser.add_argument("--end", type=int, default=None, help="RGB frame number where to end trimming the bag. If not set, ends at the end of original recording.")
args = parser.parse_args()
# Read desired bag file
in_bag = args.in_bag
init_frame = args.start
end_frame = args.end
start_frame_time = None
end_frame_time = None
first_frame_t = None
last_frame_t = None
# Locate the times from the wanted frames
# - This topic contains the Frame counter from the recording.
for topic, msg, t in rosbag.Bag(in_bag).read_messages(topics="/device_0/sensor_1/Color_0/image/metadata"):
# Saved for the case of no staring frame set.
if first_frame_t is None:
first_frame_t = t
if msg.key == "Frame Counter":
if init_frame is not None:
if str(init_frame) == msg.value:
start_frame_time = t
if end_frame is not None:
if str(end_frame) == msg.value:
end_frame_time = t
# This is kept for the case of no ending frame set.
last_frame_t = t
# Used when either no starting o ending frames are set (or both, if you want that for some reason).
if init_frame is None:
start_frame_time = first_frame_t
if end_frame is None:
end_frame_time = last_frame_t
# Create the new bag file
out_bag = rosbag.Bag(args.out_bag, "w")
# First write the RealSense Headers, these are located at time = 1
header_time = rospy.Time(nsecs=1)
for topic, msg, t in rosbag.Bag(in_bag).read_messages(end_time=header_time, raw=True):
out_bag.write(topic, msg, t, raw=True)
# Offset the output as pointed out by @antoniogrimalt:
BAG_SENSORS_START_TIME = rospy.Time(nsecs=20000) # Publish start time of sensors
clip_start_time = None
# Write the rest of the bag from the frames / times selected.
for topic, msg, t in rosbag.Bag(in_bag).read_messages(start_time=start_frame_time, end_time=end_frame_time, raw=True):
if clip_start_time is None:
clip_start_time = t
new_t = (t - clip_start_time + BAG_SENSORS_START_TIME)
out_bag.write(topic, msg, new_t, raw=True)
out_bag.close()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment