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