38 #include <geometry_msgs/PointStamped.h> 43 geometry_msgs::PointStamped laser_point;
44 laser_point.header.frame_id =
"base_laser";
50 laser_point.point.x = 1.0;
51 laser_point.point.y = 0.2;
52 laser_point.point.z = 0.0;
55 geometry_msgs::PointStamped base_point;
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());
63 ROS_ERROR(
"Received an exception trying to transform a point from \"base_laser\" to \"base_link\": %s", ex.what());
67 int main(
int argc,
char** argv){
68 ros::init(argc, argv,
"robot_tf_listener");
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
void transformPoint(const tf::TransformListener &listener)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const