2 #include "geometry_msgs/PointStamped.h" 21 void msgCallback(
const geometry_msgs::PointStampedConstPtr& point_ptr)
23 geometry_msgs::PointStamped point_out;
28 ROS_INFO(
"point of turtle 3 in frame of turtle 1 Position(x:%f y:%f z:%f)\n",
50 int main(
int argc,
char ** argv)
tf2_ros::TransformListener tf2_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
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)