12 #include <std_msgs/Bool.h> 13 #include <std_srvs/Empty.h> 15 #include <boost/scoped_ptr.hpp> 16 #include <boost/thread/thread.hpp> 18 boost::scoped_ptr< rosbag::Recorder >
recorder;
24 std_msgs::BoolPtr msg(
new std_msgs::Bool());
25 msg->data = is_recording;
26 is_recording_publisher.
publish(msg);
29 bool start(std_srvs::Empty::Request &, std_srvs::Empty::Response &) {
41 rp::get(
"~regex", options.
regex);
42 rp::get(
"~quiet", options.
quiet);
45 rp::get(
"~verbose", options.
verbose);
47 std::string compression;
48 if (rp::get(
"~compression", compression)) {
49 if (compression ==
"uncompressed") {
51 }
else if (compression ==
"bz2") {
53 }
else if (compression ==
"lz4") {
60 rp::get(
"~prefix", options.
prefix);
61 rp::get(
"~name", options.
name);
62 rp::get(
"~topics", options.
topics);
64 std::string exclude_regex;
65 if (rp::get(
"~exclude_regex", exclude_regex)) {
72 if (rp::get(
"~buffer_size", buffer_size)) {
76 rp::get(
"~node", options.
node);
97 bool stop(std_srvs::Empty::Request &, std_srvs::Empty::Response &) {
120 int main(
int argc,
char *argv[]) {
121 ros::init(argc, argv,
"remote_rosbag_record");
129 is_recording_publisher = nh.
advertise< std_msgs::Bool >(
"is_recording", 1,
true);
136 spinner.
spin(&queue);
bool stop(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
virtual void spin(CallbackQueue *queue=0)
void publish(const boost::shared_ptr< M > &message) const
boost::thread shutdown_thread
bool start(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
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[])
void publishIsRecording(const bool is_recording)
void setCallbackQueue(CallbackQueueInterface *queue)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher is_recording_publisher
#define ROS_WARN_STREAM(args)
ROSCPP_DECL void shutdown()
CompressionType compression
boost::scoped_ptr< rosbag::Recorder > recorder
std::vector< std::string > topics