00001
00002
00003
00004
00005
00006
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 left_front_camera = "left_front_camera";
00044 const std::string left_front_camera_optical = "left_front_camera_optical";
00045 const std::string right_front_camera = "right_front_camera";
00046 const std::string right_front_camera_optical = "right_front_camera_optical";
00047
00048 class VehicleRelative
00049 {
00050 public:
00051 VehicleRelative() {};
00052
00054 void getPrefixParam(void)
00055 {
00056 ros::NodeHandle private_nh("~");
00057 std::string prefix_param;
00058 if (private_nh.searchParam("tf_prefix", prefix_param))
00059 {
00060 private_nh.getParam(prefix_param, prefix_);
00061 ROS_INFO_STREAM("vehicle-relative transform prefix: " << prefix_);
00062 }
00063 }
00064
00070 inline std::string getFrame(std::string relframe)
00071 {
00072 return tf::resolve(prefix_, relframe);
00073 }
00074
00075 private:
00076 std::string prefix_;
00077 };
00078 };
00079
00080 #endif // _FRAMES_H_