moveit2
The MoveIt Motion Planning Framework for ROS 2.
publish_scene_from_text.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Ioan A. Sucan nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #include <chrono>
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>
46 
47 using namespace std::chrono_literals;
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger("publish_scene_from_text");
49 
50 int main(int argc, char** argv)
51 {
52  rclcpp::init(argc, argv);
53  auto node = rclcpp::Node::make_shared("publish_planning_scene");
54 
55  // decide whether to publish the full scene
56  bool full_scene = false;
57 
58  // the index of the argument with the filename
59  int filename_index = 1;
60  if (argc > 2)
61  if (strncmp(argv[1], "--scene", 7) == 0)
62  {
63  full_scene = true;
64  filename_index = 2;
65  }
66 
67  if (argc > 1)
68  {
69  rclcpp::executors::MultiThreadedExecutor executor;
70  executor.add_node(node);
71 
72  rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr pub_scene;
73  rclcpp::Publisher<moveit_msgs::msg::PlanningSceneWorld>::SharedPtr pub_world_scene;
74 
75  if (full_scene)
76  pub_scene = node->create_publisher<moveit_msgs::msg::PlanningScene>(
78  else
79  pub_world_scene = node->create_publisher<moveit_msgs::msg::PlanningSceneWorld>(
81 
83  opt.robot_description_ = "robot_description";
84  opt.load_kinematics_solvers_ = false;
85 
86  auto rml = std::make_shared<robot_model_loader::RobotModelLoader>(node, opt);
87  planning_scene::PlanningScene ps(rml->getModel());
88 
89  std::ifstream f(argv[filename_index]);
90  if (ps.loadGeometryFromStream(f))
91  {
92  RCLCPP_INFO(LOGGER, "Publishing geometry from '%s' ...", argv[filename_index]);
93  moveit_msgs::msg::PlanningScene ps_msg;
94  ps.getPlanningSceneMsg(ps_msg);
95  ps_msg.is_diff = true;
96 
97  unsigned int attempts = 0;
98  while (pub_scene->get_subscription_count() < 1 && ++attempts < 100)
99  rclcpp::sleep_for(500ms);
100 
101  if (full_scene)
102  pub_scene->publish(ps_msg);
103  else
104  pub_world_scene->publish(ps_msg.world);
105 
106  rclcpp::sleep_for(1s);
107  }
108  }
109  else
110  RCLCPP_WARN(LOGGER,
111  "A filename was expected as argument. That file should be a text representation of the geometry in a "
112  "planning scene.");
113 
114  rclcpp::shutdown();
115  return 0;
116 }
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.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
int main(int argc, char **argv)
Structure that encodes the options to be passed to the RobotModelLoader constructor.