やりたいこと
Pythonスクリプトでrosbag record
を開始したり、止めたりしたい。
topic名を指定するだけで、recordしたい。
方法
import rospy
from rqt_bag.recorder import Recorder
if __name__ == '__main__':
rospy.init_node("sample")
# すべてのトピックをrecordする場合
rec_1 = Recorder("sample_1.bag")
rec_1.start()
rospy.sleep(10)
rec_1.stop()
# 特定のトピック(/hogeと/fuga)をrecordする場合
rec_2 = Recorder("sample_2.bag", topics=['/hoge', '/fuga'], all=False)
rec_2.start()
rospy.sleep(10)
rec_2.stop()
# 特定のトピック(/hogeで始まるトピック)をrecordする場合
rec_3 = Recorder("sample_3.bag", topics=['/hoge*'], regex=True, all=False)
rec_3.start()
rospy.sleep(10)
rec_3.stop()
# 各topicのメッセージを1つだけrecordする場合
rec_4 = Recorder("sample_4.bag", topics=['/hoge', '/fuga'], all=False, limit=1)
rec_4.start()
rospy.sleep(10)
rec_4.stop()
方法2~4は、オプション引数のall
をFalseにしないと、全てのトピックがsubscribeされてしまうので注意が必要。