moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
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 <fmt/format.h>
47#include <tf2_ros/transform_listener.h>
48#include <rclcpp/executors.hpp>
49#include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
50#include <rclcpp/logger.hpp>
51#include <rclcpp/logging.hpp>
52#include <rclcpp/node.hpp>
53#include <rclcpp/node_options.hpp>
54#include <rclcpp/version.h>
55#if RCLCPP_VERSION_GTE(20, 0, 0)
56#include <rclcpp/event_handler.hpp>
57#else
58#include <rclcpp/qos_event.hpp>
59#endif
60#include <rclcpp/subscription.hpp>
61#include <rclcpp/utilities.hpp>
62
63rclcpp::Logger getLogger()
64{
65 return moveit::getLogger("moveit.ros.save_to_warehouse");
66}
67
68static const std::string ROBOT_DESCRIPTION = "robot_description";
69
71{
72 RCLCPP_INFO(getLogger(), "Received an update to the planning scene...");
73
74 if (!psm.getPlanningScene()->getName().empty())
75 {
76 if (!pss.hasPlanningScene(psm.getPlanningScene()->getName()))
77 {
78 moveit_msgs::msg::PlanningScene psmsg;
79 psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
80 pss.addPlanningScene(psmsg);
81 }
82 else
83 {
84 RCLCPP_INFO(getLogger(), "Scene '%s' was previously added. Not adding again.",
85 psm.getPlanningScene()->getName().c_str());
86 }
87 }
88 else
89 RCLCPP_INFO(getLogger(), "Scene name is empty. Not saving.");
90}
91
92void onMotionPlanRequest(const moveit_msgs::msg::MotionPlanRequest& req,
94{
95 if (psm.getPlanningScene()->getName().empty())
96 {
97 RCLCPP_INFO(getLogger(), "Scene name is empty. Not saving planning request.");
98 return;
99 }
100 pss.addPlanningQuery(req, psm.getPlanningScene()->getName());
101}
102
103void onConstraints(const moveit_msgs::msg::Constraints& msg, moveit_warehouse::ConstraintsStorage& cs)
104{
105 if (msg.name.empty())
106 {
107 RCLCPP_INFO(getLogger(), "No name specified for constraints. Not saving.");
108 return;
109 }
110
111 if (cs.hasConstraints(msg.name))
112 {
113 RCLCPP_INFO(getLogger(), "Replacing constraints '%s'", msg.name.c_str());
114 cs.removeConstraints(msg.name);
115 cs.addConstraints(msg);
116 }
117 else
118 {
119 RCLCPP_INFO(getLogger(), "Adding constraints '%s'", msg.name.c_str());
120 cs.addConstraints(msg);
121 }
122}
123
124void onRobotState(const moveit_msgs::msg::RobotState& msg, moveit_warehouse::RobotStateStorage& rs)
125{
126 std::vector<std::string> names;
127 rs.getKnownRobotStates(names);
128 std::set<std::string> names_set(names.begin(), names.end());
129 std::size_t n = names.size();
130 while (names_set.find("S" + std::to_string(n)) != names_set.end())
131 n++;
132 std::string name = "S" + std::to_string(n);
133 RCLCPP_INFO(getLogger(), "Adding robot state '%s'", name.c_str());
134 rs.addRobotState(msg, name);
135}
136
137int main(int argc, char** argv)
138{
139 rclcpp::init(argc, argv);
140 rclcpp::NodeOptions node_options;
141 node_options.allow_undeclared_parameters(true);
142 node_options.automatically_declare_parameters_from_overrides(true);
143 rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("save_to_warehouse", node_options);
144 moveit::setNodeLoggerName(node->get_name());
145
146 boost::program_options::options_description desc;
147 desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
148 "Host for the "
149 "DB.")("port", boost::program_options::value<std::size_t>(),
150 "Port for the DB.");
151
152 boost::program_options::variables_map vm;
153 boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
154 boost::program_options::notify(vm);
155
156 if (vm.count("help"))
157 {
158 std::cout << desc << '\n';
159 return 1;
160 }
161 // Set up db
162 warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node);
163 if (vm.count("host") && vm.count("port"))
164 conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
165 if (!conn->connect())
166 return 1;
167
168 planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
169 if (!psm.getPlanningScene())
170 {
171 RCLCPP_ERROR(node->get_logger(), "Unable to initialize PlanningSceneMonitor");
172 return 1;
173 }
174
175 psm.startSceneMonitor();
180 std::vector<std::string> names;
181 pss.getPlanningSceneNames(names);
182 if (names.empty())
183 {
184 RCLCPP_INFO(node->get_logger(), "There are no previously stored scenes");
185 }
186 else
187 {
188 RCLCPP_INFO(node->get_logger(), "Previously stored scenes:");
189 for (const std::string& name : names)
190 RCLCPP_INFO(node->get_logger(), " * %s", name.c_str());
191 }
192 cs.getKnownConstraints(names);
193 if (names.empty())
194 {
195 RCLCPP_INFO(node->get_logger(), "There are no previously stored constraints");
196 }
197 else
198 {
199 RCLCPP_INFO(node->get_logger(), "Previously stored constraints:");
200 for (const std::string& name : names)
201 RCLCPP_INFO(node->get_logger(), " * %s", name.c_str());
202 }
203 rs.getKnownRobotStates(names);
204 if (names.empty())
205 {
206 RCLCPP_INFO(node->get_logger(), "There are no previously stored robot states");
207 }
208 else
209 {
210 RCLCPP_INFO(node->get_logger(), "Previously stored robot states:");
211 for (const std::string& name : names)
212 RCLCPP_INFO(node->get_logger(), " * %s", name.c_str());
213 }
214
215 psm.addUpdateCallback([&](auto&&) { return onSceneUpdate(psm, pss); });
216
217 auto mplan_req_sub = node->create_subscription<moveit_msgs::msg::MotionPlanRequest>(
218 "motion_plan_request", rclcpp::SystemDefaultsQoS(),
219 [&](const moveit_msgs::msg::MotionPlanRequest& msg) { onMotionPlanRequest(msg, psm, pss); });
220 auto constr_sub = node->create_subscription<moveit_msgs::msg::Constraints>(
221 "constraints", rclcpp::SystemDefaultsQoS(),
222 [&](const moveit_msgs::msg::Constraints& msg) { onConstraints(msg, cs); });
223 auto state_sub = node->create_subscription<moveit_msgs::msg::RobotState>(
224 "robot_state", rclcpp::SystemDefaultsQoS(),
225 [&](const moveit_msgs::msg::RobotState& msg) { onRobotState(msg, rs); });
226
227 std::vector<std::string> topics;
228 psm.getMonitoredTopics(topics);
229 RCLCPP_INFO_STREAM(node->get_logger(),
230 "Listening for scene updates on topics " << fmt::format("{}", fmt::join(topics, ", ")));
231 RCLCPP_INFO_STREAM(node->get_logger(), "Listening for planning requests on topic " << mplan_req_sub->get_topic_name());
232 RCLCPP_INFO_STREAM(node->get_logger(), "Listening for named constraints on topic " << constr_sub->get_topic_name());
233 RCLCPP_INFO_STREAM(node->get_logger(), "Listening for states on topic " << state_sub->get_topic_name());
234
235 rclcpp::spin(node);
236 return 0;
237}
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.
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:
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition logger.cpp:73
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)
rclcpp::Logger getLogger()
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)