37 #include <std_msgs/Int32.h> 39 #include <boost/foreach.hpp> 50 int main(
int argc,
char *argv[])
52 ros::init(argc, argv,
"rosbag_trajectory_combiner");
54 std::string name =
"/home/winklera/bags/optimal_traj";
62 int n_opt_iterations = 0;
65 std_msgs::Int32::ConstPtr i = m.
instantiate<std_msgs::Int32>();
66 n_opt_iterations = i->data;
70 std::vector<std::string> topics;
71 ROS_INFO_STREAM(
"Detected " + std::to_string(n_opt_iterations) +
" iterations");
72 int n_visualizations = 5;
73 int frequency = std::floor(n_opt_iterations/n_visualizations);
75 for (
int i=0; i<n_visualizations; ++i)
82 std::map<std::string, double> t_iter;
84 for (
int i=0; i<topics.size(); ++i)
85 t_iter[topics.at(i)] = i*duration;
89 std::cout << m.first << std::endl;
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")
ros::Time const & getTime() const
boost::shared_ptr< T > instantiate() const
#define ROS_INFO_STREAM(args)
std::string const & getTopic() const
void write(std::string const &topic, ros::MessageEvent< T > const &event)