4 #include <geometry_msgs/TransformStamped.h>
5 #include <turtlesim/Pose.h>
13 geometry_msgs::TransformStamped transformStamped;
16 transformStamped.header.frame_id =
"world";
18 transformStamped.transform.translation.x =
msg->x;
19 transformStamped.transform.translation.y =
msg->y;
20 transformStamped.transform.translation.z = 0.0;
23 transformStamped.transform.rotation.x = q.x();
24 transformStamped.transform.rotation.y = q.y();
25 transformStamped.transform.rotation.z = q.z();
26 transformStamped.transform.rotation.w = q.w();
28 br.sendTransform(transformStamped);
31 int main(
int argc,
char** argv){
32 ros::init(argc, argv,
"my_tf2_broadcaster");
35 if (! private_node.
hasParam(
"turtle"))
37 if (argc != 2){
ROS_ERROR(
"need turtle name as argument");
return -1;};