src
turtle_tf_broadcaster.cpp
Go to the documentation of this file.
1
#include <
ros/ros.h
>
2
#include <
tf/transform_broadcaster.h
>
3
#include <turtlesim/Pose.h>
4
5
std::string
turtle_name
;
6
7
void
poseCallback
(
const
turtlesim::PoseConstPtr&
msg
){
8
static
tf::TransformBroadcaster
br
;
9
tf::Transform
transform;
10
transform.
setOrigin
( tf::Vector3(
msg
->x,
msg
->y, 0.0) );
11
tf::Quaternion
q;
12
q.
setRPY
(0, 0,
msg
->theta);
13
transform.
setRotation
(q);
14
br
.sendTransform(
tf::StampedTransform
(transform,
ros::Time::now
(),
"world"
,
turtle_name
));
15
}
16
17
int
main
(
int
argc,
char
** argv){
18
ros::init
(argc, argv,
"my_tf_broadcaster"
);
19
if
(argc != 2){
ROS_ERROR
(
"need turtle name as argument"
);
return
-1;};
20
turtle_name
= argv[1];
21
22
ros::NodeHandle
node;
23
ros::Subscriber
sub = node.
subscribe
(
turtle_name
+
"/pose"
, 10, &
poseCallback
);
24
25
ros::spin
();
26
return
0;
27
}
turtle_name
std::string turtle_name
Definition:
turtle_tf_broadcaster.cpp:5
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
ros.h
tf::StampedTransform
transform_broadcaster.h
turtle_tf_listener.msg
msg
Definition:
turtle_tf_listener.py:61
tf::Transform::setRotation
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
tf::TransformBroadcaster
poseCallback
void poseCallback(const turtlesim::PoseConstPtr &msg)
Definition:
turtle_tf_broadcaster.cpp:7
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf::Transform
tf::Transform::setOrigin
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
ROS_ERROR
#define ROS_ERROR(...)
main
int main(int argc, char **argv)
Definition:
turtle_tf_broadcaster.cpp:17
ros::spin
ROSCPP_DECL void spin()
dynamic_tf_broadcaster.br
br
Definition:
dynamic_tf_broadcaster.py:41
tf::Quaternion
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()
turtle_tf
Author(s): James Bowman, Isaac Saito
autogenerated on Sun Apr 13 2025 02:34:12