moveit2
The MoveIt Motion Planning Framework for ROS 2.
visualize_robot_collision_volume.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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: Ioan Sucan */
36 
38 #include <rclcpp/duration.hpp>
39 #include <rclcpp/executors/multi_threaded_executor.hpp>
40 #include <rclcpp/node.hpp>
41 #include <rclcpp/publisher.hpp>
42 #include <rclcpp/version.h>
43 #include <moveit/utils/logger.hpp>
44 #if RCLCPP_VERSION_GTE(20, 0, 0)
45 #include <rclcpp/event_handler.hpp>
46 #else
47 #include <rclcpp/qos_event.hpp>
48 #endif
49 #include <rclcpp/time.hpp>
50 #include <rclcpp/utilities.hpp>
51 #include <memory>
52 
53 static const std::string ROBOT_DESCRIPTION = "robot_description";
54 
55 int main(int argc, char** argv)
56 {
57  rclcpp::init(argc, argv);
58  auto node = rclcpp::Node::make_shared("visualize_robot_collision_volume");
59  moveit::setNodeLoggerName(node->get_name());
60 
61  rclcpp::executors::MultiThreadedExecutor executor;
62  executor.add_node(node);
63  double radius = 0.02;
64  int lifetime = 600;
65 
66  planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
67  if (psm.getPlanningScene())
68  {
70  psm.startSceneMonitor();
71  psm.startStateMonitor();
72  auto pub_markers = node->create_publisher<visualization_msgs::msg::MarkerArray>("visualization_marker_array", 10);
73  std::cout << "\nListening for planning scene...\nType the number of spheres to generate and press Enter: " << '\n';
74  int num_spheres;
75  std::cin >> num_spheres;
76 
77  planning_scene::PlanningScenePtr scene = psm.getPlanningScene();
78  std::vector<double> aabb;
79  scene->getCurrentState().computeAABB(aabb);
80 
81  // publish the bounding box
82  visualization_msgs::msg::Marker mk;
83  mk.header.stamp = node->now();
84  mk.header.frame_id = scene->getPlanningFrame();
85  mk.ns = "bounding_box";
86  mk.id = 0;
87  mk.type = visualization_msgs::msg::Marker::CUBE;
88  mk.action = visualization_msgs::msg::Marker::ADD;
89  mk.pose.position.x = (aabb[0] + aabb[1]) / 2.0;
90  mk.pose.position.y = (aabb[2] + aabb[3]) / 2.0;
91  mk.pose.position.z = (aabb[4] + aabb[5]) / 2.0;
92  mk.pose.orientation.w = 1.0;
93  mk.scale.x = aabb[1] - aabb[0];
94  mk.scale.y = aabb[3] - aabb[2];
95  mk.scale.z = aabb[5] - aabb[4];
96  mk.color.r = 0.0f;
97  mk.color.g = 0.5f;
98  mk.color.b = 1.0f;
99  mk.color.a = 0.3f;
100  mk.lifetime = rclcpp::Duration::from_seconds(lifetime);
101  visualization_msgs::msg::MarkerArray arr;
102  arr.markers.push_back(mk);
103  pub_markers->publish(arr);
104 
105  Eigen::Isometry3d t;
106  t.setIdentity();
107  std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> points;
108  std::size_t published = 0;
109  random_numbers::RandomNumberGenerator rng;
111 
112  std_msgs::msg::ColorRGBA color;
113  color.r = 1.0f;
114  color.g = 0.0f;
115  color.b = 0.0f;
116  color.a = 1.0f;
117 
118  for (int i = 0; i < num_spheres; ++i)
119  {
120  t.translation() = Eigen::Vector3d(rng.uniformReal(aabb[0], aabb[1]), rng.uniformReal(aabb[2], aabb[3]),
121  rng.uniformReal(aabb[4], aabb[5]));
122  scene->getWorldNonConst()->clearObjects();
123  scene->getWorldNonConst()->addToObject("test", std::make_shared<shapes::Sphere>(radius), t);
125  scene->checkCollision(req, res);
126  if (res.collision)
127  {
128  points.push_back(t.translation());
129  if (points.size() - published >= 100 || (points.size() > published && i + 1 >= num_spheres))
130  {
131  arr.markers.clear();
132  for (std::size_t k = published; k < points.size(); ++k)
133  {
134  visualization_msgs::msg::Marker mk;
135  mk.header.stamp = node->now();
136  mk.header.frame_id = scene->getPlanningFrame();
137  mk.ns = "colliding";
138  mk.id = k;
139  mk.type = visualization_msgs::msg::Marker::SPHERE;
140  mk.action = visualization_msgs::msg::Marker::ADD;
141  mk.pose.position.x = points[k].x();
142  mk.pose.position.y = points[k].y();
143  mk.pose.position.z = points[k].z();
144  mk.pose.orientation.w = 1.0;
145  mk.scale.x = mk.scale.y = mk.scale.z = radius;
146  mk.color = color;
147  mk.lifetime = rclcpp::Duration::from_seconds(lifetime);
148  arr.markers.push_back(mk);
149  pub_markers->publish(arr);
150  }
151  pub_markers->publish(arr);
152  published = points.size();
153  }
154  }
155  }
156  }
157  executor.spin();
158  return 0;
159 }
PlanningSceneMonitor Subscribes to the topic planning_scene.
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
void startStateMonitor(const std::string &joint_states_topic=DEFAULT_JOINT_STATES_TOPIC, const std::string &attached_objects_topic=DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC)
Start the current state monitor.
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
Start the OccupancyMapMonitor and listening for:
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition: logger.cpp:73
Representation of a collision checking request.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
int main(int argc, char **argv)