Go to the documentation of this file.00001
00006 #ifndef POSE_H
00007 #define POSE_H
00008
00009 #include <ros/ros.h>
00010 #include <tf/transform_broadcaster.h>
00011 #include <nav_msgs/Odometry.h>
00012
00013 using namespace std;
00014
00015 namespace slam
00016 {
00017
00018 class Pose
00019 {
00020
00021 public:
00022
00023
00024 Pose();
00025
00026 struct Params
00027 {
00028 string pose_frame_id;
00029 string pose_child_frame_id;
00030
00031
00032 Params () {
00033 pose_frame_id = "/map";
00034 pose_child_frame_id = "/robot";
00035 }
00036 };
00037
00041 inline void setParams(const Params& params)
00042 {
00043 params_ = params;
00044 }
00045
00049 inline Params params() const { return params_; }
00050
00051
00052 void advertisePoseMsg(ros::NodeHandle nh);
00053
00054
00055 tf::Transform correctOdom(tf::Transform current_odom, tf::Transform last_graph_pose, tf::Transform last_graph_odom);
00056
00057
00058 void publish(nav_msgs::Odometry odom_msg, tf::Transform pose, bool publish_graph);
00059
00060 private:
00061
00062
00063 Params params_;
00064
00065
00066 ros::Publisher pose_pub_;
00067 ros::Publisher graph_pub_;
00068
00069 };
00070
00071 }
00072
00073 #endif // POSE_H