turtle_tf_message_filter.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
3 #include "tf/message_filter.h"
5 
6 class PoseDrawer
7 {
8 public:
9  PoseDrawer() : tf_(), target_frame_("turtle1")
10  {
11  point_sub_.subscribe(n_, "turtle_point_stamped", 10);
13  tf_filter_->registerCallback( boost::bind(&PoseDrawer::msgCallback, this, _1) );
14  } ;
15 
16 private:
21  std::string target_frame_;
22 
23  // Callback to register with tf::MessageFilter to be called when transforms are available
25  {
26  geometry_msgs::PointStamped point_out;
27  try
28  {
29  tf_.transformPoint(target_frame_, *point_ptr, point_out);
30 
31  printf("point of turtle 3 in frame of turtle 1 Position(x:%f y:%f z:%f)\n",
32  point_out.point.x,
33  point_out.point.y,
34  point_out.point.z);
35  }
36  catch (tf::TransformException &ex)
37  {
38  printf ("Failure %s\n", ex.what()); //Print exception which was caught
39  }
40  };
41 
42 };
43 
44 
45 int main(int argc, char ** argv)
46 {
47  ros::init(argc, argv, "pose_drawer"); //Init ROS
48  PoseDrawer pd; //Construct class
49  ros::spin(); // Run until interupted
50 };
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
ROSCPP_DECL void spin(Spinner &spinner)
void msgCallback(const boost::shared_ptr< const geometry_msgs::PointStamped > &point_ptr)
ros::NodeHandle n_
int main(int argc, char **argv)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< geometry_msgs::PointStamped > point_sub_
tf::TransformListener tf_
tf::MessageFilter< geometry_msgs::PointStamped > * tf_filter_
Connection registerCallback(const C &callback)


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