40 using namespace std::chrono_literals;
42 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"display_random_state");
44 int main(
int argc,
char** argv)
46 rclcpp::init(argc, argv);
47 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);
69 opt.robot_description_ =
"robot_description";
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(LOGGER,
"Planning scene did not load properly, exiting...");
86 std::cout <<
"Type a number and hit Enter. That number of ";
88 std::cout <<
"valid ";
90 std::cout <<
"invalid ";
91 std::cout <<
"states will be randomly generated at an interval of one second and published as a planning scene."
96 for (std::size_t i = 0; i < n; ++i)
101 unsigned int attempts = 0;
110 }
while (!found && attempts < 100);
113 std::cout <<
"Unable to find valid state" <<
'\n';
120 unsigned int attempts = 0;
129 }
while (!found && attempts < 100);
132 std::cout <<
"Unable to find invalid state" <<
'\n';
139 moveit_msgs::msg::PlanningScene psmsg;
141 pub_scene->publish(psmsg);
144 rclcpp::sleep_for(1s);
146 }
while (rclcpp::ok());
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 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:
int main(int argc, char **argv)
const rclcpp::Logger LOGGER
Representation of a collision checking request.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Structure that encodes the options to be passed to the RobotModelLoader constructor.