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);
153 boost::program_options::options_description desc;
154 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
156 "DB.")(
"port", boost::program_options::value<std::size_t>(),
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);
163 if (vm.count(
"help"))
165 std::cout << desc <<
'\n';
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())
178 RCLCPP_ERROR(node->get_logger(),
"Unable to initialize PlanningSceneMonitor");
187 std::vector<std::string> names;
191 RCLCPP_INFO(node->get_logger(),
"There are no previously stored scenes");
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());
202 RCLCPP_INFO(node->get_logger(),
"There are no previously stored constraints");
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());
213 RCLCPP_INFO(node->get_logger(),
"There are no previously stored robot states");
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());
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); });
234 std::vector<std::string> 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());