rosbag_traj_combiner.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #include <iostream>
31 #include <string>
32 #include <vector>
33 
34 #include <ros/init.h>
35 #include <rosbag/bag.h>
36 #include <rosbag/view.h>
37 #include <std_msgs/Int32.h>
39 #include <boost/foreach.hpp>
40 
41 #include <xpp_msgs/topic_names.h>
42 #include <towr_ros/topic_names.h>
43 
50 int main(int argc, char *argv[])
51 {
52  ros::init(argc, argv, "rosbag_trajectory_combiner");
53 
54  std::string name = "/home/winklera/bags/optimal_traj";
55 
56  rosbag::Bag bag_r;
57  bag_r.open(name+".bag", rosbag::bagmode::Read);
58  ROS_INFO_STREAM("Reading from bag " + bag_r.getFileName());
59 
60 
61  // get number of iterations in bag file
62  int n_opt_iterations = 0;
64  BOOST_FOREACH(rosbag::MessageInstance const m, view1) {
65  std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
66  n_opt_iterations = i->data;
67  }
68 
69  // select which iterations (message topics) to be included in bag file
70  std::vector<std::string> topics;
71  ROS_INFO_STREAM("Detected " + std::to_string(n_opt_iterations) + " iterations");
72  int n_visualizations = 5; // total number of visualizations is fixed
73  int frequency = std::floor(n_opt_iterations/n_visualizations);
74 
75  for (int i=0; i<n_visualizations; ++i)
76  topics.push_back(towr_msgs::nlp_iterations_name + std::to_string(frequency*i));
77  topics.push_back(towr_msgs::nlp_iterations_name + std::to_string(n_opt_iterations-1)); // for sure add final trajectory
78  rosbag::View view(bag_r, rosbag::TopicQuery(topics));
79 
80 
81  // change the timestamp so iterations are played back subsequently
82  std::map<std::string, double> t_iter;
83  double duration = view.getEndTime().toSec(); // duration of the trajectory
84  for (int i=0; i<topics.size(); ++i)
85  t_iter[topics.at(i)] = i*duration;
86 
87  ROS_INFO_STREAM("Visualizing messages:");
88  for (auto m : t_iter)
89  std::cout << m.first << std::endl;
90 
91 
92  // write the message with modified timestamp into new bag file
93  rosbag::Bag bag_w;
94  bag_w.open(name + "_combined.bag", rosbag::bagmode::Write);
95 
96  BOOST_FOREACH(rosbag::MessageInstance const m, view)
97  {
98  double t_global = t_iter.at(m.getTopic()) + m.getTime().toSec();
99  bag_w.write(xpp_msgs::robot_state_desired, ::ros::Time(t_global), m);
100  }
101 
102  bag_r.close();
103  bag_w.close();
104  ROS_INFO_STREAM("Successfully created bag " + bag_w.getFileName());
105 
106  return 1;
107 }
void open(std::string const &filename, uint32_t mode=bagmode::Read)
static const std::string robot_state_desired("/xpp/state_des")
std::string getFileName() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static const std::string nlp_iterations_count("/towr/nlp_iterations_count")
int main(int argc, char *argv[])
static const std::string nlp_iterations_name("/towr/nlp_iterations_name")
void close()
ros::Time const & getTime() const
boost::shared_ptr< T > instantiate() const
ros::Time getEndTime()
#define ROS_INFO_STREAM(args)
std::string const & getTopic() const
void write(std::string const &topic, ros::MessageEvent< T > const &event)


towr_ros
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:21