41 #include <tf2_ros/transform_broadcaster.h>
42 #include <tf2_eigen/tf2_eigen.hpp>
48 static const rclcpp::Logger
LOGGER =
49 rclcpp::get_logger(
"moveit_move_group_default_capabilities.tf_publisher_capability");
57 keep_running_ =
false;
64 const std::string& parent_object,
const rclcpp::Time& stamp)
66 geometry_msgs::msg::TransformStamped transform;
67 for (
auto& subframe : subframes)
69 transform = tf2::eigenToTransform(subframe.second);
70 transform.child_frame_id = parent_object +
"/" + subframe.first;
71 transform.header.stamp = stamp;
72 transform.header.frame_id = parent_object;
73 broadcaster.sendTransform(transform);
78 void TfPublisher::publishPlanningSceneFrames()
80 tf2_ros::TransformBroadcaster broadcaster(
context_->moveit_cpp_->getNode());
81 geometry_msgs::msg::TransformStamped transform;
82 rclcpp::Rate rate(rate_);
87 rclcpp::Time stamp =
context_->moveit_cpp_->getNode()->get_clock()->now();
89 collision_detection::WorldConstPtr world = locked_planning_scene->getWorld();
90 std::string planning_frame = locked_planning_scene->getPlanningFrame();
92 for (
const auto& obj : *world)
94 std::string object_frame = prefix_ + obj.second->id_;
95 transform = tf2::eigenToTransform(obj.second->pose_);
96 transform.child_frame_id = object_frame;
97 transform.header.stamp = stamp;
98 transform.header.frame_id = planning_frame;
99 broadcaster.sendTransform(transform);
102 publishSubframes(broadcaster, subframes, object_frame, stamp);
106 std::vector<const moveit::core::AttachedBody*> attached_collision_objects;
110 std::string object_frame = prefix_ + attached_body->getName();
111 transform = tf2::eigenToTransform(attached_body->getPose());
112 transform.child_frame_id = object_frame;
113 transform.header.stamp = stamp;
114 transform.header.frame_id = attached_body->getAttachedLinkName();
115 broadcaster.sendTransform(transform);
118 publishSubframes(broadcaster, subframes, object_frame, stamp);
128 std::string prefix =
context_->moveit_cpp_->getNode()->get_name();
129 context_->moveit_cpp_->getNode()->get_parameter_or(
"planning_scene_frame_publishing_rate", rate_, 10);
130 context_->moveit_cpp_->getNode()->get_parameter_or(
"planning_scene_tf_prefix", prefix_, prefix);
131 if (!prefix_.empty())
134 keep_running_ =
true;
136 RCLCPP_INFO(LOGGER,
"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...
const rclcpp::Logger LOGGER