initialize_demo_db.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
43 #include <boost/algorithm/string/join.hpp>
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>
48 #include <boost/math/constants/constants.hpp>
49 #include <ros/ros.h>
50 
51 static const std::string ROBOT_DESCRIPTION = "robot_description";
52 
53 int main(int argc, char** argv)
54 {
55  ros::init(argc, argv, "initialize_demo_db", ros::init_options::AnonymousName);
56 
57  boost::program_options::options_description desc;
58  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(), "Host for the "
59  "DB.")(
60  "port", boost::program_options::value<std::size_t>(), "Port for the DB.");
61 
62  boost::program_options::variables_map vm;
63  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
64  boost::program_options::notify(vm);
65 
66  if (vm.count("help"))
67  {
68  std::cout << desc << std::endl;
69  return 1;
70  }
71  // Set up db
73  if (vm.count("host") && vm.count("port"))
74  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
75  if (!conn->connect())
76  return 1;
77 
79  spinner.start();
80 
81  ros::NodeHandle nh;
83  if (!psm.getPlanningScene())
84  {
85  ROS_ERROR("Unable to initialize PlanningSceneMonitor");
86  return 1;
87  }
88 
92  pss.reset();
93  cs.reset();
94  rs.reset();
95 
96  // add default planning scenes
97  moveit_msgs::PlanningScene psmsg;
98  psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
99  psmsg.name = "default";
100  pss.addPlanningScene(psmsg);
101  ROS_INFO("Added default scene: '%s'", psmsg.name.c_str());
102 
103  moveit_msgs::RobotState rsmsg;
104  robot_state::robotStateToRobotStateMsg(psm.getPlanningScene()->getCurrentState(), rsmsg);
105  rs.addRobotState(rsmsg, "default");
106  ROS_INFO("Added default state");
107 
108  const std::vector<std::string>& gnames = psm.getRobotModel()->getJointModelGroupNames();
109  for (std::size_t i = 0; i < gnames.size(); ++i)
110  {
111  const robot_model::JointModelGroup* jmg = psm.getRobotModel()->getJointModelGroup(gnames[i]);
112  if (!jmg->isChain())
113  continue;
114  const std::vector<std::string>& lnames = jmg->getLinkModelNames();
115  if (lnames.empty())
116  continue;
117 
118  moveit_msgs::OrientationConstraint ocm;
119  ocm.link_name = lnames.back();
120  ocm.header.frame_id = psm.getRobotModel()->getModelFrame();
121  ocm.orientation.x = 0.0;
122  ocm.orientation.y = 0.0;
123  ocm.orientation.z = 0.0;
124  ocm.orientation.w = 1.0;
125  ocm.absolute_x_axis_tolerance = 0.1;
126  ocm.absolute_y_axis_tolerance = 0.1;
127  ocm.absolute_z_axis_tolerance = boost::math::constants::pi<double>();
128  ocm.weight = 1.0;
129  moveit_msgs::Constraints cmsg;
130  cmsg.orientation_constraints.resize(1, ocm);
131  cmsg.name = ocm.link_name + ":upright";
132  cs.addConstraints(cmsg, psm.getRobotModel()->getName(), jmg->getName());
133  ROS_INFO("Added default constraint: '%s'", cmsg.name.c_str());
134  }
135  ROS_INFO("Default MoveIt! Warehouse was reset.");
136 
137  ros::shutdown();
138 
139  return 0;
140 }
void addRobotState(const moveit_msgs::RobotState &msg, const std::string &name, const std::string &robot="")
void addConstraints(const moveit_msgs::Constraints &msg, const std::string &robot="", const std::string &group="")
static const std::string ROBOT_DESCRIPTION
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const robot_model::RobotModelConstPtr & getRobotModel() const
void spinner()
const planning_scene::PlanningScenePtr & getPlanningScene()
warehouse_ros::DatabaseConnection::Ptr loadDatabase()
Load a database connection.
#define ROS_INFO(...)
void addPlanningScene(const moveit_msgs::PlanningScene &scene)
ROSCPP_DECL void shutdown()
#define ROS_ERROR(...)
int main(int argc, char **argv)


warehouse
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:37