initialize_demo_db.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/warehouse/planning_scene_storage.h>
00038 #include <moveit/warehouse/constraints_storage.h>
00039 #include <moveit/warehouse/state_storage.h>
00040 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00041 #include <moveit/robot_state/conversions.h>
00042 #include <moveit/kinematic_constraints/utils.h>
00043 #include <boost/algorithm/string/join.hpp>
00044 #include <boost/program_options/cmdline.hpp>
00045 #include <boost/program_options/options_description.hpp>
00046 #include <boost/program_options/parsers.hpp>
00047 #include <boost/program_options/variables_map.hpp>
00048 #include <boost/math/constants/constants.hpp>
00049 #include <ros/ros.h>
00050 
00051 static const std::string ROBOT_DESCRIPTION = "robot_description";
00052 
00053 int main(int argc, char** argv)
00054 {
00055   ros::init(argc, argv, "initialize_demo_db", ros::init_options::AnonymousName);
00056 
00057   boost::program_options::options_description desc;
00058   desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(), "Host for the "
00059                                                                                                         "MongoDB.")(
00060       "port", boost::program_options::value<std::size_t>(), "Port for the MongoDB.");
00061 
00062   boost::program_options::variables_map vm;
00063   boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
00064   boost::program_options::notify(vm);
00065 
00066   if (vm.count("help"))
00067   {
00068     std::cout << desc << std::endl;
00069     return 1;
00070   }
00071 
00072   ros::AsyncSpinner spinner(1);
00073   spinner.start();
00074 
00075   ros::NodeHandle nh;
00076   planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00077   if (!psm.getPlanningScene())
00078   {
00079     ROS_ERROR("Unable to initialize PlanningSceneMonitor");
00080     return 1;
00081   }
00082 
00083   bool done = false;
00084   unsigned int attempts = 0;
00085   while (!done && attempts < 5)
00086   {
00087     attempts++;
00088     try
00089     {
00090       moveit_warehouse::PlanningSceneStorage pss(vm.count("host") ? vm["host"].as<std::string>() : "",
00091                                                  vm.count("port") ? vm["port"].as<std::size_t>() : 0);
00092       moveit_warehouse::ConstraintsStorage cs(vm.count("host") ? vm["host"].as<std::string>() : "",
00093                                               vm.count("port") ? vm["port"].as<std::size_t>() : 0);
00094       moveit_warehouse::RobotStateStorage rs(vm.count("host") ? vm["host"].as<std::string>() : "",
00095                                              vm.count("port") ? vm["port"].as<std::size_t>() : 0);
00096       pss.reset();
00097       cs.reset();
00098       rs.reset();
00099 
00100       // add default planning scenes
00101       moveit_msgs::PlanningScene psmsg;
00102       psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
00103       psmsg.name = "default";
00104       pss.addPlanningScene(psmsg);
00105       ROS_INFO("Added default scene: '%s'", psmsg.name.c_str());
00106 
00107       moveit_msgs::RobotState rsmsg;
00108       robot_state::robotStateToRobotStateMsg(psm.getPlanningScene()->getCurrentState(), rsmsg);
00109       rs.addRobotState(rsmsg, "default");
00110       ROS_INFO("Added default state");
00111 
00112       const std::vector<std::string>& gnames = psm.getRobotModel()->getJointModelGroupNames();
00113       for (std::size_t i = 0; i < gnames.size(); ++i)
00114       {
00115         const robot_model::JointModelGroup* jmg = psm.getRobotModel()->getJointModelGroup(gnames[i]);
00116         if (!jmg->isChain())
00117           continue;
00118         const std::vector<std::string>& lnames = jmg->getLinkModelNames();
00119         if (lnames.empty())
00120           continue;
00121 
00122         moveit_msgs::OrientationConstraint ocm;
00123         ocm.link_name = lnames.back();
00124         ocm.header.frame_id = psm.getRobotModel()->getModelFrame();
00125         ocm.orientation.x = 0.0;
00126         ocm.orientation.y = 0.0;
00127         ocm.orientation.z = 0.0;
00128         ocm.orientation.w = 1.0;
00129         ocm.absolute_x_axis_tolerance = 0.1;
00130         ocm.absolute_y_axis_tolerance = 0.1;
00131         ocm.absolute_z_axis_tolerance = boost::math::constants::pi<double>();
00132         ocm.weight = 1.0;
00133         moveit_msgs::Constraints cmsg;
00134         cmsg.orientation_constraints.resize(1, ocm);
00135         cmsg.name = ocm.link_name + ":upright";
00136         cs.addConstraints(cmsg, psm.getRobotModel()->getName(), jmg->getName());
00137         ROS_INFO("Added default constraint: '%s'", cmsg.name.c_str());
00138       }
00139       done = true;
00140       ROS_INFO("Default MoveIt! Warehouse was reset. Done.");
00141     }
00142     catch (mongo_ros::DbConnectException& ex)
00143     {
00144       ROS_WARN("MongoDB does not appear to be initialized yet. Waiting for a few seconds before trying again ...");
00145       ros::WallDuration(15.0).sleep();
00146     }
00147   }
00148 
00149   ros::shutdown();
00150 
00151   return 0;
00152 }


warehouse
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:47