55int main(
int argc,
char** argv)
57 rclcpp::init(argc, argv);
58 auto node = rclcpp::Node::make_shared(
"visualize_robot_collision_volume");
61 rclcpp::executors::MultiThreadedExecutor executor;
62 executor.add_node(node);
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';
75 std::cin >> num_spheres;
78 std::vector<double> aabb;
79 scene->getCurrentState().computeAABB(aabb);
82 visualization_msgs::msg::Marker mk;
83 mk.header.stamp = node->now();
84 mk.header.frame_id = scene->getPlanningFrame();
85 mk.ns =
"bounding_box";
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];
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);
107 std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> points;
108 std::size_t published = 0;
109 random_numbers::RandomNumberGenerator rng;
112 std_msgs::msg::ColorRGBA color;
118 for (
int i = 0; i < num_spheres; ++i)
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);
128 points.push_back(t.translation());
129 if (points.size() - published >= 100 || (points.size() > published && i + 1 >= num_spheres))
132 for (std::size_t k = published; k < points.size(); ++k)
134 visualization_msgs::msg::Marker mk;
135 mk.header.stamp = node->now();
136 mk.header.frame_id = scene->getPlanningFrame();
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;
147 mk.lifetime = rclcpp::Duration::from_seconds(lifetime);
148 arr.markers.push_back(mk);
149 pub_markers->publish(arr);
151 pub_markers->publish(arr);
152 published = points.size();