message_filter.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "geometry_msgs/PointStamped.h"
3 
8 
9 class PoseDrawer
10 {
11 public:
13  tf2_(buffer_), target_frame_("turtle1"),
15  {
16  point_sub_.subscribe(n_, "turtle_point_stamped", 10);
17  tf2_filter_.registerCallback( boost::bind(&PoseDrawer::msgCallback, this, _1) );
18  }
19 
20  // Callback to register with tf2_ros::MessageFilter to be called when transforms are available
21  void msgCallback(const geometry_msgs::PointStampedConstPtr& point_ptr)
22  {
23  geometry_msgs::PointStamped point_out;
24  try
25  {
26  buffer_.transform(*point_ptr, point_out, target_frame_);
27 
28  ROS_INFO("point of turtle 3 in frame of turtle 1 Position(x:%f y:%f z:%f)\n",
29  point_out.point.x,
30  point_out.point.y,
31  point_out.point.z);
32  }
33  catch (tf2::TransformException &ex)
34  {
35  ROS_WARN("Failure %s\n", ex.what()); //Print exception which was caught
36  }
37  }
38 
39 private:
40  std::string target_frame_;
46 
47 };
48 
49 
50 int main(int argc, char ** argv)
51 {
52  ros::init(argc, argv, "pose_drawer"); //Init ROS
53  PoseDrawer pd; //Construct class
54  ros::spin(); // Run until interupted
55  return 0;
56 };
57 
tf2_ros::TransformListener tf2_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
tf2_ros::Buffer buffer_
ROSCPP_DECL void spin(Spinner &spinner)
ros::NodeHandle n_
#define ROS_INFO(...)
std::string target_frame_
void msgCallback(const geometry_msgs::PointStampedConstPtr &point_ptr)
tf2_ros::MessageFilter< geometry_msgs::PointStamped > tf2_filter_
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_
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
int main(int argc, char **argv)
Connection registerCallback(const C &callback)


turtle_tf2
Author(s): Denis Štogl
autogenerated on Mon Jun 10 2019 13:24:50