37 #include <kdl/frames_io.hpp> 38 #include <geometry_msgs/TransformStamped.h> 61 for (
unsigned int i=0; i<children.size(); i++) {
66 ROS_INFO(
"Floating joint. Not adding segment from %s to %s. This TF can not be published based on joint_states info", root.c_str(), child.
getName().c_str());
70 ROS_DEBUG(
"Adding fixed segment from %s to %s", root.c_str(), child.
getName().c_str());
75 ROS_DEBUG(
"Adding moving segment from %s to %s", root.c_str(), child.
getName().c_str());
85 ROS_DEBUG(
"Publishing transforms for moving joints");
86 std::vector<geometry_msgs::TransformStamped> tf_transforms;
89 for (map<string, double>::const_iterator jnt=joint_positions.begin(); jnt != joint_positions.end(); jnt++) {
90 std::map<std::string, SegmentPair>::const_iterator seg =
segments_.find(jnt->first);
92 geometry_msgs::TransformStamped tf_transform =
tf2::kdlToTransform(seg->second.segment.pose(jnt->second));
93 tf_transform.header.stamp = time;
94 tf_transform.header.frame_id =
tf::resolve(tf_prefix, seg->second.root);
95 tf_transform.child_frame_id =
tf::resolve(tf_prefix, seg->second.tip);
96 tf_transforms.push_back(tf_transform);
99 ROS_WARN_THROTTLE(10,
"Joint state with name: \"%s\" was received but not found in URDF", jnt->first.c_str());
108 ROS_DEBUG(
"Publishing transforms for fixed joints");
109 std::vector<geometry_msgs::TransformStamped> tf_transforms;
110 geometry_msgs::TransformStamped tf_transform;
114 geometry_msgs::TransformStamped tf_transform =
tf2::kdlToTransform(seg->second.segment.pose(0));
116 if (!use_tf_static) {
119 tf_transform.header.frame_id =
tf::resolve(tf_prefix, seg->second.root);
120 tf_transform.child_frame_id =
tf::resolve(tf_prefix, seg->second.tip);
121 tf_transforms.push_back(tf_transform);
#define GetTreeElementSegment(tree_element)
SegmentMap::const_iterator getRootSegment() const
virtual void addChildren(const KDL::SegmentMap::const_iterator segment)
virtual void publishFixedTransforms(const std::string &tf_prefix, bool use_tf_static=false)
#define GetTreeElementChildren(tree_element)
std::map< std::string, SegmentPair > segments_fixed_
std::string resolve(const std::string &prefix, const std::string &frame_name)
const Joint & getJoint() const
const urdf::Model & model_
tf2_ros::TransformBroadcaster tf_broadcaster_
virtual void publishTransforms(const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix)
#define ROS_WARN_THROTTLE(period,...)
std::map< std::string, SegmentPair > segments_
const JointType & getType() const
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
geometry_msgs::TransformStamped kdlToTransform(const KDL::Frame &k)
const std::string & getName() const
const std::string & getName() const