41#include <tf2_ros/transform_broadcaster.h>
42#include <tf2_eigen/tf2_eigen.hpp>
56 keep_running_ =
false;
63 const std::string& parent_object,
const rclcpp::Time& stamp)
65 geometry_msgs::msg::TransformStamped transform;
66 for (
auto& subframe : subframes)
68 transform = tf2::eigenToTransform(subframe.second);
69 transform.child_frame_id = parent_object +
"/" + subframe.first;
70 transform.header.stamp = stamp;
71 transform.header.frame_id = parent_object;
72 broadcaster.sendTransform(transform);
77void TfPublisher::publishPlanningSceneFrames()
79 tf2_ros::TransformBroadcaster broadcaster(
context_->moveit_cpp_->getNode());
80 geometry_msgs::msg::TransformStamped transform;
81 rclcpp::Rate rate(rate_);
86 rclcpp::Time stamp =
context_->moveit_cpp_->getNode()->get_clock()->now();
88 collision_detection::WorldConstPtr world = locked_planning_scene->getWorld();
89 std::string planning_frame = locked_planning_scene->getPlanningFrame();
91 for (
const auto& obj : *world)
93 std::string object_frame = prefix_ + obj.second->id_;
94 transform = tf2::eigenToTransform(obj.second->pose_);
95 transform.child_frame_id = object_frame;
96 transform.header.stamp = stamp;
97 transform.header.frame_id = planning_frame;
98 broadcaster.sendTransform(transform);
101 publishSubframes(broadcaster, subframes, object_frame, stamp);
105 std::vector<const moveit::core::AttachedBody*> attached_collision_objects;
109 std::string object_frame = prefix_ + attached_body->getName();
110 transform = tf2::eigenToTransform(attached_body->getPose());
111 transform.child_frame_id = object_frame;
112 transform.header.stamp = stamp;
113 transform.header.frame_id = attached_body->getAttachedLinkName();
114 broadcaster.sendTransform(transform);
117 publishSubframes(broadcaster, subframes, object_frame, stamp);
127 std::string prefix =
context_->moveit_cpp_->getNode()->get_name();
128 context_->moveit_cpp_->getNode()->get_parameter_or(
"planning_scene_frame_publishing_rate", rate_, 10);
129 context_->moveit_cpp_->getNode()->get_parameter_or(
"planning_scene_tf_prefix", prefix_, prefix);
130 if (!prefix_.empty())
133 keep_running_ =
true;
136 "Initializing MoveGroupTfPublisher with a frame publishing rate of %d", rate_);
137 thread_ = std::thread(&TfPublisher::publishPlanningSceneFrames,
this);
141#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
MoveGroupContextPtr context_
void initialize() override
Object defining bodies that can be attached to robot links.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.