$search
00001 /* -*- mode: C++ -*- 00002 * 00003 * Copyright (C) 2009 Austin Robot Technology 00004 * License: Modified BSD Software License Agreement 00005 * 00006 * $Id: frames.h 1774 2011-09-10 19:23:37Z austinrobot $ 00007 */ 00008 00019 #ifndef _FRAMES_H_ 00020 #define _FRAMES_H_ 00021 00022 #include <string> 00023 #include <ros/ros.h> 00024 #include <tf/tf.h> 00025 00026 namespace ArtFrames 00027 { 00029 const std::string earth = "earth"; 00030 00032 const std::string odom = "odom"; 00033 00035 const std::string vehicle = "vehicle"; 00036 00038 const std::string velodyne = "velodyne"; 00039 const std::string front_sick = "front_sick"; 00040 const std::string rear_sick = "rear_sick"; 00041 00043 const std::string center_front_camera = "center_front_camera"; 00044 const std::string center_front_camera_optical = "center_front_camera_optical"; 00045 const std::string left_front_camera = "left_front_camera"; 00046 const std::string left_front_camera_optical = "left_front_camera_optical"; 00047 const std::string right_front_camera = "right_front_camera"; 00048 const std::string right_front_camera_optical = "right_front_camera_optical"; 00049 00050 class VehicleRelative 00051 { 00052 public: 00053 VehicleRelative() {}; 00054 00056 void getPrefixParam(void) 00057 { 00058 ros::NodeHandle private_nh("~"); 00059 std::string prefix_param; 00060 if (private_nh.searchParam("tf_prefix", prefix_param)) 00061 { 00062 private_nh.getParam(prefix_param, prefix_); 00063 ROS_INFO_STREAM("vehicle-relative transform prefix: " << prefix_); 00064 } 00065 } 00066 00072 inline std::string getFrame(std::string relframe) 00073 { 00074 return tf::resolve(prefix_, relframe); 00075 } 00076 00077 private: 00078 std::string prefix_; 00079 }; 00080 }; 00081 00082 #endif // _FRAMES_H_