26 geometry_msgs::PointStamped point_out;
31 printf(
"point of turtle 3 in frame of turtle 1 Position(x:%f y:%f z:%f)\n",
38 printf (
"Failure %s\n", ex.what());
45 int main(
int argc,
char ** argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
void msgCallback(const boost::shared_ptr< const geometry_msgs::PointStamped > &point_ptr)
int main(int argc, char **argv)
std::string target_frame_
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)