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
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048 #include "rtt_tf-component.hpp"
00049 #include <rtt/Component.hpp>
00050 #include <ros/ros.h>
00051
00052 namespace rtt_tf
00053 {
00054
00055 using namespace RTT;
00056 using namespace tf;
00057
00058 RTT_TF::RTT_TF(const std::string& name) :
00059 TaskContext(name, PreOperational),
00060 tf::Transformer(true, ros::Duration(Transformer::DEFAULT_CACHE_TIME)),
00061 prop_cache_time(Transformer::DEFAULT_CACHE_TIME),
00062 prop_buffer_size(DEFAULT_BUFFER_SIZE)
00063 {
00064 this->addProperty("cache_time", prop_cache_time);
00065 this->addProperty("buffer_size", prop_buffer_size);
00066 this->addProperty("tf_prefix", prop_tf_prefix);
00067 this->addEventPort("tf_in", port_tf_in);
00068 this->addPort("tf_out", port_tf_out);
00069
00070 this->addTFOperations(this->provides());
00071 this->addTFOperations(this->provides("tf"));
00072 }
00073
00074 void RTT_TF::addTFOperations(RTT::Service::shared_ptr service)
00075 {
00076 service->addOperation("lookupTransform", &RTT_TF::lookupTransform, this)
00077 .doc("Lookup the most recent transform from source to target.")
00078 .arg("target", "target frame")
00079 .arg("source", "source frame");
00080
00081 service->addOperation("lookupTransformAtTime", &RTT_TF::lookupTransformAtTime, this)
00082 .doc("Lookup the most recent transform from source to target at a specific time.")
00083 .arg("target", "Target frame")
00084 .arg("source", "Source frame")
00085 .arg("common_time", "[ros::Time] The common time at which the transform should be computed");
00086
00087 service->addOperation("broadcastTransform", &RTT_TF::broadcastTransform, this, RTT::OwnThread)
00088 .doc("Broadcast a stamped transform immediately.")
00089 .arg("transform", "[geometry_msgs::TransformStamped]");
00090
00091 service->addOperation("broadcastTransforms", &RTT_TF::broadcastTransforms, this, RTT::OwnThread)
00092 .doc("Broadcast a stamped transform immediately.")
00093 .arg("transforms", "[std::vector<geometry_msgs::TransformStamped>]");
00094
00095 service->addOperation("canTransform", &RTT_TF::canTransform, this)
00096 .doc("Check if the transform from source to target can be resolved..")
00097 .arg("target", "Target frame")
00098 .arg("source", "Source frame");
00099 }
00100
00101 bool RTT_TF::configureHook()
00102 {
00103 Logger::In(this->getName());
00104
00105
00106 ros::NodeHandle nh("~");
00107 std::string tf_prefix_param_key;
00108 if(nh.searchParam("tf_prefix",tf_prefix_param_key)) {
00109 nh.getParam(tf_prefix_param_key, prop_tf_prefix);
00110 }
00111
00112
00113 tf_prefix_ = prop_tf_prefix;
00114
00115
00116 ConnPolicy cp = ConnPolicy::buffer(prop_buffer_size);
00117 cp.transport = 3;
00118 cp.name_id = "/tf";
00119
00120 return (port_tf_in.createStream(cp) && port_tf_out.createStream(cp));
00121 }
00122
00123 void RTT_TF::updateHook()
00124 {
00125 Logger::In(this->getName());
00126 #ifndef NDEBUG
00127
00128 #endif
00129 try {
00130 tf::tfMessage msg_in;
00131
00132 while (port_tf_in.read(msg_in) == NewData) {
00133 for (unsigned int i = 0; i < msg_in.transforms.size(); i++) {
00134 StampedTransform trans;
00135 transformStampedMsgToTF(msg_in.transforms[i], trans);
00136 try {
00137 #if ROS_VERSION_MINIMUM(1,11,0)
00138 this->setTransform(trans);
00139 #else
00140 std::map<std::string, std::string>* msg_header_map =
00141 msg_in.__connection_header.get();
00142 std::string authority;
00143 std::map<std::string, std::string>::iterator it =
00144 msg_header_map->find("callerid");
00145
00146 if (it == msg_header_map->end()) {
00147 log(Warning) << "Message received without callerid" << endlog();
00148 authority = "no callerid";
00149 } else {
00150 authority = it->second;
00151 }
00152 this->setTransform(trans, authority);
00153 #endif
00154 } catch (TransformException& ex) {
00155 log(Error) << "Failure to set received transform from "
00156 << msg_in.transforms[i].child_frame_id << " to "
00157 << msg_in.transforms[i].header.frame_id
00158 << " with error: " << ex.what() << endlog();
00159 }
00160 }
00161 }
00162 } catch (std::exception& ex) {
00163 log(Error) << ex.what() << endlog();
00164 }
00165 }
00166
00167 geometry_msgs::TransformStamped RTT_TF::lookupTransform(
00168 const std::string& target,
00169 const std::string& source)
00170 {
00171 tf::StampedTransform stamped_tf;
00172 ros::Time common_time;
00173 this->getLatestCommonTime(source, target, common_time,NULL);
00174 static_cast<tf::Transformer*>(this)->lookupTransform(target, source, common_time, stamped_tf);
00175 geometry_msgs::TransformStamped msg;
00176 tf::transformStampedTFToMsg(stamped_tf,msg);
00177 return msg;
00178 }
00179
00180 bool RTT_TF::canTransform(
00181 const std::string& target,
00182 const std::string& source)
00183 {
00184 tf::StampedTransform stamped_tf;
00185 ros::Time common_time;
00186 this->getLatestCommonTime(source, target, common_time,NULL);
00187 return static_cast<tf::Transformer*>(this)->canTransform(target, source, common_time);
00188 }
00189
00190 geometry_msgs::TransformStamped RTT_TF::lookupTransformAtTime(
00191 const std::string& target,
00192 const std::string& source,
00193 const ros::Time& common_time)
00194 {
00195 tf::StampedTransform stamped_tf;
00196 static_cast<tf::Transformer*>(this)->lookupTransform(target, source, common_time, stamped_tf);
00197 geometry_msgs::TransformStamped msg;
00198 tf::transformStampedTFToMsg(stamped_tf,msg);
00199 return msg;
00200 }
00201
00202 void RTT_TF::broadcastTransform(
00203 const geometry_msgs::TransformStamped &tform)
00204 {
00205
00206 tf::tfMessage msg_out;
00207 msg_out.transforms.push_back(tform);
00208
00209
00210 msg_out.transforms.back().header.frame_id = tf::resolve(prop_tf_prefix, msg_out.transforms.back().header.frame_id);
00211 msg_out.transforms.back().child_frame_id = tf::resolve(prop_tf_prefix, msg_out.transforms.back().child_frame_id);
00212
00213 port_tf_out.write(msg_out);
00214 }
00215
00216 void RTT_TF::broadcastTransforms(
00217 const std::vector<geometry_msgs::TransformStamped> &tform)
00218 {
00219
00220 tf::tfMessage msg_out;
00221
00222
00223 for(std::vector<geometry_msgs::TransformStamped>::const_iterator it = tform.begin();
00224 it != tform.end();
00225 ++it)
00226 {
00227 msg_out.transforms.push_back(*it);
00228 msg_out.transforms.back().header.frame_id = tf::resolve(prop_tf_prefix, msg_out.transforms.back().header.frame_id);
00229 msg_out.transforms.back().child_frame_id = tf::resolve(prop_tf_prefix, msg_out.transforms.back().child_frame_id);
00230 }
00231
00232 port_tf_out.write(msg_out);
00233 }
00234
00235 }
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249 ORO_CREATE_COMPONENT(rtt_tf::RTT_TF)