44 #include <boost/program_options/cmdline.hpp> 
   45 #include <boost/program_options/options_description.hpp> 
   46 #include <boost/program_options/parsers.hpp> 
   47 #include <boost/program_options/variables_map.hpp> 
   58   if (in.good() && !in.eof())
 
   60     for (
int i = 0; i < count; ++i)
 
   62       std::map<std::string, double> v;
 
   65       if (in.good() && !in.eof())
 
   71         while (joint != 
"." && in.good() && !in.eof())
 
   89         moveit_msgs::RobotState msg;
 
  101   Eigen::Translation3d pos(Eigen::Vector3d::Zero());
 
  102   Eigen::Quaterniond rot(Eigen::Quaterniond::Identity());
 
  104   bool have_position = 
false;
 
  105   bool have_orientation = 
false;
 
  108   std::getline(in, 
name);
 
  111   std::string link_name;
 
  112   std::getline(in, link_name);
 
  117   while (type != 
"." && in.good() && !in.eof())
 
  121       have_position = 
true;
 
  124       pos = Eigen::Translation3d(
x, 
y, 
z);
 
  126     else if (type == 
"rpy")
 
  128       have_orientation = 
true;
 
  131       rot = Eigen::Quaterniond(Eigen::AngleAxisd(
r, Eigen::Vector3d::UnitX()) *
 
  132                                Eigen::AngleAxisd(p, Eigen::Vector3d::UnitY()) *
 
  133                                Eigen::AngleAxisd(
y, Eigen::Vector3d::UnitZ()));
 
  136       ROS_ERROR(
"Unknown link constraint element: '%s'", type.c_str());
 
  141   std::string end_link;
 
  142   std::getline(in, end_link);
 
  144   if (have_position && have_orientation)
 
  146     geometry_msgs::PoseStamped pose;
 
  148     pose.header.frame_id = psm->
getRobotModel()->getModelFrame();
 
  163   std::string end_link;
 
  164   std::getline(in, end_link);
 
  166   if (in.good() && !in.eof())
 
  168     for (
int i = 0; i < count; ++i)
 
  171       std::getline(in, type);
 
  173       if (in.good() && !in.eof())
 
  175         if (type == 
"link_constraint")
 
  178           ROS_ERROR(
"Unknown goal type: '%s'", type.c_str());
 
  187   std::string scene_name;
 
  189   while (in.good() && !in.eof())
 
  194     if (in.good() && !in.eof())
 
  198       else if (type == 
"goal")
 
  201         ROS_ERROR(
"Unknown query type: '%s'", type.c_str());
 
  206 int main(
int argc, 
char** argv)
 
  210   boost::program_options::options_description desc;
 
  211   desc.add_options()(
"help", 
"Show help message")(
"queries", boost::program_options::value<std::string>(),
 
  212                                                   "Name of file containing motion planning queries.")(
 
  213       "scene", boost::program_options::value<std::string>(), 
"Name of file containing motion planning scene.")(
 
  214       "host", boost::program_options::value<std::string>(),
 
  215       "Host for the DB.")(
"port", boost::program_options::value<std::size_t>(), 
"Port for the DB.");
 
  217   boost::program_options::variables_map vm;
 
  218   boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
 
  219   boost::program_options::notify(vm);
 
  221   if (vm.count(
"help") || argc == 1)  
 
  223     std::cout << desc << std::endl;
 
  227   auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
 
  229   if (vm.count(
"host") && vm.count(
"port"))
 
  230     conn->setParams(vm[
"host"].as<std::string>(), vm[
"port"].as<std::size_t>());
 
  231   if (!conn->connect())
 
  241     ROS_ERROR(
"Unable to initialize PlanningSceneMonitor");
 
  249   if (vm.count(
"scene"))
 
  251     std::ifstream fin(vm[
"scene"].as<std::string>().c_str());
 
  254     moveit_msgs::PlanningScene psmsg;
 
  259   if (vm.count(
"queries"))
 
  261     std::ifstream fin(vm[
"queries"].as<std::string>().c_str());
 
  262     if (fin.good() && !fin.eof())