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.<div>
<br></div><div>You probably want to either:</div><div> * Spin up a thread for each recording instance</div><div> * Have another executable which does the recording (can probably just use rosbag), and fork()/exec() it.</div>
<div><br></div><div>Josh<br><br><div class="gmail_quote">On Tue, Aug 31, 2010 at 12:06 PM, Gautier Dumonteil <span dir="ltr"><<a href="mailto:gautier.dumonteil@gmail.com">gautier.dumonteil@gmail.com</a>></span> wrote:<br>
<blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;">
<div text="#000000" bgcolor="#ffffff">
Hi users, <br>
<br>
In our reseach project, we would like to be able to record bags
"automatically" (e.g recording when our UAV is flying).<br>
So, I'm trying to write a simple node (<i>recorder_interface</i>)
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.<br>
<br>
Also, when checking available nodes with "rosnode list", I've only
the <i>recorder_interface</i> node. I should have also something
like "record_1283279499007996727", which is the rosbag record node.<br>
<br>
I'm wondering if a node can launch others nodes??<br>
<br>
Here, the console output and code:<br>
<br>
[ INFO] [1283279481.648585599]: Recorder_interface spinning: ready
to record.<br>
[ INFO] [1283279499.006083281]: Request to record topics: test<br>
[ INFO] [1283279499.007996722]: Child: pid = 10497<br>
<br>
[ INFO] [1283279499.008979878]: Subscribing to /fake_alti<br>
[ INFO] [1283279499.009749320]: Recording to
test_2010-08-31-14-31-39.bag.<br>
<br>
<small>#include <signal.h><br>
#include "ros/ros.h"<br>
#include "recorder_interface/rec_interface.h"<br>
#include "rosbag/recorder.h"<br>
#include "rosbag/exceptions.h"<br>
<br>
bool recording;<br>
int recorder_exit_code;<br>
pid_t rosbag_pid;<br>
<br>
void rosbagRecord (rosbag::RecorderOptions opts)<br>
{<br>
char ** argv = NULL;<br>
int argc=0;<br>
ros::init(argc, argv, "record",
ros::init_options::AnonymousName);<br>
<br>
// **** Run the recorder<br>
rosbag::Recorder recorder(opts);<br>
recorder_exit_code = recorder.run();<br>
ROS_INFO("recorder_exit_code: %d\n",recorder_exit_code);<br>
}<br>
<br>
bool startRec(recorder_interface::rec_interface::Request &req,<br>
recorder_interface::rec_interface::Response
&res)<br>
{<br>
if(!recording)<br>
{<br>
recording=true;<br>
ROS_INFO("Request to record topics: %s", req.topics.c_str
());<br>
<br>
// **** Fill rosbag options<br>
rosbag::RecorderOptions opts;<br>
opts.record_all = false;<br>
opts.quiet = true;<br>
opts.prefix = req.prefix;<br>
opts.append_date = true;<br>
opts.topics.push_back("/fake_alti");<br>
<br>
rosbag_pid = fork();<br>
if(rosbag_pid == -1)<br>
{<br>
// **** ouch, fork() failed<br>
perror("fork");<br>
exit(-1);<br>
}<br>
else if(rosbag_pid == 0)<br>
{<br>
// **** child<br>
ROS_INFO("Child: pid = %d\n", (int)getpid());<br>
rosbagRecord(opts);<br>
exit(-1);<br>
}<br>
}<br>
else<br>
{<br>
ROS_WARN("Already recording!");<br>
}<br>
return true;<br>
}<br>
<br>
<br>
bool stopRec(recorder_interface::rec_interface::Request &req,<br>
recorder_interface::rec_interface::Response
&res)<br>
{ <br>
if(recording)<br>
{<br>
int err = kill(rosbag_pid, SIGINT);<br>
ROS_INFO("err = %d\n",err);<br>
if(err==0)<br>
{<br>
res.ans=recorder_exit_code;<br>
recording=false;<br>
}<br>
}<br>
else<br>
{<br>
ROS_WARN("Not recording!");<br>
}<br>
return true;<br>
}<br>
<br>
int main(int argc, char **argv)<br>
{<br>
recording=false;<br>
<br>
ros::init(argc, argv, "recorder_interface");<br>
ros::NodeHandle n;<br>
<br>
ros::ServiceServer serviceStart,serviceStop;<br>
serviceStart = n.advertiseService("start_record", startRec);<br>
serviceStop = n.advertiseService("stop_record", stopRec);<br>
ROS_INFO("Recorder_interface spinning: ready to record.");<br>
ros::spin();<br>
return 0;<br>
}</small><br>
<br>
<br>
</div>
<br>_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
<br></blockquote></div><br></div>