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/qos_event.hpp>
43 #include <rclcpp/time.hpp>
44 #include <rclcpp/utilities.hpp>
47 static const std::string ROBOT_DESCRIPTION =
"robot_description";
49 int main(
int argc,
char** argv)
51 rclcpp::init(argc, argv);
52 auto node = rclcpp::Node::make_shared(
"visualize_robot_collision_volume");
54 rclcpp::executors::MultiThreadedExecutor executor;
55 executor.add_node(node);
65 auto pub_markers = node->create_publisher<visualization_msgs::msg::MarkerArray>(
"visualization_marker_array", 10);
66 std::cout <<
"\nListening for planning scene...\nType the number of spheres to generate and press Enter: " <<
'\n';
68 std::cin >> num_spheres;
71 std::vector<double> aabb;
72 scene->getCurrentState().computeAABB(aabb);
75 visualization_msgs::msg::Marker mk;
76 mk.header.stamp = node->now();
77 mk.header.frame_id =
scene->getPlanningFrame();
78 mk.ns =
"bounding_box";
80 mk.type = visualization_msgs::msg::Marker::CUBE;
81 mk.action = visualization_msgs::msg::Marker::ADD;
82 mk.pose.position.x = (aabb[0] + aabb[1]) / 2.0;
83 mk.pose.position.y = (aabb[2] + aabb[3]) / 2.0;
84 mk.pose.position.z = (aabb[4] + aabb[5]) / 2.0;
85 mk.pose.orientation.w = 1.0;
86 mk.scale.x = aabb[1] - aabb[0];
87 mk.scale.y = aabb[3] - aabb[2];
88 mk.scale.z = aabb[5] - aabb[4];
93 mk.lifetime = rclcpp::Duration::from_seconds(lifetime);
94 visualization_msgs::msg::MarkerArray arr;
95 arr.markers.push_back(mk);
96 pub_markers->publish(arr);
100 std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> points;
101 std::size_t published = 0;
102 random_numbers::RandomNumberGenerator rng;
105 std_msgs::msg::ColorRGBA color;
111 for (
int i = 0; i < num_spheres; ++i)
113 t.translation() =
Eigen::Vector3d(rng.uniformReal(aabb[0], aabb[1]), rng.uniformReal(aabb[2], aabb[3]),
114 rng.uniformReal(aabb[4], aabb[5]));
115 scene->getWorldNonConst()->clearObjects();
116 scene->getWorldNonConst()->addToObject(
"test", std::make_shared<shapes::Sphere>(radius), t);
118 scene->checkCollision(req, res);
121 points.push_back(t.translation());
122 if (points.size() - published >= 100 || (points.size() > published && i + 1 >= num_spheres))
125 for (std::size_t k = published; k < points.size(); ++k)
127 visualization_msgs::msg::Marker mk;
128 mk.header.stamp = node->now();
129 mk.header.frame_id =
scene->getPlanningFrame();
132 mk.type = visualization_msgs::msg::Marker::SPHERE;
133 mk.action = visualization_msgs::msg::Marker::ADD;
134 mk.pose.position.x = points[k].x();
135 mk.pose.position.y = points[k].y();
136 mk.pose.position.z = points[k].z();
137 mk.pose.orientation.w = 1.0;
138 mk.scale.x = mk.scale.y = mk.scale.z = radius;
140 mk.lifetime = rclcpp::Duration::from_seconds(lifetime);
141 arr.markers.push_back(mk);
142 pub_markers->publish(arr);
144 pub_markers->publish(arr);
145 published = points.size();
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
Representation of a collision checking request.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
int main(int argc, char **argv)