trajectory_saver.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, ATR, Atsushi Watanabe
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * This research was supported by a contract with the Ministry of Internal
32  Affairs and Communications entitled, 'Novel and innovative R&D making use
33  of brain structures'
34 
35  This software was implemented to accomplish the above research.
36  */
37 
38 #include <ros/ros.h>
39 
40 #include <geometry_msgs/Twist.h>
41 #include <nav_msgs/Path.h>
42 
43 #include <math.h>
44 #include <fstream>
45 #include <string>
46 
48 
49 class SaverNode
50 {
51 public:
52  SaverNode();
53  ~SaverNode();
54  void save();
55 
56 private:
60 
61  std::string topic_path_;
62  std::string filename_;
63  bool saved_;
64  void cbPath(const nav_msgs::Path::ConstPtr& msg);
65 };
66 
68  : nh_()
69  , pnh_("~")
70  , saved_(false)
71 {
73  neonavigation_common::compat::deprecatedParam(pnh_, "path", topic_path_, std::string("recpath"));
74  pnh_.param("file", filename_, std::string("a.path"));
75 
77  nh_, "path",
78  pnh_, topic_path_, 10, &SaverNode::cbPath, this);
79 }
81 {
82 }
83 
84 void SaverNode::cbPath(const nav_msgs::Path::ConstPtr& msg)
85 {
86  if (saved_)
87  return;
88  std::ofstream ofs(filename_.c_str());
89 
90  if (!ofs)
91  {
92  ROS_ERROR("Failed to open %s", filename_.c_str());
93  return;
94  }
95 
96  uint32_t serial_size = ros::serialization::serializationLength(*msg);
97  ROS_INFO("Size: %d\n", (int)serial_size);
98  boost::shared_array<uint8_t> buffer(new uint8_t[serial_size]);
99 
100  ros::serialization::OStream stream(buffer.get(), serial_size);
101  ros::serialization::serialize(stream, *msg);
102 
103  ofs.write(reinterpret_cast<char*>(buffer.get()), serial_size);
104 
105  saved_ = true;
106 }
107 
109 {
110  ros::Rate loop_rate(5);
111  ROS_INFO("Waiting for the path");
112 
113  while (ros::ok())
114  {
115  ros::spinOnce();
116  loop_rate.sleep();
117  if (saved_)
118  break;
119  }
120  ROS_INFO("Path saved");
121 }
122 
123 int main(int argc, char** argv)
124 {
125  ros::init(argc, argv, "trajectory_saver");
126 
127  SaverNode rec;
128  rec.save();
129 
130  return 0;
131 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber sub_path_
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
ros::NodeHandle pnh_
int main(int argc, char **argv)
ros::NodeHandle nh_
void serialize(Stream &stream, const T &t)
std::string filename_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
std::string topic_path_
void cbPath(const nav_msgs::Path::ConstPtr &msg)
bool sleep()
uint32_t serializationLength(const T &t)
ROSCPP_DECL void spinOnce()
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T &param, const T &default_value)
#define ROS_ERROR(...)


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:09