moveit2
The MoveIt Motion Planning Framework for ROS 2.
save_as_text.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 
40 #include <boost/program_options/cmdline.hpp>
41 #include <boost/program_options/options_description.hpp>
42 #include <boost/program_options/parsers.hpp>
43 #include <boost/program_options/variables_map.hpp>
46 #include <rclcpp/executors.hpp>
47 #include <rclcpp/logger.hpp>
48 #include <rclcpp/logging.hpp>
49 #include <rclcpp/node.hpp>
50 #include <rclcpp/node_options.hpp>
51 #include <rclcpp/utilities.hpp>
52 
53 static const std::string ROBOT_DESCRIPTION = "robot_description";
54 
55 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.save_to_text");
56 
57 typedef std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Quaternion> LinkConstraintPair;
58 typedef std::map<std::string, LinkConstraintPair> LinkConstraintMap;
59 
60 void collectLinkConstraints(const moveit_msgs::msg::Constraints& constraints, LinkConstraintMap& lcmap)
61 {
62  for (const moveit_msgs::msg::PositionConstraint& position_constraint : constraints.position_constraints)
63  {
65  const moveit_msgs::msg::PositionConstraint& pc = position_constraint;
66  lcp.first = pc.constraint_region.primitive_poses[0].position;
67  lcmap[position_constraint.link_name] = lcp;
68  }
69 
70  for (const moveit_msgs::msg::OrientationConstraint& orientation_constraint : constraints.orientation_constraints)
71  {
72  if (lcmap.count(orientation_constraint.link_name))
73  {
74  lcmap[orientation_constraint.link_name].second = orientation_constraint.orientation;
75  }
76  else
77  {
78  RCLCPP_WARN(LOGGER, "Orientation constraint for %s has no matching position constraint",
79  orientation_constraint.link_name.c_str());
80  }
81  }
82 }
83 
84 int main(int argc, char** argv)
85 {
86  rclcpp::init(argc, argv);
87  rclcpp::NodeOptions node_options;
88  node_options.allow_undeclared_parameters(true);
89  node_options.automatically_declare_parameters_from_overrides(true);
90  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("save_warehouse_as_text", node_options);
91 
92  boost::program_options::options_description desc;
93  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
94  "Host for the "
95  "DB.")("port", boost::program_options::value<std::size_t>(),
96  "Port for the DB.");
97 
98  boost::program_options::variables_map vm;
99  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
100  boost::program_options::notify(vm);
101 
102  if (vm.count("help"))
103  {
104  std::cout << desc << '\n';
105  return 1;
106  }
107  // Set up db
108  warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node);
109  if (vm.count("host") && vm.count("port"))
110  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
111  if (!conn->connect())
112  return 1;
113 
114  planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
115 
119 
120  std::vector<std::string> scene_names;
121  pss.getPlanningSceneNames(scene_names);
122 
123  for (const std::string& scene_name : scene_names)
124  {
126  if (pss.getPlanningScene(pswm, scene_name))
127  {
128  RCLCPP_INFO(LOGGER, "Saving scene '%s'", scene_name.c_str());
129  psm.getPlanningScene()->setPlanningSceneMsg(static_cast<const moveit_msgs::msg::PlanningScene&>(*pswm));
130  std::ofstream fout((scene_name + ".scene").c_str());
131  psm.getPlanningScene()->saveGeometryToStream(fout);
132  fout.close();
133 
134  std::vector<std::string> robot_state_names;
135  moveit::core::RobotModelConstPtr km = psm.getRobotModel();
136  // Get start states for scene
137  std::stringstream rsregex;
138  rsregex << ".*" << scene_name << ".*";
139  rss.getKnownRobotStates(rsregex.str(), robot_state_names);
140 
141  // Get goal constraints for scene
142  std::vector<std::string> constraint_names;
143 
144  std::stringstream csregex;
145  csregex << ".*" << scene_name << ".*";
146  cs.getKnownConstraints(csregex.str(), constraint_names);
147 
148  if (!(robot_state_names.empty() && constraint_names.empty()))
149  {
150  std::ofstream qfout((scene_name + ".queries").c_str());
151  qfout << scene_name << '\n';
152  if (!robot_state_names.empty())
153  {
154  qfout << "start" << '\n';
155  qfout << robot_state_names.size() << '\n';
156  for (const std::string& robot_state_name : robot_state_names)
157  {
158  RCLCPP_INFO(LOGGER, "Saving start state %s for scene %s", robot_state_name.c_str(), scene_name.c_str());
159  qfout << robot_state_name << '\n';
161  rss.getRobotState(robot_state, robot_state_name);
163  moveit::core::robotStateMsgToRobotState(*robot_state, ks, false);
164  ks.printStateInfo(qfout);
165  qfout << "." << '\n';
166  }
167  }
168 
169  if (!constraint_names.empty())
170  {
171  qfout << "goal" << '\n';
172  qfout << constraint_names.size() << '\n';
173  for (const std::string& constraint_name : constraint_names)
174  {
175  RCLCPP_INFO(LOGGER, "Saving goal %s for scene %s", constraint_name.c_str(), scene_name.c_str());
176  qfout << "link_constraint" << '\n';
177  qfout << constraint_name << '\n';
179  cs.getConstraints(constraints, constraint_name);
180 
181  LinkConstraintMap lcmap;
182  collectLinkConstraints(*constraints, lcmap);
183  for (std::pair<const std::string, LinkConstraintPair>& iter : lcmap)
184  {
185  std::string link_name = iter.first;
186  LinkConstraintPair lcp = iter.second;
187  qfout << link_name << '\n';
188  qfout << "xyz " << lcp.first.x << " " << lcp.first.y << " " << lcp.first.z << '\n';
189  Eigen::Quaterniond orientation(lcp.second.w, lcp.second.x, lcp.second.y, lcp.second.z);
190  Eigen::Vector3d rpy = orientation.matrix().eulerAngles(0, 1, 2);
191  qfout << "rpy " << rpy[0] << " " << rpy[1] << " " << rpy[2] << '\n';
192  }
193  qfout << "." << '\n';
194  }
195  }
196  qfout.close();
197  }
198  }
199  }
200 
201  RCLCPP_INFO(LOGGER, "Done.");
202  rclcpp::spin(node);
203  return 0;
204 }
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void printStateInfo(std::ostream &out=std::cout) const
bool getConstraints(ConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
Get the constraints named name. Return false on failure.
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
void getPlanningSceneNames(std::vector< std::string > &names) const
bool getPlanningScene(PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const
Get the latest planning scene named scene_name.
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
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
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
Definition: state_storage.h:47
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::map< std::string, LinkConstraintPair > LinkConstraintMap
int main(int argc, char **argv)
std::pair< geometry_msgs::msg::Point, geometry_msgs::msg::Quaternion > LinkConstraintPair
void collectLinkConstraints(const moveit_msgs::msg::Constraints &constraints, LinkConstraintMap &lcmap)