38 #include <tf2/LinearMath/Quaternion.h>
39 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
40 #include <tf2/convert.h>
49 ROS_INFO_ONCE(
"odom received!");
53 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
54 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
55 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
56 base_odom_.child_frame_id = msg->child_frame_id;
70 geometry_msgs::Twist global_vel;
73 global_vel.linear.x =
base_odom_.twist.twist.linear.x;
74 global_vel.linear.y =
base_odom_.twist.twist.linear.y;
75 global_vel.angular.z =
base_odom_.twist.twist.angular.z;
77 robot_vel.header.frame_id =
base_odom_.child_frame_id;
79 robot_vel.pose.position.x = global_vel.linear.x;
80 robot_vel.pose.position.y = global_vel.linear.y;
81 robot_vel.pose.position.z = 0;
83 q.setRPY(0, 0, global_vel.angular.z);
84 tf2::convert(q, robot_vel.pose.orientation);
85 robot_vel.header.stamp = ros::Time();