44 #include <boost/algorithm/string/join.hpp> 
   45 #include <boost/program_options/cmdline.hpp> 
   46 #include <boost/program_options/options_description.hpp> 
   47 #include <boost/program_options/parsers.hpp> 
   48 #include <boost/program_options/variables_map.hpp> 
   49 #include <boost/math/constants/constants.hpp> 
   54 int main(
int argc, 
char** argv)
 
   58   boost::program_options::options_description desc;
 
   59   desc.add_options()(
"help", 
"Show help message")(
"host", boost::program_options::value<std::string>(),
 
   61                                                   "DB.")(
"port", boost::program_options::value<std::size_t>(),
 
   64   boost::program_options::variables_map vm;
 
   65   boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
 
   66   boost::program_options::notify(vm);
 
   70     std::cout << desc << std::endl;
 
   74   auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
 
   76   if (vm.count(
"host") && vm.count(
"port"))
 
   77     conn->setParams(vm[
"host"].as<std::string>(), vm[
"port"].as<std::size_t>());
 
   88     ROS_ERROR(
"Unable to initialize PlanningSceneMonitor");
 
  100   moveit_msgs::PlanningScene psmsg;
 
  102   psmsg.name = 
"default";
 
  104   ROS_INFO(
"Added default scene: '%s'", psmsg.name.c_str());
 
  106   moveit_msgs::RobotState rsmsg;
 
  111   const std::vector<std::string>& gnames = psm.
getRobotModel()->getJointModelGroupNames();
 
  112   for (
const std::string& gname : gnames)
 
  121     moveit_msgs::OrientationConstraint ocm;
 
  122     ocm.link_name = lnames.back();
 
  124     ocm.orientation.x = 0.0;
 
  125     ocm.orientation.y = 0.0;
 
  126     ocm.orientation.z = 0.0;
 
  127     ocm.orientation.w = 1.0;
 
  128     ocm.absolute_x_axis_tolerance = 0.1;
 
  129     ocm.absolute_y_axis_tolerance = 0.1;
 
  130     ocm.absolute_z_axis_tolerance = boost::math::constants::pi<double>();
 
  132     moveit_msgs::Constraints cmsg;
 
  133     cmsg.orientation_constraints.resize(1, ocm);
 
  134     cmsg.name = ocm.link_name + 
":upright";
 
  136     ROS_INFO(
"Added default constraint: '%s'", cmsg.name.c_str());
 
  138   ROS_INFO(
"Default MoveIt Warehouse was reset.");