41#include <rclcpp/executors/multi_threaded_executor.hpp>
42#include <rclcpp/logger.hpp>
43#include <rclcpp/logging.hpp>
44#include <rclcpp/node.hpp>
45#include <rclcpp/utilities.hpp>
48static const std::string ROBOT_DESCRIPTION =
"robot_description";
50int main(
int argc,
char** argv)
52 rclcpp::init(argc, argv);
54 auto node = rclcpp::Node::make_shared(
"print_scene_info_to_console");
57 rclcpp::executors::MultiThreadedExecutor executor;
58 executor.add_node(node);
60 RCLCPP_INFO_STREAM(node->get_logger(),
"Getting planning scene info to print");
66 RCLCPP_ERROR_STREAM(node->get_logger(),
"Planning scene not configured");
PlanningSceneMonitor Subscribes to the topic planning_scene.
static const std::string DEFAULT_PLANNING_SCENE_SERVICE
The name of the service used by default for requesting full planning scene state.
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Request a full planning scene state using a service call Be careful not to use this in conjunction wi...
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
int main(int argc, char **argv)