moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
46
47namespace move_group
48{
49
53
55{
56 keep_running_ = false;
57 thread_.join();
58}
59
60namespace
61{
62void publishSubframes(tf2_ros::TransformBroadcaster& broadcaster, const moveit::core::FixedTransformsMap& subframes,
63 const std::string& parent_object, const rclcpp::Time& stamp)
64{
65 geometry_msgs::msg::TransformStamped transform;
66 for (auto& subframe : subframes)
67 {
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);
73 }
74}
75} // namespace
76
77void TfPublisher::publishPlanningSceneFrames()
78{
79 tf2_ros::TransformBroadcaster broadcaster(context_->moveit_cpp_->getNode());
80 geometry_msgs::msg::TransformStamped transform;
81 rclcpp::Rate rate(rate_);
82
83 while (keep_running_)
84 {
85 {
86 rclcpp::Time stamp = context_->moveit_cpp_->getNode()->get_clock()->now();
87 planning_scene_monitor::LockedPlanningSceneRO locked_planning_scene(context_->planning_scene_monitor_);
88 collision_detection::WorldConstPtr world = locked_planning_scene->getWorld();
89 std::string planning_frame = locked_planning_scene->getPlanningFrame();
90
91 for (const auto& obj : *world)
92 {
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);
99
100 const moveit::core::FixedTransformsMap& subframes = obj.second->subframe_poses_;
101 publishSubframes(broadcaster, subframes, object_frame, stamp);
102 }
103
104 const moveit::core::RobotState& rs = locked_planning_scene->getCurrentState();
105 std::vector<const moveit::core::AttachedBody*> attached_collision_objects;
106 rs.getAttachedBodies(attached_collision_objects);
107 for (const moveit::core::AttachedBody* attached_body : attached_collision_objects)
108 {
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);
115
116 const moveit::core::FixedTransformsMap& subframes = attached_body->getSubframes();
117 publishSubframes(broadcaster, subframes, object_frame, stamp);
118 }
119 }
120
121 rate.sleep();
122 }
123}
124
126{
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())
131 prefix_ += "/";
132
133 keep_running_ = true;
134
135 RCLCPP_INFO(moveit::getLogger("moveit.ros.move_group.tf_publisher"),
136 "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.
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
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79