moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
37 #include <math.h>
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 <rclcpp/executors.hpp>
50 #include <rclcpp/logger.hpp>
51 #include <rclcpp/logging.hpp>
52 #include <rclcpp/node.hpp>
53 #include <rclcpp/node_options.hpp>
54 #include <rclcpp/utilities.hpp>
55 #include <moveit/utils/logger.hpp>
56 
57 static const std::string ROBOT_DESCRIPTION = "robot_description";
58 
59 int main(int argc, char** argv)
60 {
61  rclcpp::init(argc, argv);
62  rclcpp::NodeOptions node_options;
63  node_options.allow_undeclared_parameters(true);
64  node_options.automatically_declare_parameters_from_overrides(true);
65  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("initialize_demo_db", node_options);
66  moveit::setNodeLoggerName(node->get_name());
67 
68  boost::program_options::options_description desc;
69  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
70  "Host for the "
71  "DB.")("port", boost::program_options::value<std::size_t>(),
72  "Port for the DB.");
73 
74  boost::program_options::variables_map vm;
75  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
76  boost::program_options::notify(vm);
77 
78  if (vm.count("help"))
79  {
80  std::cout << desc << '\n';
81  return 1;
82  }
83  // Set up db
84  warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node);
85  if (vm.count("host") && vm.count("port"))
86  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
87  if (!conn->connect())
88  return 1;
89 
90  planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
91  if (!psm.getPlanningScene())
92  {
93  RCLCPP_ERROR(node->get_logger(), "Unable to initialize PlanningSceneMonitor");
94  return 1;
95  }
96 
100  pss.reset();
101  cs.reset();
102  rs.reset();
103 
104  // add default planning scenes
105  moveit_msgs::msg::PlanningScene psmsg;
106  psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
107  psmsg.name = "default";
108  pss.addPlanningScene(psmsg);
109  RCLCPP_INFO(node->get_logger(), "Added default scene: '%s'", psmsg.name.c_str());
110 
111  moveit_msgs::msg::RobotState rsmsg;
112  moveit::core::robotStateToRobotStateMsg(psm.getPlanningScene()->getCurrentState(), rsmsg);
113  rs.addRobotState(rsmsg, "default");
114  RCLCPP_INFO(node->get_logger(), "Added default state");
115 
116  const std::vector<std::string>& gnames = psm.getRobotModel()->getJointModelGroupNames();
117  for (const std::string& gname : gnames)
118  {
119  const moveit::core::JointModelGroup* jmg = psm.getRobotModel()->getJointModelGroup(gname);
120  if (!jmg->isChain())
121  continue;
122  const std::vector<std::string>& lnames = jmg->getLinkModelNames();
123  if (lnames.empty())
124  continue;
125 
126  moveit_msgs::msg::OrientationConstraint ocm;
127  ocm.link_name = lnames.back();
128  ocm.header.frame_id = psm.getRobotModel()->getModelFrame();
129  ocm.orientation.x = 0.0;
130  ocm.orientation.y = 0.0;
131  ocm.orientation.z = 0.0;
132  ocm.orientation.w = 1.0;
133  ocm.absolute_x_axis_tolerance = 0.1;
134  ocm.absolute_y_axis_tolerance = 0.1;
135  ocm.absolute_z_axis_tolerance = M_PI;
136  ocm.weight = 1.0;
137  moveit_msgs::msg::Constraints cmsg;
138  cmsg.orientation_constraints.resize(1, ocm);
139  cmsg.name = ocm.link_name + ":upright";
140  cs.addConstraints(cmsg, psm.getRobotModel()->getName(), jmg->getName());
141  RCLCPP_INFO(node->get_logger(), "Added default constraint: '%s'", cmsg.name.c_str());
142  }
143  RCLCPP_INFO(node->get_logger(), "Default MoveIt Warehouse was reset.");
144 
145  rclcpp::spin(node);
146 
147  return 0;
148 }
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
bool isChain() const
Check if this group is a linear chain.
const std::string & getName() const
Get the name of the joint group.
void addConstraints(const moveit_msgs::msg::Constraints &msg, const std::string &robot="", const std::string &group="")
void addPlanningScene(const moveit_msgs::msg::PlanningScene &scene)
void addRobotState(const moveit_msgs::msg::RobotState &msg, const std::string &name, const std::string &robot="")
PlanningSceneMonitor Subscribes to the topic planning_scene.
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
const moveit::core::RobotModelConstPtr & getRobotModel() const
int main(int argc, char **argv)
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition: logger.cpp:73