moveit2
The MoveIt Motion Planning Framework for ROS 2.
tf_publisher_capability.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Hamburg University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Hamburg University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Jonas Tietz */
36 
41 #include <tf2_ros/transform_broadcaster.h>
42 #include <tf2_eigen/tf2_eigen.hpp>
45 
46 namespace move_group
47 {
48 static const rclcpp::Logger LOGGER =
49  rclcpp::get_logger("moveit_move_group_default_capabilities.tf_publisher_capability");
50 
52 {
53 }
54 
56 {
57  keep_running_ = false;
58  thread_.join();
59 }
60 
61 namespace
62 {
63 void publishSubframes(tf2_ros::TransformBroadcaster& broadcaster, const moveit::core::FixedTransformsMap& subframes,
64  const std::string& parent_object, const rclcpp::Time& stamp)
65 {
66  geometry_msgs::msg::TransformStamped transform;
67  for (auto& subframe : subframes)
68  {
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);
74  }
75 }
76 } // namespace
77 
78 void TfPublisher::publishPlanningSceneFrames()
79 {
80  tf2_ros::TransformBroadcaster broadcaster(context_->moveit_cpp_->getNode());
81  geometry_msgs::msg::TransformStamped transform;
82  rclcpp::Rate rate(rate_);
83 
84  while (keep_running_)
85  {
86  {
87  rclcpp::Time stamp = context_->moveit_cpp_->getNode()->get_clock()->now();
88  planning_scene_monitor::LockedPlanningSceneRO locked_planning_scene(context_->planning_scene_monitor_);
89  collision_detection::WorldConstPtr world = locked_planning_scene->getWorld();
90  std::string planning_frame = locked_planning_scene->getPlanningFrame();
91 
92  for (const auto& obj : *world)
93  {
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);
100 
101  const moveit::core::FixedTransformsMap& subframes = obj.second->subframe_poses_;
102  publishSubframes(broadcaster, subframes, object_frame, stamp);
103  }
104 
105  const moveit::core::RobotState& rs = locked_planning_scene->getCurrentState();
106  std::vector<const moveit::core::AttachedBody*> attached_collision_objects;
107  rs.getAttachedBodies(attached_collision_objects);
108  for (const moveit::core::AttachedBody* attached_body : attached_collision_objects)
109  {
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);
116 
117  const moveit::core::FixedTransformsMap& subframes = attached_body->getSubframes();
118  publishSubframes(broadcaster, subframes, object_frame, stamp);
119  }
120  }
121 
122  rate.sleep();
123  }
124 }
125 
127 {
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())
132  prefix_ += "/";
133 
134  keep_running_ = true;
135 
136  RCLCPP_INFO(LOGGER, "Initializing MoveGroupTfPublisher with a frame publishing rate of %d", rate_);
137  thread_ = std::thread(&TfPublisher::publishPlanningSceneFrames, this);
138 }
139 } // namespace move_group
140 
141 #include <pluginlib/class_list_macros.hpp>
142 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
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...
Definition: transforms.h:53
const rclcpp::Logger LOGGER
Definition: async_test.h:31