39#include <rclcpp/version.h>
45#if RCLCPP_VERSION_GTE(29, 6, 0)
46#include <tf2_ros/transform_broadcaster.hpp>
49#include <tf2_ros/transform_broadcaster.h>
51#include <tf2_eigen/tf2_eigen.hpp>
65 keep_running_ =
false;
72 const std::string& parent_object,
const rclcpp::Time& stamp)
74 geometry_msgs::msg::TransformStamped transform;
75 for (
auto& subframe : subframes)
77 transform = tf2::eigenToTransform(subframe.second);
78 transform.child_frame_id = parent_object +
"/" + subframe.first;
79 transform.header.stamp = stamp;
80 transform.header.frame_id = parent_object;
81 broadcaster.sendTransform(transform);
86void TfPublisher::publishPlanningSceneFrames()
89#if RCLCPP_VERSION_GTE(30, 0, 0)
90 tf2_ros::TransformBroadcaster broadcaster(tf2_ros::TransformBroadcaster::RequiredInterfaces{
91 context_->moveit_cpp_->getNode()->get_node_parameters_interface(),
92 context_->moveit_cpp_->getNode()->get_node_topics_interface() });
94 tf2_ros::TransformBroadcaster broadcaster(
context_->moveit_cpp_->getNode());
96 geometry_msgs::msg::TransformStamped transform;
97 rclcpp::Rate rate(rate_);
102 rclcpp::Time stamp =
context_->moveit_cpp_->getNode()->get_clock()->now();
104 collision_detection::WorldConstPtr world = locked_planning_scene->getWorld();
105 std::string planning_frame = locked_planning_scene->getPlanningFrame();
107 for (
const auto& obj : *world)
109 std::string object_frame = prefix_ + obj.second->id_;
110 transform = tf2::eigenToTransform(obj.second->pose_);
111 transform.child_frame_id = object_frame;
112 transform.header.stamp = stamp;
113 transform.header.frame_id = planning_frame;
114 broadcaster.sendTransform(transform);
117 publishSubframes(broadcaster, subframes, object_frame, stamp);
121 std::vector<const moveit::core::AttachedBody*> attached_collision_objects;
125 std::string object_frame = prefix_ + attached_body->getName();
126 transform = tf2::eigenToTransform(attached_body->getPose());
127 transform.child_frame_id = object_frame;
128 transform.header.stamp = stamp;
129 transform.header.frame_id = attached_body->getAttachedLinkName();
130 broadcaster.sendTransform(transform);
133 publishSubframes(broadcaster, subframes, object_frame, stamp);
143 std::string prefix =
context_->moveit_cpp_->getNode()->get_name();
144 context_->moveit_cpp_->getNode()->get_parameter_or(
"planning_scene_frame_publishing_rate", rate_, 10);
145 context_->moveit_cpp_->getNode()->get_parameter_or(
"planning_scene_tf_prefix", prefix_, prefix);
146 if (!prefix_.empty())
149 keep_running_ =
true;
152 "Initializing MoveGroupTfPublisher with a frame publishing rate of %d", rate_);
153 thread_ = std::thread(&TfPublisher::publishPlanningSceneFrames,
this);
157#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.