turtle_tf_broadcaster.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <turtlesim/Pose.h>
4 
5 std::string turtle_name;
6 
7 void poseCallback(const turtlesim::PoseConstPtr& msg){
9  tf::Transform transform;
10  transform.setOrigin( tf::Vector3(msg->x, msg->y, 0.0) );
12  q.setRPY(0, 0, msg->theta);
13  transform.setRotation(q);
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 }
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string turtle_name
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
void poseCallback(const turtlesim::PoseConstPtr &msg)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
void sendTransform(const StampedTransform &transform)
static Time now()
int main(int argc, char **argv)
#define ROS_ERROR(...)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)


turtle_tf
Author(s): James Bowman, Isaac Saito
autogenerated on Wed Jun 5 2019 20:50:39