ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Define time in synthetic rosbag

asked 2018-05-10 07:58:08 -0500

Peter1 gravatar image

I am creating a rosbag from a csv file. I am using the python api. My question is how can I set the time information in the bag with which it will be player back. the relevant parts of my current code look like this:

import os
import rosbag
import rospy 
from nav_msgs.msg import Odometry
import numpy as np

try:
file = os.path.expanduser('test.csv')

# Get data from text file(s)
data = np.genfromtxt(file, delimiter=',', skip_header=0, skip_footer=0, names=True)
bag = rosbag.Bag('test.bag', 'w')
time = data['Nano_from_start_of_regions']
time = time - time[0]
v_x = data['Velocity_forwardms']
v_y = data['Velocity_lateralms']
v_z = data['Velocity_downms']
odom = Odometry()
time = np.array(time)
sec_time = time.astype(int)
nsec_time = (time-sec_time)*10e8
nsec_time = np.array(nsec_time)
nsec_time = nsec_time.astype(int)

for i in range(len(time)):
    odom.header.frame_id = 'odom'
    odom.child_frame_id = 'base_link'
    odom.header.stamp.secs = sec_time[i]
    odom.header.stamp.nsecs= nsec_time[i]
    odom.twist.twist.linear.x = v_x[i]
    odom.twist.twist.linear.y = v_y[i]
    odom.twist.twist.linear.z = v_z[i]

    bag.write('odom',odom)

finally:
bag.close()

how ever the time in the header doesnt seem to have an influence on the bag. its just saves it as fast as possible and replays at the same speed. How could I change that speed? Clock topic?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-05-10 08:24:58 -0500

lucasw gravatar image

updated 2018-05-10 08:47:33 -0500

There is a third parameter to write that holds the time, set it to header.stamp.

http://docs.ros.org/api/rosbag/html/p...

(I can't link straight to it because the html prevents it: click rosbag.bag on the left, then Bag on the right, then write() appears)

rosbag play will use that time during playback, it doesn't use the header time because many messages don't have headers. Not supplying the time results in the current time being used.

The tutorial example should be changed to show that if it doesn't.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2018-05-10 07:58:08 -0500

Seen: 262 times

Last updated: May 10 '18