Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #ifndef FLIRTLIB_ROS_COMMON_H
00040 #define FLIRTLIB_ROS_COMMON_H
00041
00042 #include <tf/transform_listener.h>
00043 #include <flirtlib_ros/flirtlib.h>
00044
00045 namespace flirtlib_ros
00046 {
00047
00048 namespace gm=geometry_msgs;
00049
00051 inline
00052 gm::Pose tfTransformToPose (const tf::Transform& trans)
00053 {
00054 gm::Pose m;
00055 tf::poseTFToMsg(trans, m);
00056 return m;
00057 }
00058
00060 inline
00061 tf::Pose poseMsgToTf (const gm::Pose& p)
00062 {
00063 const gm::Quaternion& q = p.orientation;
00064 const gm::Point& v = p.position;
00065 return tf::Pose(tf::Quaternion(q.x, q.y, q.z, q.w),
00066 tf::Vector3(v.x, v.y, v.z));
00067 }
00068
00069
00073 template <typename T>
00074 T getPrivateParam (const std::string& name, const T& default_val)
00075 {
00076 ros::NodeHandle nh("~");
00077 T val;
00078 nh.param(name, val, default_val);
00079 ROS_DEBUG_STREAM_NAMED ("init", "Initialized " << name << " to " << val <<
00080 "(default was " << default_val << ")");
00081 return val;
00082 }
00083
00084
00085
00088 gm::Pose getCurrentPose (const tf::TransformListener& tf,
00089 const std::string& frame);
00090
00092 gm::Pose transformPose (const gm::Pose& p, const OrientedPoint2D& trans);
00093
00095 gm::Pose transformPose (const tf::Transform& trans, const gm::Pose& pose);
00096
00098 gm::Pose makePose (double x, double y, double theta);
00099
00101 tf::Transform getLaserOffset (const tf::TransformListener& tf);
00102
00103 }
00104
00105 #endif // include guard