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 GRAPH_MAPPING_UTILS_ROS_H
00040 #define GRAPH_MAPPING_UTILS_ROS_H
00041
00042 #include <ros/message_traits.h>
00043 #include <ros/ros.h>
00044 #include <tf/transform_listener.h>
00045 #include <tf/exceptions.h>
00046 #include <boost/type_traits/remove_const.hpp>
00047 #include <boost/optional.hpp>
00048
00049 namespace graph_mapping_utils
00050 {
00051
00052 namespace gm=geometry_msgs;
00053
00054 using std::string;
00055 using ros::Time;
00056
00058 template <class MsgPtr>
00059 ros::Time timestamp (const MsgPtr& data)
00060 {
00061 typedef typename MsgPtr::element_type Msg;
00062
00063
00064 typedef typename boost::remove_const<Msg>::type MsgWithoutConst;
00065
00066 return ros::message_traits::TimeStamp<MsgWithoutConst>::value(*data);
00067 }
00068
00069
00071 template <class P>
00072 P searchParam (const ros::NodeHandle& nh, const string& name)
00073 {
00074 string global_name;
00075 bool found = nh.searchParam(name, global_name);
00076 const string ns = nh.getNamespace();
00077 ROS_ASSERT_MSG (found, "Could not find %s in any parent of %s", name.c_str(), ns.c_str());
00078
00079 P val;
00080 nh.getParam(global_name, val);
00081 ROS_DEBUG_STREAM_NAMED ("init", "Searched upwards for " << name << " from " << ns <<
00082 "; found " << global_name << " = " << val);
00083 return val;
00084 }
00085
00087 template <class P>
00088 P searchParam (const ros::NodeHandle& nh, const string& name, const P& default_val)
00089 {
00090 string global_name;
00091 bool found = nh.searchParam(name, global_name);
00092 const string ns = nh.getNamespace();
00093 if (!found) {
00094 ROS_DEBUG_STREAM_NAMED ("init", "Using default value " << default_val << " for " << name);
00095 return default_val;
00096 }
00097 else {
00098 P val;
00099 nh.getParam(global_name, val);
00100 ROS_DEBUG_STREAM_NAMED ("init", "Searched upwards for " << name << " from " << ns <<
00101 "; found " << global_name << " = " << val);
00102 return val;
00103 }
00104 }
00105
00107 template <class P>
00108 P getParam (const ros::NodeHandle& nh, const string& name)
00109 {
00110 P val;
00111 bool found = nh.getParam(name, val);
00112 ROS_ASSERT_MSG (found, "Could not find parameter %s in %s",
00113 name.c_str(), nh.getNamespace().c_str());
00114 ROS_DEBUG_STREAM_NAMED ("init", "Initialized " << name << " to " << val);
00115 return val;
00116 }
00117
00118
00120 template <class P>
00121 P getParam (const ros::NodeHandle& nh, const string& name, const P& default_val)
00122 {
00123 P val;
00124 nh.param(name, val, default_val);
00125 ROS_DEBUG_STREAM_NAMED ("init", "Initialized " << name << " to " << val <<
00126 " (default was " << default_val << ")");
00127 return val;
00128 }
00129
00130 inline
00131 ros::Duration duration (const double rate)
00132 {
00133 ROS_ASSERT_MSG (rate > 0, "A rate parameter was 0, which is not allowed.");
00134 return ros::Duration(1/rate);
00135 }
00136
00137 inline
00138 void doNothing (const ros::TimerEvent& e)
00139 {
00140 }
00141
00142 template <class F, class G>
00143 ros::Timer timerFromRate(const ros::NodeHandle& nh, const double rate, const F& fn, const G& obj_ptr)
00144 {
00145 if (rate > 1e-6)
00146 return nh.createTimer(duration(rate), fn, obj_ptr);
00147 else
00148 return nh.createTimer(ros::Duration(1.0), doNothing);
00149 }
00150
00151 typedef boost::optional<tf::StampedTransform> MaybeTransform;
00152 typedef boost::optional<gm::PoseStamped> MaybePose;
00153
00156 inline
00157 MaybeTransform getTransform
00158 (const tf::Transformer& tf, const string& target_frame,
00159 const ros::Time& target_time, const string& source_frame,
00160 const ros::Time& source_time, const string& fixed_frame,
00161 const ros::Duration& timeout)
00162 {
00163 MaybeTransform tr;
00164 if (tf.waitForTransform(target_frame, target_time, source_frame,
00165 source_time, fixed_frame, timeout)) {
00166 try
00167 {
00168 tf::StampedTransform trans;
00169 tf.lookupTransform(target_frame, target_time, source_frame,
00170 source_time, fixed_frame, trans);
00171 tr.reset(trans);
00172 }
00173 catch (tf::TransformException& e)
00174 {
00175
00176 }
00177 }
00178 return tr;
00179 }
00180
00181 inline
00182 MaybePose waitAndTransform
00183 (const tf::TransformListener& tf, const gm::PoseStamped& pose_in,
00184 const string& target_frame, const ros::Time& target_time,
00185 const string& fixed_frame, const ros::Duration& timeout)
00186 {
00187 MaybePose pose_out;
00188 if (tf.waitForTransform(target_frame, target_time,
00189 pose_in.header.frame_id, pose_in.header.stamp,
00190 fixed_frame, timeout*0.5))
00191 {
00192 try
00193 {
00194 gm::PoseStamped p;
00195 tf.transformPose(target_frame, target_time, pose_in,
00196 fixed_frame, p);
00197 pose_out.reset(p);
00198 }
00199 catch (tf::TransformException& e)
00200 {
00201
00202 }
00203 }
00204 return pose_out;
00205 }
00206
00207 inline
00208 MaybeTransform getTransform
00209 (const tf::TransformListener& tf, const string& target_frame,
00210 const string& source_frame, const ros::Time& t, const ros::Duration& timeout)
00211 {
00212 MaybeTransform trans;
00213 if (tf.waitForTransform(target_frame, source_frame, t, timeout))
00214 {
00215 try
00216 {
00217 tf::StampedTransform tr;
00218 tf.lookupTransform(target_frame, source_frame, t, tr);
00219 trans.reset(tr);
00220 }
00221 catch (tf::TransformException& e)
00222 {
00223
00224 }
00225 }
00226 return trans;
00227 }
00228
00229
00230 }
00231
00232 #endif // include guard