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);
146 boost::program_options::options_description desc;
147 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
149 "DB.")(
"port", boost::program_options::value<std::size_t>(),
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);
156 if (vm.count(
"help"))
158 std::cout << desc <<
'\n';
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())
171 RCLCPP_ERROR(node->get_logger(),
"Unable to initialize PlanningSceneMonitor");
180 std::vector<std::string> names;
184 RCLCPP_INFO(node->get_logger(),
"There are no previously stored scenes");
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());
195 RCLCPP_INFO(node->get_logger(),
"There are no previously stored constraints");
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());
206 RCLCPP_INFO(node->get_logger(),
"There are no previously stored robot states");
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());
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); });
227 std::vector<std::string> 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());