Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039
00040 #include <geometry_msgs/Twist.h>
00041 #include <nav_msgs/Path.h>
00042
00043 #include <math.h>
00044 #include <fstream>
00045 #include <string>
00046
00047 #include <neonavigation_common/compatibility.h>
00048
00049 class SaverNode
00050 {
00051 public:
00052 SaverNode();
00053 ~SaverNode();
00054 void save();
00055
00056 private:
00057 ros::NodeHandle nh_;
00058 ros::NodeHandle pnh_;
00059 ros::Subscriber sub_path_;
00060
00061 std::string topic_path_;
00062 std::string filename_;
00063 bool saved_;
00064 void cbPath(const nav_msgs::Path::ConstPtr& msg);
00065 };
00066
00067 SaverNode::SaverNode()
00068 : nh_()
00069 , pnh_("~")
00070 , saved_(false)
00071 {
00072 neonavigation_common::compat::checkCompatMode();
00073 neonavigation_common::compat::deprecatedParam(pnh_, "path", topic_path_, std::string("recpath"));
00074 pnh_.param("file", filename_, std::string("a.path"));
00075
00076 sub_path_ = neonavigation_common::compat::subscribe(
00077 nh_, "path",
00078 pnh_, topic_path_, 10, &SaverNode::cbPath, this);
00079 }
00080 SaverNode::~SaverNode()
00081 {
00082 }
00083
00084 void SaverNode::cbPath(const nav_msgs::Path::ConstPtr& msg)
00085 {
00086 if (saved_)
00087 return;
00088 std::ofstream ofs(filename_.c_str());
00089
00090 if (!ofs)
00091 {
00092 ROS_ERROR("Failed to open %s", filename_.c_str());
00093 return;
00094 }
00095
00096 uint32_t serial_size = ros::serialization::serializationLength(*msg);
00097 ROS_INFO("Size: %d\n", (int)serial_size);
00098 boost::shared_array<uint8_t> buffer(new uint8_t[serial_size]);
00099
00100 ros::serialization::OStream stream(buffer.get(), serial_size);
00101 ros::serialization::serialize(stream, *msg);
00102
00103 ofs.write(reinterpret_cast<char*>(buffer.get()), serial_size);
00104
00105 saved_ = true;
00106 }
00107
00108 void SaverNode::save()
00109 {
00110 ros::Rate loop_rate(5);
00111 ROS_INFO("Waiting for the path");
00112
00113 while (ros::ok())
00114 {
00115 ros::spinOnce();
00116 loop_rate.sleep();
00117 if (saved_)
00118 break;
00119 }
00120 ROS_INFO("Path saved");
00121 }
00122
00123 int main(int argc, char** argv)
00124 {
00125 ros::init(argc, argv, "trajectory_saver");
00126
00127 SaverNode rec;
00128 rec.save();
00129
00130 return 0;
00131 }