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 #include <iostream>
00031 #include <string>
00032 #include <vector>
00033
00034 #include <ros/init.h>
00035 #include <rosbag/bag.h>
00036 #include <rosbag/view.h>
00037 #include <std_msgs/Int32.h>
00038 #include <rosbag/message_instance.h>
00039 #include <boost/foreach.hpp>
00040
00041 #include <xpp_msgs/topic_names.h>
00042 #include <towr_ros/topic_names.h>
00043
00050 int main(int argc, char *argv[])
00051 {
00052 ros::init(argc, argv, "rosbag_trajectory_combiner");
00053
00054 std::string name = "/home/winklera/bags/optimal_traj";
00055
00056 rosbag::Bag bag_r;
00057 bag_r.open(name+".bag", rosbag::bagmode::Read);
00058 ROS_INFO_STREAM("Reading from bag " + bag_r.getFileName());
00059
00060
00061
00062 int n_opt_iterations = 0;
00063 rosbag::View view1(bag_r, rosbag::TopicQuery(towr_msgs::nlp_iterations_count));
00064 BOOST_FOREACH(rosbag::MessageInstance const m, view1) {
00065 std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
00066 n_opt_iterations = i->data;
00067 }
00068
00069
00070 std::vector<std::string> topics;
00071 ROS_INFO_STREAM("Detected " + std::to_string(n_opt_iterations) + " iterations");
00072 int n_visualizations = 5;
00073 int frequency = std::floor(n_opt_iterations/n_visualizations);
00074
00075 for (int i=0; i<n_visualizations; ++i)
00076 topics.push_back(towr_msgs::nlp_iterations_name + std::to_string(frequency*i));
00077 topics.push_back(towr_msgs::nlp_iterations_name + std::to_string(n_opt_iterations-1));
00078 rosbag::View view(bag_r, rosbag::TopicQuery(topics));
00079
00080
00081
00082 std::map<std::string, double> t_iter;
00083 double duration = view.getEndTime().toSec();
00084 for (int i=0; i<topics.size(); ++i)
00085 t_iter[topics.at(i)] = i*duration;
00086
00087 ROS_INFO_STREAM("Visualizing messages:");
00088 for (auto m : t_iter)
00089 std::cout << m.first << std::endl;
00090
00091
00092
00093 rosbag::Bag bag_w;
00094 bag_w.open(name + "_combined.bag", rosbag::bagmode::Write);
00095
00096 BOOST_FOREACH(rosbag::MessageInstance const m, view)
00097 {
00098 double t_global = t_iter.at(m.getTopic()) + m.getTime().toSec();
00099 bag_w.write(xpp_msgs::robot_state_desired, ::ros::Time(t_global), m);
00100 }
00101
00102 bag_r.close();
00103 bag_w.close();
00104 ROS_INFO_STREAM("Successfully created bag " + bag_w.getFileName());
00105
00106 return 1;
00107 }