pose_to_file.cpp
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #include <geometry_msgs/PoseStamped.h>
23 #include <geometry_msgs/PoseWithCovarianceStamped.h>
24 #include <geometry_msgs/TransformStamped.h>
25 #include <nav_msgs/Odometry.h>
26 #include <ros/ros.h>
27 
28 #include "utils/Recorder.h"
29 #include "utils/print.h"
30 
31 int main(int argc, char **argv) {
32 
33  // Create ros node
34  ros::init(argc, argv, "pose_to_file");
35  ros::NodeHandle nh("~");
36 
37  // Verbosity setting
38  std::string verbosity;
39  nh.param<std::string>("verbosity", verbosity, "INFO");
41 
42  // Get parameters to subscribe
43  std::string topic, topic_type, fileoutput;
44  nh.getParam("topic", topic);
45  nh.getParam("topic_type", topic_type);
46  nh.getParam("output", fileoutput);
47 
48  // Debug
49  PRINT_DEBUG("Done reading config values");
50  PRINT_DEBUG(" - topic = %s", topic.c_str());
51  PRINT_DEBUG(" - topic_type = %s", topic_type.c_str());
52  PRINT_DEBUG(" - file = %s", fileoutput.c_str());
53 
54  // Create the recorder object
55  ov_eval::Recorder recorder(fileoutput);
56 
57  // Subscribe to topic
58  ros::Subscriber sub;
59  if (topic_type == std::string("PoseWithCovarianceStamped")) {
60  sub = nh.subscribe(topic, 9999, &ov_eval::Recorder::callback_posecovariance, &recorder);
61  } else if (topic_type == std::string("PoseStamped")) {
62  sub = nh.subscribe(topic, 9999, &ov_eval::Recorder::callback_pose, &recorder);
63  } else if (topic_type == std::string("TransformStamped")) {
64  sub = nh.subscribe(topic, 9999, &ov_eval::Recorder::callback_transform, &recorder);
65  } else if (topic_type == std::string("Odometry")) {
66  sub = nh.subscribe(topic, 9999, &ov_eval::Recorder::callback_odometry, &recorder);
67  } else {
68  PRINT_ERROR("The specified topic type is not supported");
69  PRINT_ERROR("topic_type = %s", topic_type.c_str());
70  PRINT_ERROR("please select from: PoseWithCovarianceStamped, PoseStamped, TransformStamped, Odometry");
71  std::exit(EXIT_FAILURE);
72  }
73 
74  // Done!
75  ros::spin();
76  return EXIT_SUCCESS;
77 }
void callback_posecovariance(const geometry_msgs::PoseWithCovarianceStampedPtr &msg)
Callback for geometry_msgs::PoseWithCovarianceStamped message types.
Definition: Recorder.h:125
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
This class takes in published poses and writes them to file.
Definition: Recorder.h:47
void callback_odometry(const nav_msgs::OdometryPtr &msg)
Callback for nav_msgs::Odometry message types.
Definition: Recorder.h:92
void callback_pose(const geometry_msgs::PoseStampedPtr &msg)
Callback for geometry_msgs::PoseStamped message types.
Definition: Recorder.h:110
void callback_transform(const geometry_msgs::TransformStampedPtr &msg)
Callback for geometry_msgs::TransformStamped message types.
Definition: Recorder.h:143
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool getParam(const std::string &key, std::string &s) const
ROSCPP_DECL void spin()
static void setPrintLevel(const std::string &level)
int main(int argc, char **argv)


ov_eval
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Wed Jun 21 2023 03:05:40