tf_listener.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #include <ros/ros.h>
38 #include <geometry_msgs/PointStamped.h>
39 #include <tf/transform_listener.h>
40 
41 void transformPoint(const tf::TransformListener& listener){
42  //we'll create a point in the base_laser frame that we'd like to transform to the base_link frame
43  geometry_msgs::PointStamped laser_point;
44  laser_point.header.frame_id = "base_laser";
45 
46  //we'll just use the most recent transform available for our simple example
47  laser_point.header.stamp = ros::Time();
48 
49  //just an arbitrary point in space
50  laser_point.point.x = 1.0;
51  laser_point.point.y = 0.2;
52  laser_point.point.z = 0.0;
53 
54  try{
55  geometry_msgs::PointStamped base_point;
56  listener.transformPoint("base_link", laser_point, base_point);
57 
58  ROS_INFO("base_laser: (%.2f, %.2f. %.2f) -----> base_link: (%.2f, %.2f, %.2f) at time %.2f",
59  laser_point.point.x, laser_point.point.y, laser_point.point.z,
60  base_point.point.x, base_point.point.y, base_point.point.z, base_point.header.stamp.toSec());
61  }
62  catch(tf::TransformException& ex){
63  ROS_ERROR("Received an exception trying to transform a point from \"base_laser\" to \"base_link\": %s", ex.what());
64  }
65 }
66 
67 int main(int argc, char** argv){
68  ros::init(argc, argv, "robot_tf_listener");
70 
72 
73  //we'll transform a point once every second
74  ros::Timer timer = n.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));
75 
76  ros::spin();
77 
78 }
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
int main(int argc, char **argv)
Definition: tf_listener.cpp:67
ROSCPP_DECL void spin(Spinner &spinner)
void transformPoint(const tf::TransformListener &listener)
Definition: tf_listener.cpp:41
#define ROS_INFO(...)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
#define ROS_ERROR(...)


robot_setup_tf_tutorial
Author(s): Eitan Marder-Eppstein
autogenerated on Sun Jul 12 2020 03:52:54