31 #include <geometry_msgs/Twist.h>
32 #include <geometry_msgs/PoseWithCovarianceStamped.h>
33 #include <nav_msgs/Odometry.h>
60 void cbTwist(
const geometry_msgs::Twist::ConstPtr& msg)
65 void cbInit(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
67 geometry_msgs::PoseStamped pose_in, pose_out;
68 pose_in.header =
msg->header;
69 pose_in.pose =
msg->pose.pose;
72 geometry_msgs::TransformStamped trans =
82 x_ = pose_out.pose.position.x;
83 y_ = pose_out.pose.position.y;
108 const float dt = 0.01;
121 geometry_msgs::TransformStamped trans;
122 trans.header.stamp = current_time;
123 trans.header.frame_id =
"odom";
124 trans.child_frame_id =
"base_link";
125 trans.transform.translation =
tf2::toMsg(tf2::Vector3(
x_,
y_, 0.0));
129 nav_msgs::Odometry odom;
130 odom.header.frame_id =
"odom";
131 odom.header.stamp = current_time;
132 odom.child_frame_id =
"base_link";
133 odom.pose.pose.position.x =
x_;
134 odom.pose.pose.position.y =
y_;
136 odom.twist.twist.linear.x =
v_;
137 odom.twist.twist.angular.z =
w_;
143 int main(
int argc,
char* argv[])