43int main(
int argc,
char** argv)
45 rclcpp::init(argc, argv);
46 auto node = rclcpp::Node::make_shared(
"display_random_state");
51 for (
int i = 0; i < argc; ++i)
53 if (strcmp(argv[i],
"--valid") == 0)
58 if (strcmp(argv[i],
"--invalid") == 0)
65 rclcpp::executors::MultiThreadedExecutor executor;
66 executor.add_node(node);
70 auto rml = std::make_shared<robot_model_loader::RobotModelLoader>(node, opt);
74 auto pub_scene = node->create_publisher<moveit_msgs::msg::PlanningScene>(
"planning_scene", 1);
76 rclcpp::sleep_for(500ms);
82 RCLCPP_ERROR(node->get_logger(),
"Planning scene did not load properly, exiting...");
86 std::cout <<
"Type a number and hit Enter. That number of ";
89 std::cout <<
"valid ";
93 std::cout <<
"invalid ";
95 std::cout <<
"states will be randomly generated at an interval of one second and published as a planning scene."
100 for (std::size_t i = 0; i < n; ++i)
105 unsigned int attempts = 0;
114 }
while (!found && attempts < 100);
117 std::cout <<
"Unable to find valid state" <<
'\n';
124 unsigned int attempts = 0;
133 }
while (!found && attempts < 100);
136 std::cout <<
"Unable to find invalid state" <<
'\n';
143 moveit_msgs::msg::PlanningScene psmsg;
145 pub_scene->publish(psmsg);
148 rclcpp::sleep_for(1s);
150 }
while (rclcpp::ok());
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: