40 #include <boost/program_options/cmdline.hpp> 
   41 #include <boost/program_options/options_description.hpp> 
   42 #include <boost/program_options/parsers.hpp> 
   43 #include <boost/program_options/variables_map.hpp> 
   56   for (
const moveit_msgs::PositionConstraint& position_constraint : constraints.position_constraints)
 
   59     const moveit_msgs::PositionConstraint& pc = position_constraint;
 
   60     lcp.first = pc.constraint_region.primitive_poses[0].position;
 
   61     lcmap[position_constraint.link_name] = lcp;
 
   64   for (
const moveit_msgs::OrientationConstraint& orientation_constraint : constraints.orientation_constraints)
 
   66     if (lcmap.count(orientation_constraint.link_name))
 
   68       lcmap[orientation_constraint.link_name].second = orientation_constraint.orientation;
 
   72       ROS_WARN(
"Orientation constraint for %s has no matching position constraint",
 
   73                orientation_constraint.link_name.c_str());
 
   78 int main(
int argc, 
char** argv)
 
   82   boost::program_options::options_description desc;
 
   83   desc.add_options()(
"help", 
"Show help message")(
"host", boost::program_options::value<std::string>(),
 
   85                                                   "DB.")(
"port", boost::program_options::value<std::size_t>(),
 
   88   boost::program_options::variables_map vm;
 
   89   boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
 
   90   boost::program_options::notify(vm);
 
   94     std::cout << desc << std::endl;
 
   98   auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
 
  100   if (vm.count(
"host") && vm.count(
"port"))
 
  101     conn->setParams(vm[
"host"].as<std::string>(), vm[
"port"].as<std::size_t>());
 
  102   if (!conn->connect())
 
  114   std::vector<std::string> scene_names;
 
  117   for (
const std::string& scene_name : scene_names)
 
  122       ROS_INFO(
"Saving scene '%s'", scene_name.c_str());
 
  123       psm.
getPlanningScene()->setPlanningSceneMsg(
static_cast<const moveit_msgs::PlanningScene&
>(*pswm));
 
  124       std::ofstream fout((scene_name + 
".scene").c_str());
 
  128       std::vector<std::string> robot_state_names;
 
  131       std::stringstream rsregex;
 
  132       rsregex << 
".*" << scene_name << 
".*";
 
  136       std::vector<std::string> constraint_names;
 
  138       std::stringstream csregex;
 
  139       csregex << 
".*" << scene_name << 
".*";
 
  142       if (!(robot_state_names.empty() && constraint_names.empty()))
 
  144         std::ofstream qfout((scene_name + 
".queries").c_str());
 
  145         qfout << scene_name << std::endl;
 
  146         if (!robot_state_names.empty())
 
  148           qfout << 
"start" << std::endl;
 
  149           qfout << robot_state_names.size() << std::endl;
 
  150           for (
const std::string& robot_state_name : robot_state_names)
 
  152             ROS_INFO(
"Saving start state %s for scene %s", robot_state_name.c_str(), scene_name.c_str());
 
  153             qfout << robot_state_name << std::endl;
 
  159             qfout << 
"." << std::endl;
 
  163         if (!constraint_names.empty())
 
  165           qfout << 
"goal" << std::endl;
 
  166           qfout << constraint_names.size() << std::endl;
 
  167           for (
const std::string& constraint_name : constraint_names)
 
  169             ROS_INFO(
"Saving goal %s for scene %s", constraint_name.c_str(), scene_name.c_str());
 
  170             qfout << 
"link_constraint" << std::endl;
 
  171             qfout << constraint_name << std::endl;
 
  177             for (std::pair<const std::string, LinkConstraintPair>& iter : lcmap)
 
  179               std::string link_name = iter.first;
 
  181               qfout << link_name << std::endl;
 
  182               qfout << 
"xyz " << lcp.first.x << 
" " << lcp.first.y << 
" " << lcp.first.z << std::endl;
 
  183               Eigen::Quaterniond orientation(lcp.second.w, lcp.second.x, lcp.second.y, lcp.second.z);
 
  184               Eigen::Vector3d rpy = orientation.matrix().eulerAngles(0, 1, 2);
 
  185               qfout << 
"rpy " << rpy[0] << 
" " << rpy[1] << 
" " << rpy[2] << std::endl;
 
  187             qfout << 
"." << std::endl;