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 
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>
50 #include <ros/ros.h>
51 
52 static const std::string ROBOT_DESCRIPTION = "robot_description";
53 
54 int main(int argc, char** argv)
55 {
56  ros::init(argc, argv, "initialize_demo_db", ros::init_options::AnonymousName);
57 
58  boost::program_options::options_description desc;
59  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
60  "Host for the "
61  "DB.")("port", boost::program_options::value<std::size_t>(),
62  "Port for the DB.");
63 
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);
67 
68  if (vm.count("help"))
69  {
70  std::cout << desc << std::endl;
71  return 1;
72  }
73  // Set up db
74  auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
75  warehouse_ros::DatabaseConnection::Ptr conn = db_loader->loadDatabase();
76  if (vm.count("host") && vm.count("port"))
77  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
78  if (!conn->connect())
79  return 1;
80 
82  spinner.start();
83 
84  ros::NodeHandle nh;
86  if (!psm.getPlanningScene())
87  {
88  ROS_ERROR("Unable to initialize PlanningSceneMonitor");
89  return 1;
90  }
91 
95  pss.reset();
96  cs.reset();
97  rs.reset();
98 
99  // add default planning scenes
100  moveit_msgs::PlanningScene psmsg;
101  psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
102  psmsg.name = "default";
103  pss.addPlanningScene(psmsg);
104  ROS_INFO("Added default scene: '%s'", psmsg.name.c_str());
105 
106  moveit_msgs::RobotState rsmsg;
107  moveit::core::robotStateToRobotStateMsg(psm.getPlanningScene()->getCurrentState(), rsmsg);
108  rs.addRobotState(rsmsg, "default");
109  ROS_INFO("Added default state");
110 
111  const std::vector<std::string>& gnames = psm.getRobotModel()->getJointModelGroupNames();
112  for (const std::string& gname : gnames)
113  {
114  const moveit::core::JointModelGroup* jmg = psm.getRobotModel()->getJointModelGroup(gname);
115  if (!jmg->isChain())
116  continue;
117  const std::vector<std::string>& lnames = jmg->getLinkModelNames();
118  if (lnames.empty())
119  continue;
120 
121  moveit_msgs::OrientationConstraint ocm;
122  ocm.link_name = lnames.back();
123  ocm.header.frame_id = psm.getRobotModel()->getModelFrame();
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>();
131  ocm.weight = 1.0;
132  moveit_msgs::Constraints cmsg;
133  cmsg.orientation_constraints.resize(1, ocm);
134  cmsg.name = ocm.link_name + ":upright";
135  cs.addConstraints(cmsg, psm.getRobotModel()->getName(), jmg->getName());
136  ROS_INFO("Added default constraint: '%s'", cmsg.name.c_str());
137  }
138  ROS_INFO("Default MoveIt Warehouse was reset.");
139 
140  ros::shutdown();
141 
142  return 0;
143 }
ros::init_options::AnonymousName
AnonymousName
boost::shared_ptr
moveit_warehouse::RobotStateStorage
Definition: state_storage.h:82
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
utils.h
ros.h
moveit_warehouse::RobotStateStorage::addRobotState
void addRobotState(const moveit_msgs::RobotState &msg, const std::string &name, const std::string &robot="")
Definition: state_storage.cpp:67
state_storage.h
ros::AsyncSpinner
ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: initialize_demo_db.cpp:52
ros::shutdown
ROSCPP_DECL void shutdown()
planning_scene_monitor::PlanningSceneMonitor::getPlanningScene
const planning_scene::PlanningScenePtr & getPlanningScene()
moveit_warehouse::ConstraintsStorage
Definition: constraints_storage.h:82
moveit_warehouse::PlanningSceneStorage::addPlanningScene
void addPlanningScene(const moveit_msgs::PlanningScene &scene)
Definition: planning_scene_storage.cpp:73
planning_scene_monitor::PlanningSceneMonitor
database_loader.h
spinner
void spinner()
moveit::core::JointModelGroup::getName
const std::string & getName() const
main
int main(int argc, char **argv)
Definition: initialize_demo_db.cpp:54
planning_scene_monitor::PlanningSceneMonitor::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
planning_scene_monitor.h
planning_scene_storage.h
constraints_storage.h
ROS_ERROR
#define ROS_ERROR(...)
moveit_warehouse::PlanningSceneStorage
Definition: planning_scene_storage.h:89
moveit_warehouse::ConstraintsStorage::addConstraints
void addConstraints(const moveit_msgs::Constraints &msg, const std::string &robot="", const std::string &group="")
Definition: constraints_storage.cpp:68
moveit::core::JointModelGroup::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
moveit_warehouse::ConstraintsStorage::reset
void reset()
Definition: constraints_storage.cpp:61
moveit::core::JointModelGroup::isChain
bool isChain() const
moveit::core::JointModelGroup
moveit_warehouse::RobotStateStorage::reset
void reset()
Definition: state_storage.cpp:60
conversions.h
moveit_warehouse::PlanningSceneStorage::reset
void reset()
Definition: planning_scene_storage.cpp:64
ROS_INFO
#define ROS_INFO(...)
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
ros::NodeHandle


warehouse
Author(s): Ioan Sucan
autogenerated on Mon May 27 2024 02:28:07