40 #include <geometry_msgs/TransformStamped.h> 52 geometry_msgs::TransformStamped
operator()(
const geometry_msgs::TransformStamped& elem)
54 geometry_msgs::TransformStamped result = elem;
64 tf2_msgs::TFMessage
transformsToMessage(
const std::vector<geometry_msgs::TransformStamped>& tforms,
const std::string& prefix)
66 tf2_msgs::TFMessage msg;
68 msg.transforms.resize(tforms.size());
69 std::transform(tforms.begin(), tforms.end(), msg.transforms.begin(),
PrefixResolver(prefix));
77 tf2::BufferCore(
ros::Duration(BufferCore::DEFAULT_CACHE_TIME) ),
78 prop_cache_time( BufferCore::DEFAULT_CACHE_TIME ),
79 prop_buffer_size(DEFAULT_BUFFER_SIZE)
95 .doc(
"Lookup the most recent transform from source to target.")
96 .arg(
"target",
"target frame")
97 .arg(
"source",
"source frame");
100 .doc(
"Lookup the most recent transform from source to target at a specific time.")
101 .arg(
"target",
"Target frame")
102 .arg(
"source",
"Source frame")
103 .arg(
"common_time",
"[ros::Time] The common time at which the transform should be computed");
106 .doc(
"Broadcast a stamped transform immediately.")
107 .arg(
"transform",
"[geometry_msgs::TransformStamped]");
110 .doc(
"Broadcast stamped transforms immediately.")
111 .arg(
"transforms",
"[std::vector<geometry_msgs::TransformStamped>]");
114 .doc(
"Broadcast a stamped transform as a static transform immediately.")
115 .arg(
"transform",
"[geometry_msgs::TransformStamped]");
118 .doc(
"Broadcast stamped transforms as static transforms immediately.")
119 .arg(
"transforms",
"[std::vector<geometry_msgs::TransformStamped>]");
122 .doc(
"Check if the transform from source to target can be resolved.")
123 .arg(
"target",
"Target frame")
124 .arg(
"source",
"Source frame");
127 .doc(
"Check if the transform from source to target can be resolved for a given common time.")
128 .arg(
"target",
"Target frame")
129 .arg(
"source",
"Source frame")
130 .arg(
"common_time",
"[ros::Time] The common time for which the transform would resolve");
133 .doc(
"Tracks a transformation and reprots the new transforms via a port")
134 .arg(
"target",
"Target frame id")
135 .arg(
"source",
"Source frame id");
138 .doc(
"Lists the TF trackers added via subscribeTransfrom()");
147 std::string tf_prefix_param_key;
148 if(nh.
searchParam(
"tf_prefix",tf_prefix_param_key)) {
160 cp_static.
name_id =
"/tf_static";
178 const std::string authority =
"unknown_authority";
181 for (std::size_t i = 0; i < msg.transforms.size(); ++i) {
183 this->
setTransform(msg.transforms[i], authority, is_static);
185 log(
Error) <<
"Failure to set received transform from " 186 << msg.transforms[i].child_frame_id <<
" to " 187 << msg.transforms[i].header.frame_id
188 <<
" with error: " << ex.what() << endlog();
201 geometry_msgs::TransformStamped msg =
lookupTransform(it_tracker->first.first, it_tracker->first.second);
202 it_tracker->second->write(msg);
210 " updates form TF will be published automatically" <<
RTT::endlog();
225 tf2_msgs::TFMessage msg_in;
229 catch (std::exception& ex)
231 log(
Error) << ex.what() << endlog();
250 const std::string& target,
251 const std::string& source)
const 264 const std::string& target,
265 const std::string& source)
const 271 const std::string& target,
272 const std::string& source)
const 278 const std::string& target,
279 const std::string& source,
286 const std::string& target,
287 const std::string& source,
295 const std::vector<geometry_msgs::TransformStamped> tforms(1, tform);
308 const std::vector<geometry_msgs::TransformStamped> tforms(1, tform);
322 const std::pair<std::string, std::string> transfrom_pair(target, source);
323 const std::string name_transform = source +
"_" + target;
324 const std::string name_port =
"tracker_tf_" + name_transform;
332 " to " << target <<
" cannot yet be performed" <<
RTT::endlog();
335 boost::make_shared<RTT::OutputPort<geometry_msgs::TransformStamped> >(name_port);
337 .
doc(
"Port generated by " +
getName() +
" for the transformation: " + name_transform);
357 " : [" << it->second->getName() <<
"]" <<
RTT::endlog();
Property< T > & addProperty(const std::string &name, T &attr)
bool canTransform(const std::string &target, const std::string &source) const
void addTFOperations(RTT::Service::shared_ptr service)
geometry_msgs::TransformStamped lookupTransform(const std::string &target, const std::string &source) const
ORO_CREATE_COMPONENT(BroadcasterComponent)
boost::shared_ptr< tf2_ros::TransformListener > TransformListenerPtr
Service::shared_ptr provides()
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
base::InputPortInterface & addEventPort(const std::string &name, base::InputPortInterface &port, SlotFunction callback=SlotFunction())
LogLevel getLogLevel() const
static Logger * Instance(std::ostream &str=std::cerr)
ros::Time getLatestCommonTime(const std::string &target, const std::string &source) const
TransformListenerPtr transform_listener
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_static_out
std::map< std::pair< std::string, std::string >, OutputPortGeometryTransfromStampedPtr > ports_trackers
std::string resolve(const std::string &prefix, const std::string &frame_name)
bool subscribeTransfrom(const std::string &target, const std::string &source)
virtual Seconds getPeriod() const
bool searchParam(const std::string &key, std::string &result) const
bool canTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_out
base::PortInterface & addPort(const std::string &name, base::PortInterface &port)
virtual bool createStream(ConnPolicy const &policy)
void broadcastTransform(const geometry_msgs::TransformStamped &tform)
const std::string & prefix_
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
static ConnPolicy buffer(int size, int lock_policy=LOCK_FREE, bool init_connection=false, bool pull=false)
WriteStatus write(const T &sample)
RTT::InputPort< tf2_msgs::TFMessage > port_tf_static_in
CompactFrameID _lookupFrameNumber(const std::string &frameid_str) const
RTT::InputPort< tf2_msgs::TFMessage > port_tf_in
void internalUpdate(tf2_msgs::TFMessage &msg, RTT::InputPort< tf2_msgs::TFMessage > &port, bool is_static)
PrefixResolver(const std::string &prefix)
int _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
void broadcastTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
virtual void disconnect()
void broadcastStaticTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
bool getParam(const std::string &key, std::string &s) const
BufferCorePtr buffer_core
void broadcastStaticTransform(const geometry_msgs::TransformStamped &tform)
tf2_msgs::TFMessage transformsToMessage(const std::vector< geometry_msgs::TransformStamped > &tforms, const std::string &prefix)
PortInterface & doc(const std::string &desc)
geometry_msgs::TransformStamped operator()(const geometry_msgs::TransformStamped &elem)
RTT_TF(std::string const &name)
geometry_msgs::TransformStamped lookupTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
std::string prop_tf_prefix
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
static Logger::LogFunction endlog()
virtual const std::string & getName() const
void setLogLevel(LogLevel ll)