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

start and stop rosbag within a python script

asked 2011-07-25 05:59:25 -0500

r_kempf gravatar image

updated 2016-10-24 09:05:59 -0500

ngrennan gravatar image

Hi,

I wrote an Action Server which gets all topics I want to record via the goal. Everything works fine until i want to stop rosbag. With my script i can start rosbag out of my script and i can see the bag-file which is generated. But when i want to kill the rosbag process out of my script, rosbag doesn't stop. It doesn't stop until i stop my whole ActionServer. But the action server should still run after stopping rosbag.

Here is the code I wrote: (the topic_logger.msg includes the goal, an id and an array of topics)

#! /usr/bin/env python

import roslib; roslib.load_manifest('topic_logger')
import rospy
import subprocess
import signal

import actionlib

import topic_logger.msg

class TopicLoggerAction(object):
# create messages that are used to publish feedback/result
_feedback = topic_logger.msg.topicLoggerFeedback()
_result = topic_logger.msg.topicLoggerResult()

def __init__(self, name):
    self._action_name = name
    self._as = actionlib.SimpleActionServer(self._action_name, topic_logger.msg.TopicLoggerAction, execute_cb = self.execute_cb)
    self._as.start()
    rospy.loginfo('Server is up')

def execute_cb(self, goal):
    if goal.ID == "topicLog":
        # decide whether recording should be started or stopped
        if goal.command == "start":
            #start to record the topics
            rospy.loginfo('now the topic recording should start')
            args = ""               
            for i in goal.selectedTopics:
                args = args + " " + i
            command = "rosbag record" + args
            self.p = subprocess.Popen(command, stdin=subprocess.PIPE, shell=True, cwd=dir_save_bagfile)
            rospy.loginfo(self.p.pid)
            # process = p
            # print p.stdout.read()
            # check if the goal is preempted    
            while 1:
                if self._as.is_preempt_requested():
                    rospy.loginfo('Logging is preempted')
                    self._as.set_preempted()
                    break

        elif goal.command == "stop":
            #stop to record the topics
            rospy.loginfo('now the topic recording should stop')
            #self.p.send_signal(signal.SIGTERM)
            rospy.loginfo(self.p.pid)
            killcommand = "kill -9 " + str(self.p.pid)
            rospy.loginfo(killcommand)
            self.k = subprocess.Popen(killcommand, shell=True)

            rospy.loginfo("I'm done")
            #while 1:
            #   if self._as.is_preempt_requested():
            #       rospy.loginfo('Logging is preempted')
            #       self._as.set_preempted()
            #       break

        else:
            rospy.loginfo('goal.command is not valid')
    else:
        rospy.loginfo('goal.ID is not valid')

if __name__ == '__main__':
rospy.init_node('topicLogger')
dir_save_bagfile = '/home/ker1pal/'
TopicLoggerAction(rospy.get_name())
rospy.spin()

Are there any ideas why I can't stop rosbag out of my script without killing my whole ActionServer ?

Thanks Ralf

edit retag flag offensive close merge delete

6 Answers

Sort by ยป oldest newest most voted
3

answered 2011-07-26 09:01:04 -0500

heyneman gravatar image

Ralf,

I'm just now playing around with actionlib, so I don't know if there are any other interactions, but I also recently wrote a node with starts recording data via rosbag and subprocess.Popen(). I've been ending the rosbag session with:

rosbag_proc = subprocess.Popen(...)
...
rosbag_proc.send_signal(subprocess.signal.SIGINT)

SIGINT is the same as "Ctrl-C" for Unix. It seems to end the rosbag process cleanly without adversely affecting my ROS node.

edit flag offensive delete link more

Comments

4
I tried it bevor by sending such a signal but it doesn't help.what are the parameters you give to Popen?
r_kempf gravatar image r_kempf  ( 2011-07-27 10:00:17 -0500 )edit
1

