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
00031
00032
00033
00034
00035
00036
00037 #include <tf2_ros/buffer_server.h>
00038
00039 namespace tf2_ros
00040 {
00041 BufferServer::BufferServer(const Buffer& buffer, const std::string& ns, bool auto_start, ros::Duration check_period):
00042 buffer_(buffer),
00043 server_(ros::NodeHandle(),
00044 ns,
00045 boost::bind(&BufferServer::goalCB, this, _1),
00046 boost::bind(&BufferServer::cancelCB, this, _1),
00047 auto_start)
00048 {
00049 ros::NodeHandle n;
00050 check_timer_ = n.createTimer(check_period, boost::bind(&BufferServer::checkTransforms, this, _1));
00051 }
00052
00053 void BufferServer::checkTransforms(const ros::TimerEvent& e)
00054 {
00055 boost::mutex::scoped_lock l(mutex_);
00056 for(std::list<GoalInfo>::iterator it = active_goals_.begin(); it != active_goals_.end();)
00057 {
00058 GoalInfo& info = *it;
00059
00060
00061
00062 if(canTransform(info.handle) || info.end_time < ros::Time::now())
00063 {
00064 tf2_msgs::LookupTransformResult result;
00065
00066
00067 try
00068 {
00069 result.transform = lookupTransform(info.handle);
00070 }
00071 catch (tf2::ConnectivityException &ex)
00072 {
00073 result.error.error = result.error.CONNECTIVITY_ERROR;
00074 result.error.error_string = ex.what();
00075 }
00076 catch (tf2::LookupException &ex)
00077 {
00078 result.error.error = result.error.LOOKUP_ERROR;
00079 result.error.error_string = ex.what();
00080 }
00081 catch (tf2::ExtrapolationException &ex)
00082 {
00083 result.error.error = result.error.EXTRAPOLATION_ERROR;
00084 result.error.error_string = ex.what();
00085 }
00086 catch (tf2::InvalidArgumentException &ex)
00087 {
00088 result.error.error = result.error.INVALID_ARGUMENT_ERROR;
00089 result.error.error_string = ex.what();
00090 }
00091 catch (tf2::TimeoutException &ex)
00092 {
00093 result.error.error = result.error.TIMEOUT_ERROR;
00094 result.error.error_string = ex.what();
00095 }
00096 catch (tf2::TransformException &ex)
00097 {
00098 result.error.error = result.error.TRANSFORM_ERROR;
00099 result.error.error_string = ex.what();
00100 }
00101
00102
00103
00104
00105 it = active_goals_.erase(it);
00106 info.handle.setSucceeded(result);
00107 }
00108 else
00109 ++it;
00110 }
00111 }
00112
00113 void BufferServer::cancelCB(GoalHandle gh)
00114 {
00115 boost::mutex::scoped_lock l(mutex_);
00116
00117
00118
00119 for(std::list<GoalInfo>::iterator it = active_goals_.begin(); it != active_goals_.end();)
00120 {
00121 GoalInfo& info = *it;
00122 if(info.handle == gh)
00123 {
00124 it = active_goals_.erase(it);
00125 info.handle.setCanceled();
00126 return;
00127 }
00128 else
00129 ++it;
00130 }
00131 }
00132
00133 void BufferServer::goalCB(GoalHandle gh)
00134 {
00135
00136 gh.setAccepted();
00137
00138
00139
00140 GoalInfo goal_info;
00141 goal_info.handle = gh;
00142 goal_info.end_time = ros::Time::now() + gh.getGoal()->timeout;
00143
00144
00145
00146 if(canTransform(gh) || goal_info.end_time <= ros::Time::now())
00147 {
00148 tf2_msgs::LookupTransformResult result;
00149 try
00150 {
00151 result.transform = lookupTransform(gh);
00152 }
00153 catch (tf2::ConnectivityException &ex)
00154 {
00155 result.error.error = result.error.CONNECTIVITY_ERROR;
00156 result.error.error_string = ex.what();
00157 }
00158 catch (tf2::LookupException &ex)
00159 {
00160 result.error.error = result.error.LOOKUP_ERROR;
00161 result.error.error_string = ex.what();
00162 }
00163 catch (tf2::ExtrapolationException &ex)
00164 {
00165 result.error.error = result.error.EXTRAPOLATION_ERROR;
00166 result.error.error_string = ex.what();
00167 }
00168 catch (tf2::InvalidArgumentException &ex)
00169 {
00170 result.error.error = result.error.INVALID_ARGUMENT_ERROR;
00171 result.error.error_string = ex.what();
00172 }
00173 catch (tf2::TimeoutException &ex)
00174 {
00175 result.error.error = result.error.TIMEOUT_ERROR;
00176 result.error.error_string = ex.what();
00177 }
00178 catch (tf2::TransformException &ex)
00179 {
00180 result.error.error = result.error.TRANSFORM_ERROR;
00181 result.error.error_string = ex.what();
00182 }
00183
00184 gh.setSucceeded(result);
00185 return;
00186 }
00187
00188 boost::mutex::scoped_lock l(mutex_);
00189 active_goals_.push_back(goal_info);
00190 }
00191
00192 bool BufferServer::canTransform(GoalHandle gh)
00193 {
00194 const tf2_msgs::LookupTransformGoal::ConstPtr& goal = gh.getGoal();
00195
00196
00197 if(!goal->advanced)
00198 return buffer_.canTransform(goal->target_frame, goal->source_frame, goal->source_time);
00199
00200 return buffer_.canTransform(goal->target_frame, goal->target_time,
00201 goal->source_frame, goal->source_time, goal->fixed_frame);
00202 }
00203
00204 geometry_msgs::TransformStamped BufferServer::lookupTransform(GoalHandle gh)
00205 {
00206 const tf2_msgs::LookupTransformGoal::ConstPtr& goal = gh.getGoal();
00207
00208
00209 if(!goal->advanced)
00210 return buffer_.lookupTransform(goal->target_frame, goal->source_frame, goal->source_time);
00211
00212 return buffer_.lookupTransform(goal->target_frame, goal->target_time,
00213 goal->source_frame, goal->source_time, goal->fixed_frame);
00214 }
00215
00216 void BufferServer::start()
00217 {
00218 server_.start();
00219 }
00220
00221 };