22 #include <geometry_msgs/PoseStamped.h> 23 #include <geometry_msgs/PoseWithCovarianceStamped.h> 24 #include <geometry_msgs/TransformStamped.h> 25 #include <nav_msgs/Odometry.h> 31 int main(
int argc,
char **argv) {
38 std::string verbosity;
39 nh.
param<std::string>(
"verbosity", verbosity,
"INFO");
43 std::string topic, topic_type, fileoutput;
45 nh.
getParam(
"topic_type", topic_type);
51 PRINT_DEBUG(
" - topic_type = %s", topic_type.c_str());
59 if (topic_type == std::string(
"PoseWithCovarianceStamped")) {
61 }
else if (topic_type == std::string(
"PoseStamped")) {
63 }
else if (topic_type == std::string(
"TransformStamped")) {
65 }
else if (topic_type == std::string(
"Odometry")) {
68 PRINT_ERROR(
"The specified topic type is not supported");
70 PRINT_ERROR(
"please select from: PoseWithCovarianceStamped, PoseStamped, TransformStamped, Odometry");
71 std::exit(EXIT_FAILURE);
void callback_posecovariance(const geometry_msgs::PoseWithCovarianceStampedPtr &msg)
Callback for geometry_msgs::PoseWithCovarianceStamped message types.
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.
void callback_odometry(const nav_msgs::OdometryPtr &msg)
Callback for nav_msgs::Odometry message types.
void callback_pose(const geometry_msgs::PoseStampedPtr &msg)
Callback for geometry_msgs::PoseStamped message types.
void callback_transform(const geometry_msgs::TransformStampedPtr &msg)
Callback for geometry_msgs::TransformStamped message types.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getParam(const std::string &key, std::string &s) const
static void setPrintLevel(const std::string &level)
#define PRINT_ERROR(x...)
#define PRINT_DEBUG(x...)
int main(int argc, char **argv)