60 const std::string& parent_object,
const ros::Time& stamp)
62 geometry_msgs::TransformStamped
transform;
63 for (
auto& subframe : subframes)
66 transform.child_frame_id = parent_object +
"/" + subframe.first;
68 transform.header.frame_id = parent_object;
77 geometry_msgs::TransformStamped
transform;
85 collision_detection::WorldConstPtr world = locked_planning_scene->getWorld();
86 std::string planning_frame = locked_planning_scene->getPlanningFrame();
88 for (
const auto& obj : *world)
90 std::string object_frame =
prefix_ +
obj.second->id_;
94 transform.header.frame_id = planning_frame;
98 publishSubframes(broadcaster, subframes, object_frame, stamp);
102 std::vector<const moveit::core::AttachedBody*> attached_collision_objects;
106 std::string object_frame =
prefix_ + attached_body->getName();
110 transform.header.frame_id = attached_body->getAttachedLinkName();
114 publishSubframes(broadcaster, subframes, object_frame, stamp);
127 nh.
param(
"planning_scene_frame_publishing_rate",
rate_, 10);
131 ROS_INFO(
"Initializing MoveGroupTfPublisher with a frame publishing rate of %d",
rate_);