record.cpp
Go to the documentation of this file.
1 #include <string>
2 
3 #include <ros/callback_queue.h>
4 #include <ros/console.h>
5 #include <ros/init.h>
6 #include <ros/node_handle.h>
7 #include <ros/param.h>
8 #include <ros/publisher.h>
9 #include <ros/service_server.h>
10 #include <ros/spinner.h>
11 #include <rosbag/recorder.h>
12 #include <std_msgs/Bool.h>
13 #include <std_srvs/Empty.h>
14 
15 #include <boost/scoped_ptr.hpp>
16 #include <boost/thread/thread.hpp>
17 
18 boost::scoped_ptr< rosbag::Recorder > recorder;
19 boost::thread run_thread;
20 boost::thread shutdown_thread;
22 
23 void publishIsRecording(const bool is_recording) {
24  std_msgs::BoolPtr msg(new std_msgs::Bool());
25  msg->data = is_recording;
26  is_recording_publisher.publish(msg);
27 }
28 
29 bool start(std_srvs::Empty::Request &, std_srvs::Empty::Response &) {
30  namespace rp = ros::param;
31 
32  // do nothing if the recorder already started
33  if (recorder || run_thread.joinable()) {
34  ROS_ERROR("Already started");
35  return false;
36  }
37 
38  // read recorder options
40  rp::get("~record_all", options.record_all);
41  rp::get("~regex", options.regex);
42  rp::get("~quiet", options.quiet);
43  // note: as of kinetic, the quiet option looks ignored in rosbag::Recorder :(
44  rp::get("~append_date", options.append_date);
45  rp::get("~verbose", options.verbose);
46  {
47  std::string compression;
48  if (rp::get("~compression", compression)) {
49  if (compression == "uncompressed") {
51  } else if (compression == "bz2") {
53  } else if (compression == "lz4") {
55  } else {
56  ROS_WARN_STREAM("Unknown compression type: " << compression);
57  }
58  }
59  }
60  rp::get("~prefix", options.prefix);
61  rp::get("~name", options.name);
62  rp::get("~topics", options.topics);
63  {
64  std::string exclude_regex;
65  if (rp::get("~exclude_regex", exclude_regex)) {
66  options.do_exclude = true;
67  options.exclude_regex = exclude_regex;
68  }
69  }
70  {
71  int buffer_size;
72  if (rp::get("~buffer_size", buffer_size)) {
73  options.buffer_size = buffer_size;
74  }
75  }
76  rp::get("~node", options.node);
77  // note: this node aims to enable service-triggered logging.
78  // so does not support the following options that may autonomously stop logging
79  // trigger / snapshot / chunk_size / limit / split
80  // / max_size / max_split / max_duration / min_space
81 
82  publishIsRecording(true);
83 
84  // launch rosbag-record. this thread will continue unless ros::shutdown() has been called
85  ROS_INFO("Start recording");
86  recorder.reset(new rosbag::Recorder(options));
87  run_thread = boost::thread(&rosbag::Recorder::run, recorder.get());
88 
89  return true;
90 }
91 
93  ros::Duration(0.5).sleep();
94  ros::shutdown();
95 }
96 
97 bool stop(std_srvs::Empty::Request &, std_srvs::Empty::Response &) {
98  // do nothing if recording never started
99  if (!recorder && !run_thread.joinable()) {
100  ROS_ERROR("Never started");
101  return false;
102  }
103 
104  // do nothing if the shutdown already scheduled
105  if (shutdown_thread.joinable()) {
106  ROS_ERROR("Already stopped");
107  return false;
108  }
109 
110  publishIsRecording(false);
111 
112  // schedule a future call of ros::shutdown()
113  // (because a direct call disconnects the current client)
114  ROS_INFO("Stop recording");
115  shutdown_thread = boost::thread(&sleepAndShutdown);
116 
117  return true;
118 }
119 
120 int main(int argc, char *argv[]) {
121  ros::init(argc, argv, "remote_rosbag_record");
122  ros::NodeHandle nh;
123 
124  // rosbag will use the global queue.
125  // to avoid confriction, use local queue for following services
126  ros::CallbackQueue queue;
127  nh.setCallbackQueue(&queue);
128 
129  is_recording_publisher = nh.advertise< std_msgs::Bool >("is_recording", 1, true);
130  publishIsRecording(false);
131  ros::ServiceServer start_server(nh.advertiseService("start", start));
132  ros::ServiceServer stop_server(nh.advertiseService("stop", stop));
133 
134  // run services. this serving will continue unless ros::shutdown() has been called
136  spinner.spin(&queue);
137 
138  // finalize the rosbag-record threads
139  if (run_thread.joinable()) {
140  run_thread.join();
141  }
142  if (shutdown_thread.joinable()) {
143  shutdown_thread.join();
144  }
145 
146  // manually free the recorder here.
147  // the recorder contains a plugin loaded by class_loader so must be freed
148  // before static variables in class_loader library (or get an exception).
149  // these static variables will be destroyed before the gloval variable recorder
150  // because they are allocated when the recorder is allocated in start().
151  recorder.reset();
152 
153  return 0;
154 }
boost::thread run_thread
Definition: record.cpp:19
bool stop(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: record.cpp:97
virtual void spin(CallbackQueue *queue=0)
void publish(const boost::shared_ptr< M > &message) const
boost::thread shutdown_thread
Definition: record.cpp:20
bool start(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: record.cpp:29
void sleepAndShutdown()
Definition: record.cpp:92
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::regex exclude_regex
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int main(int argc, char *argv[])
Definition: record.cpp:120
void publishIsRecording(const bool is_recording)
Definition: record.cpp:23
#define ROS_INFO(...)
void setCallbackQueue(CallbackQueueInterface *queue)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher is_recording_publisher
Definition: record.cpp:21
#define ROS_WARN_STREAM(args)
ROSCPP_DECL void shutdown()
CompressionType compression
boost::scoped_ptr< rosbag::Recorder > recorder
Definition: record.cpp:18
std::vector< std::string > topics
#define ROS_ERROR(...)


remote_rosbag_record
Author(s):
autogenerated on Wed Jan 27 2021 03:18:31