When I end rosbag record by pressing Ctrl-C, it ends cleanly. But when I use subprocess.Popen and send_signal(signal.SIGINT), nothing happens (the child process doesn't stop recording). If I use SIGTERM, I end up with a filename.bag.active file, which is not good. :-(

rahvee gravatar image rahvee  ( 2018-06-01 09:14:07 -0500 )edit
1

sending Ctrl-C to rosbag record seems to stop the main process, but the child processes seem to keep running. I could finish the recording properly by sending one more Ctrl-C to one of the subprocesses. An alternative is sending SIGINT to the complete process group.

Tones gravatar image Tones  ( 2019-04-15 11:37:29 -0500 )edit
10

answered 2012-04-11 06:55:21 -0500

sergey_alexandrov gravatar image

updated 2012-04-15 00:20:32 -0500

Seems like

self.p = subprocess.Popen(command, stdin=subprocess.PIPE, shell=True, cwd=dir_save_bagfile)

starts a shell which then starts the program that does the job. One could see it with ps:

$ ps aux | grep record
sergey   17900  0.0  0.0   4272   584 pts/4    S    18:36   0:00 /bin/sh -c rosbag record -O /home/ . . . 
sergey   17901  7.3  0.1 288132  7124 pts/4    Sl   18:36   0:00 record --buffsize 256 -O /home/ . . .

Therefore killing the process with pid returned by subprocess.Popen does not kill the actual bag recording. We also need to kill its child. There is a nice code snippet here for kill_child_processes(). Here is my modified version:

import subprocess, os, signal

def terminate_process_and_children(p):
    ps_command = subprocess.Popen("ps -o pid --ppid %d --noheaders" % p.pid, shell=True, stdout=subprocess.PIPE)
    ps_output = ps_command.stdout.read()
    retcode = ps_command.wait()
    assert retcode == 0, "ps command returned %d" % retcode
    for pid_str in ps_output.split("\n")[:-1]:
            os.kill(int(pid_str), signal.SIGINT)
    p.terminate()

This function expects a subprocess.Popen object.

edit flag offensive delete link more

Comments

Works for me!

bchr gravatar image bchr  ( 2014-12-05 10:23:06 -0500 )edit

I don't fully understand it, but it works for me!

RafBerkvens gravatar image RafBerkvens  ( 2015-01-30 05:01:10 -0500 )edit

Thank you so much! Been looking for hours for something that did this. And the built in kill commands from subprocess refused to kill the child of rosbag play

vorilant gravatar image vorilant  ( 2016-07-28 17:49:03 -0500 )edit
5

answered 2013-12-06 01:20:57 -0500

schadlerm gravatar image

I was recently looking for solving the same issue and thought I would add my experience as this thread didn't have an answer that solved my problem.

The issue I was seeing was that rosbag would not clean exit, and thus write the .bag.active -> .bag file. Sending SIGINT, SIGKILL, etc.. in any order to the processes could not remedy the situation on my system.

Using rosnode I was able to kill the rosbag and have it cleanly exit. This would be more difficult when running multiple rosbag records at once (as you would need to find the rosnode id of each), however with only one running rosbag record, simply using 'rosnode list' to search for "/record_xxxx" and then executing "rosnode kill /record_xxxx" where xxx is the node id will cleanly exit the rosbag recording process.

def terminate_ros_node(s):
    list_cmd = subprocess.Popen("rosnode list", shell=True, stdout=subprocess.PIPE)
    list_output = list_cmd.stdout.read()
    retcode = list_cmd.wait()
    assert retcode == 0, "List command returned %d" % retcode
    for str in list_output.split("\n"):
        if (str.startswith(s)):
            os.system("rosnode kill " + str)

terminate_ros_node("/record")
edit flag offensive delete link more

Comments

Hi schadlerm! Thanks for sharing this info. I am running into the same problem, with C implementation. I am trying to launch and kill with SIGINT rosbag from C application. The main problem is that sometimes I end up with un-indexed bagfile. If you have any idea for this, I would appreciate it.

fapofa gravatar image fapofa  ( 2013-12-08 22:31:21 -0500 )edit
2

This was extremely useful! I created a simple gist as an example: example rosbag_record.py

Femer gravatar image Femer  ( 2017-04-28 05:43:58 -0500 )edit

Yours is the only solution that worked for me here, though I modified line 7 to be if (str.startswith(s + "_") or str == s): because the node that publishes to rosout is called "/recorder", so yours will probably try to kill that node also.

adamconkey gravatar image adamconkey  ( 2018-05-31 17:21:34 -0500 )edit
4

answered 2016-01-07 05:27:46 -0500

lgeorge gravatar image

updated 2016-01-07 05:28:41 -0500

Similar to sergey_alexandrov answer, but using psutils python module as highlight on stackoverflow : http://stackoverflow.com/questions/33...

def terminate_process_and_children(p):
  import psutil
  process = psutil.Process(p.pid)
  for sub_process in process.get_children(recursive=True):
      sub_process.send_signal(signal.SIGINT)
  p.wait()  # we wait for children to terminate
  p.terminate()

def main():
  dir_save_bagfile = '/tmp/'
  rosbag_process = subprocess.Popen('rosbag record -a -j -o {}'.format("my_rosbag_prefis"), stdin=subprocess.PIPE, shell=True, cwd=dir_save_bagfile)
  terminate_process_and_children(rosbag_process)
edit flag offensive delete link more

Comments

5

I had to change process.get_children to process.children and remove the p.terminate() (process is already gone at that point) but after that it is working.

Felix Widmaier gravatar image Felix Widmaier  ( 2017-08-10 03:51:08 -0500 )edit
1

Yeah agreed with @Felix Widmaier here that this snippet doesn't quite work as described

canderson gravatar image canderson  ( 2019-09-16 19:32:12 -0500 )edit
3

answered 2020-09-12 12:12:18 -0500

vbs gravatar image

Picking from many of the answers here, I've come up with a class and ROS node to control recording start, stop and pause. Find it here.

You can either import the class and use it directly in your code or start the node standalone and use service calls to control recording.

There is a problem with pausing where, sometimes, some of the messages get their timestamps wrong after resuming recording. Unfortunately, I don't have the time to debug it now. Start and stop seem to work fine.

Tested with Ubuntu 16 and Kinetic.

edit flag offensive delete link more
0

answered 2015-10-20 13:22:40 -0500

lucasw gravatar image

The best solution to programmatic rosbag recording I've found is to wrap rosbag::Recorder in a C++ node. There isn't a way to shutdown recording in Recorder, but there can be a subscriber which calls ros::shutdown which will cleanly close the current recording bag file, and then the the node can be set to respawn=true. The exclude list can be passed in as a parameter and then useful other parameters set like below, or have params override defaults as desired:

  recorder_options_.exclude_regex = some_string_from_ros_param;
  ROS_INFO_STREAM("exclude list \"" << recorder_options_.exclude_regex << "\"");

  recorder_options_.record_all = true;    
  recorder_options_.trigger = false;
  recorder_options_.regex = false;
  recorder_options_.do_exclude = true;
  recorder_options_.quiet = false;
  recorder_options_.append_date = true;
  recorder_options_.verbose = false;
  recorder_options_.buffer_size = 1048576 * 512;
  recorder_options_.chunk_size = 1024 * 768;
  recorder_options_.limit = 0; // 0 is unlimited
  recorder_options_.split = true;
  recorder_options_.max_size = 1024 * 1024 * 1024;
  recorder_options_.min_space = 1024 * 1024 * 1024;
  recorder_options_.min_space_str = "Recording space is running out";
edit flag offensive delete link more

Question Tools

6 followers

Stats

Asked: 2011-07-25 05:59:25 -0500

Seen: 15,279 times

Last updated: Sep 12 '20