39 #include <rclcpp/executors/multi_threaded_executor.hpp>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 #include <rclcpp/node.hpp>
43 #include <rclcpp/publisher.hpp>
44 #include <rclcpp/qos_event.hpp>
45 #include <rclcpp/utilities.hpp>
47 using namespace std::chrono_literals;
48 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"publish_scene_from_text");
50 int main(
int argc,
char** argv)
52 rclcpp::init(argc, argv);
53 auto node = rclcpp::Node::make_shared(
"publish_planning_scene");
56 bool full_scene =
false;
59 int filename_index = 1;
61 if (strncmp(argv[1],
"--scene", 7) == 0)
69 rclcpp::executors::MultiThreadedExecutor executor;
70 executor.add_node(node);
72 rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr pub_scene;
73 rclcpp::Publisher<moveit_msgs::msg::PlanningSceneWorld>::SharedPtr pub_world_scene;
76 pub_scene = node->create_publisher<moveit_msgs::msg::PlanningScene>(
79 pub_world_scene = node->create_publisher<moveit_msgs::msg::PlanningSceneWorld>(
83 opt.robot_description_ =
"robot_description";
84 opt.load_kinematics_solvers_ =
false;
86 auto rml = std::make_shared<robot_model_loader::RobotModelLoader>(node,
opt);
89 std::ifstream
f(argv[filename_index]);
92 RCLCPP_INFO(LOGGER,
"Publishing geometry from '%s' ...", argv[filename_index]);
93 moveit_msgs::msg::PlanningScene ps_msg;
95 ps_msg.is_diff =
true;
97 unsigned int attempts = 0;
98 while (pub_scene->get_subscription_count() < 1 && ++attempts < 100)
99 rclcpp::sleep_for(500ms);
102 pub_scene->publish(ps_msg);
104 pub_world_scene->publish(ps_msg.world);
106 rclcpp::sleep_for(1s);
111 "A filename was expected as argument. That file should be a text representation of the geometry in a "
This class maintains the representation of the environment as seen by a planning instance....
void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene &scene) const
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed ...
bool loadGeometryFromStream(std::istream &in)
Load the geometry of the planning scene from a stream.
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
const rclcpp::Logger LOGGER
int main(int argc, char **argv)
Structure that encodes the options to be passed to the RobotModelLoader constructor.