[ros-users] ROS nodes & SIGINT handler

Josh Faust jfaust at willowgarage.com
Tue Aug 31 22:10:35 UTC 2010


fork() without exec() is very, very dangerous, especially in multithreaded
programs (roscpp spins up threads internally).  The signal handling is
likely to be the least of your worries -- all the file handles, sockets,
etc. will be shared between the processes.

You probably want to either:
 * Spin up a thread for each recording instance
 * Have another executable which does the recording (can probably just use
rosbag), and fork()/exec() it.

Josh

On Tue, Aug 31, 2010 at 12:06 PM, Gautier Dumonteil <
gautier.dumonteil at gmail.com> wrote:

>  Hi users,
>
> In our reseach project, we would like to be able to record bags
> "automatically" (e.g recording when our UAV is flying).
> So, I'm trying to write a simple node (*recorder_interface*) with two
> services "start_record" and "stop_record", where "start_record" callback
> launch the rosbag::recorder::run() in a child process using fork(). The
> "stop_record" callback just sends the SIGINT signal to recorder PID to stop
> recording ... but nothing happen. It seems that the ROS node forked doesn't
> handle SIGINT signals.
>
> Also, when checking available nodes with "rosnode list", I've only the *
> recorder_interface* node. I should have also something like
> "record_1283279499007996727", which is the rosbag record node.
>
> I'm wondering if a node can launch others nodes??
>
> Here, the console output and code:
>
> [ INFO] [1283279481.648585599]: Recorder_interface spinning: ready to
> record.
> [ INFO] [1283279499.006083281]: Request to record topics: test
> [ INFO] [1283279499.007996722]: Child: pid = 10497
>
> [ INFO] [1283279499.008979878]: Subscribing to /fake_alti
> [ INFO] [1283279499.009749320]: Recording to test_2010-08-31-14-31-39.bag.
>
> #include <signal.h>
> #include "ros/ros.h"
> #include "recorder_interface/rec_interface.h"
> #include "rosbag/recorder.h"
> #include "rosbag/exceptions.h"
>
> bool  recording;
> int   recorder_exit_code;
> pid_t rosbag_pid;
>
> void rosbagRecord (rosbag::RecorderOptions opts)
> {
>     char ** argv = NULL;
>     int argc=0;
>     ros::init(argc, argv, "record", ros::init_options::AnonymousName);
>
>     // **** Run the recorder
>     rosbag::Recorder recorder(opts);
>     recorder_exit_code = recorder.run();
>     ROS_INFO("recorder_exit_code: %d\n",recorder_exit_code);
> }
>
> bool startRec(recorder_interface::rec_interface::Request &req,
>                   recorder_interface::rec_interface::Response &res)
> {
>     if(!recording)
>     {
>         recording=true;
>         ROS_INFO("Request to record topics: %s", req.topics.c_str ());
>
>         // **** Fill rosbag options
>         rosbag::RecorderOptions opts;
>         opts.record_all = false;
>         opts.quiet = true;
>         opts.prefix = req.prefix;
>         opts.append_date = true;
>         opts.topics.push_back("/fake_alti");
>
>         rosbag_pid = fork();
>         if(rosbag_pid == -1)
>         {
>             // **** ouch, fork() failed
>             perror("fork");
>             exit(-1);
>         }
>         else if(rosbag_pid == 0)
>         {
>             // **** child
>             ROS_INFO("Child: pid = %d\n", (int)getpid());
>             rosbagRecord(opts);
>             exit(-1);
>         }
>     }
>     else
>     {
>         ROS_WARN("Already recording!");
>     }
>    return true;
> }
>
>
> bool stopRec(recorder_interface::rec_interface::Request &req,
>                   recorder_interface::rec_interface::Response &res)
> {
>    if(recording)
>     {
>         int err = kill(rosbag_pid, SIGINT);
>         ROS_INFO("err = %d\n",err);
>         if(err==0)
>         {
>             res.ans=recorder_exit_code;
>             recording=false;
>         }
>     }
>     else
>     {
>         ROS_WARN("Not recording!");
>     }
>    return true;
> }
>
> int main(int argc, char **argv)
> {
>   recording=false;
>
>   ros::init(argc, argv, "recorder_interface");
>   ros::NodeHandle n;
>
>   ros::ServiceServer serviceStart,serviceStop;
>   serviceStart = n.advertiseService("start_record", startRec);
>   serviceStop = n.advertiseService("stop_record", stopRec);
>   ROS_INFO("Recorder_interface spinning: ready to record.");
>   ros::spin();
>   return 0;
> }
>
>
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100831/c526df18/attachment-0003.html>


More information about the ros-users mailing list