59int main(
int argc,
char** argv)
61 rclcpp::init(argc, argv);
62 rclcpp::NodeOptions node_options;
63 node_options.allow_undeclared_parameters(
true);
64 node_options.automatically_declare_parameters_from_overrides(
true);
65 rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"initialize_demo_db", node_options);
68 boost::program_options::options_description desc;
69 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
71 "DB.")(
"port", boost::program_options::value<std::size_t>(),
74 boost::program_options::variables_map vm;
75 boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
76 boost::program_options::notify(vm);
80 std::cout << desc <<
'\n';
85 if (vm.count(
"host") && vm.count(
"port"))
86 conn->setParams(vm[
"host"].as<std::string>(), vm[
"port"].as<std::size_t>());
93 RCLCPP_ERROR(node->get_logger(),
"Unable to initialize PlanningSceneMonitor");
105 moveit_msgs::msg::PlanningScene psmsg;
107 psmsg.name =
"default";
109 RCLCPP_INFO(node->get_logger(),
"Added default scene: '%s'", psmsg.name.c_str());
111 moveit_msgs::msg::RobotState rsmsg;
114 RCLCPP_INFO(node->get_logger(),
"Added default state");
116 const std::vector<std::string>& gnames = psm.
getRobotModel()->getJointModelGroupNames();
117 for (
const std::string& gname : gnames)
126 moveit_msgs::msg::OrientationConstraint ocm;
127 ocm.link_name = lnames.back();
129 ocm.orientation.x = 0.0;
130 ocm.orientation.y = 0.0;
131 ocm.orientation.z = 0.0;
132 ocm.orientation.w = 1.0;
133 ocm.absolute_x_axis_tolerance = 0.1;
134 ocm.absolute_y_axis_tolerance = 0.1;
135 ocm.absolute_z_axis_tolerance = M_PI;
137 moveit_msgs::msg::Constraints cmsg;
138 cmsg.orientation_constraints.resize(1, ocm);
139 cmsg.name = ocm.link_name +
":upright";
141 RCLCPP_INFO(node->get_logger(),
"Added default constraint: '%s'", cmsg.name.c_str());
143 RCLCPP_INFO(node->get_logger(),
"Default MoveIt Warehouse was reset.");