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