moveit2
The MoveIt Motion Planning Framework for ROS 2.
save_to_warehouse.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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 
41 #include <boost/algorithm/string/join.hpp>
42 #include <boost/program_options/cmdline.hpp>
43 #include <boost/program_options/options_description.hpp>
44 #include <boost/program_options/parsers.hpp>
45 #include <boost/program_options/variables_map.hpp>
46 #include <tf2_ros/transform_listener.h>
47 #include <rclcpp/executors.hpp>
48 #include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
49 #include <rclcpp/logger.hpp>
50 #include <rclcpp/logging.hpp>
51 #include <rclcpp/node.hpp>
52 #include <rclcpp/node_options.hpp>
53 #include <rclcpp/qos_event.hpp>
54 #include <rclcpp/subscription.hpp>
55 #include <rclcpp/utilities.hpp>
56 
57 static const std::string ROBOT_DESCRIPTION = "robot_description";
58 
59 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.save_to_warehouse");
60 
62 {
63  RCLCPP_INFO(LOGGER, "Received an update to the planning scene...");
64 
65  if (!psm.getPlanningScene()->getName().empty())
66  {
67  if (!pss.hasPlanningScene(psm.getPlanningScene()->getName()))
68  {
69  moveit_msgs::msg::PlanningScene psmsg;
70  psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
71  pss.addPlanningScene(psmsg);
72  }
73  else
74  RCLCPP_INFO(LOGGER, "Scene '%s' was previously added. Not adding again.",
75  psm.getPlanningScene()->getName().c_str());
76  }
77  else
78  RCLCPP_INFO(LOGGER, "Scene name is empty. Not saving.");
79 }
80 
83 {
84  if (psm.getPlanningScene()->getName().empty())
85  {
86  RCLCPP_INFO(LOGGER, "Scene name is empty. Not saving planning request.");
87  return;
88  }
89  pss.addPlanningQuery(req, psm.getPlanningScene()->getName());
90 }
91 
92 void onConstraints(const moveit_msgs::msg::Constraints& msg, moveit_warehouse::ConstraintsStorage& cs)
93 {
94  if (msg.name.empty())
95  {
96  RCLCPP_INFO(LOGGER, "No name specified for constraints. Not saving.");
97  return;
98  }
99 
100  if (cs.hasConstraints(msg.name))
101  {
102  RCLCPP_INFO(LOGGER, "Replacing constraints '%s'", msg.name.c_str());
103  cs.removeConstraints(msg.name);
104  cs.addConstraints(msg);
105  }
106  else
107  {
108  RCLCPP_INFO(LOGGER, "Adding constraints '%s'", msg.name.c_str());
109  cs.addConstraints(msg);
110  }
111 }
112 
113 void onRobotState(const moveit_msgs::msg::RobotState& msg, moveit_warehouse::RobotStateStorage& rs)
114 {
115  std::vector<std::string> names;
116  rs.getKnownRobotStates(names);
117  std::set<std::string> names_set(names.begin(), names.end());
118  std::size_t n = names.size();
119  while (names_set.find("S" + std::to_string(n)) != names_set.end())
120  n++;
121  std::string name = "S" + std::to_string(n);
122  RCLCPP_INFO(LOGGER, "Adding robot state '%s'", name.c_str());
123  rs.addRobotState(msg, name);
124 }
125 
126 int main(int argc, char** argv)
127 {
128  rclcpp::init(argc, argv);
129  rclcpp::NodeOptions node_options;
130  node_options.allow_undeclared_parameters(true);
131  node_options.automatically_declare_parameters_from_overrides(true);
132  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("save_to_warehouse", node_options);
133 
134  boost::program_options::options_description desc;
135  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
136  "Host for the "
137  "DB.")("port", boost::program_options::value<std::size_t>(),
138  "Port for the DB.");
139 
140  boost::program_options::variables_map vm;
141  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
142  boost::program_options::notify(vm);
143 
144  if (vm.count("help"))
145  {
146  std::cout << desc << '\n';
147  return 1;
148  }
149  // Set up db
150  warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node);
151  if (vm.count("host") && vm.count("port"))
152  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
153  if (!conn->connect())
154  return 1;
155 
156  planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
157  if (!psm.getPlanningScene())
158  {
159  RCLCPP_ERROR(LOGGER, "Unable to initialize PlanningSceneMonitor");
160  return 1;
161  }
162 
163  psm.startSceneMonitor();
168  std::vector<std::string> names;
169  pss.getPlanningSceneNames(names);
170  if (names.empty())
171  RCLCPP_INFO(LOGGER, "There are no previously stored scenes");
172  else
173  {
174  RCLCPP_INFO(LOGGER, "Previously stored scenes:");
175  for (const std::string& name : names)
176  RCLCPP_INFO(LOGGER, " * %s", name.c_str());
177  }
178  cs.getKnownConstraints(names);
179  if (names.empty())
180  RCLCPP_INFO(LOGGER, "There are no previously stored constraints");
181  else
182  {
183  RCLCPP_INFO(LOGGER, "Previously stored constraints:");
184  for (const std::string& name : names)
185  RCLCPP_INFO(LOGGER, " * %s", name.c_str());
186  }
187  rs.getKnownRobotStates(names);
188  if (names.empty())
189  RCLCPP_INFO(LOGGER, "There are no previously stored robot states");
190  else
191  {
192  RCLCPP_INFO(LOGGER, "Previously stored robot states:");
193  for (const std::string& name : names)
194  RCLCPP_INFO(LOGGER, " * %s", name.c_str());
195  }
196 
197  psm.addUpdateCallback([&](auto&&) { return onSceneUpdate(psm, pss); });
198 
199  auto mplan_req_sub = node->create_subscription<moveit_msgs::msg::MotionPlanRequest>(
200  "motion_plan_request", rclcpp::SystemDefaultsQoS(),
201  [&](const moveit_msgs::msg::MotionPlanRequest& msg) { onMotionPlanRequest(msg, psm, pss); });
202  auto constr_sub = node->create_subscription<moveit_msgs::msg::Constraints>(
203  "constraints", rclcpp::SystemDefaultsQoS(),
204  [&](const moveit_msgs::msg::Constraints& msg) { onConstraints(msg, cs); });
205  auto state_sub = node->create_subscription<moveit_msgs::msg::RobotState>(
206  "robot_state", rclcpp::SystemDefaultsQoS(),
207  [&](const moveit_msgs::msg::RobotState& msg) { onRobotState(msg, rs); });
208 
209  std::vector<std::string> topics;
210  psm.getMonitoredTopics(topics);
211  RCLCPP_INFO_STREAM(LOGGER, "Listening for scene updates on topics " << boost::algorithm::join(topics, ", "));
212  RCLCPP_INFO_STREAM(LOGGER, "Listening for planning requests on topic " << mplan_req_sub->get_topic_name());
213  RCLCPP_INFO_STREAM(LOGGER, "Listening for named constraints on topic " << constr_sub->get_topic_name());
214  RCLCPP_INFO_STREAM(LOGGER, "Listening for states on topic " << state_sub->get_topic_name());
215 
216  rclcpp::spin(node);
217  return 0;
218 }
void removeConstraints(const std::string &name, const std::string &robot="", const std::string &group="")
bool hasConstraints(const std::string &name, const std::string &robot="", const std::string &group="") const
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
void addConstraints(const moveit_msgs::msg::Constraints &msg, const std::string &robot="", const std::string &group="")
void addPlanningQuery(const moveit_msgs::msg::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="")
void addPlanningScene(const moveit_msgs::msg::PlanningScene &scene)
void getPlanningSceneNames(std::vector< std::string > &names) const
bool hasPlanningScene(const std::string &name) const
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
void addRobotState(const moveit_msgs::msg::RobotState &msg, const std::string &name, const std::string &robot="")
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 addUpdateCallback(const std::function< void(SceneUpdateType)> &fn)
Add a function to be called when an update to the scene is received.
void getMonitoredTopics(std::vector< std::string > &topics) const
Get the topic names that the monitor is listening to.
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:
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31
void onRobotState(const moveit_msgs::msg::RobotState &msg, moveit_warehouse::RobotStateStorage &rs)
int main(int argc, char **argv)
void onSceneUpdate(planning_scene_monitor::PlanningSceneMonitor &psm, moveit_warehouse::PlanningSceneStorage &pss)
void onMotionPlanRequest(const moveit_msgs::msg::MotionPlanRequest &req, planning_scene_monitor::PlanningSceneMonitor &psm, moveit_warehouse::PlanningSceneStorage &pss)
void onConstraints(const moveit_msgs::msg::Constraints &msg, moveit_warehouse::ConstraintsStorage &cs)