moveit2
The MoveIt Motion Planning Framework for ROS 2.
import_from_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 
43 #include <tf2_eigen/tf2_eigen.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 <moveit/utils/logger.hpp>
49 
50 static const std::string ROBOT_DESCRIPTION = "robot_description";
51 
52 using moveit::getLogger;
53 
56 {
57  int count;
58  in >> count;
59  if (in.good() && !in.eof())
60  {
61  for (int i = 0; i < count; ++i)
62  {
63  std::map<std::string, double> v;
64  std::string name;
65  in >> name;
66  if (in.good() && !in.eof())
67  {
68  std::string joint;
69  std::string marker;
70  double value;
71  in >> joint;
72  while (joint != "." && in.good() && !in.eof())
73  {
74  in >> marker;
75  if (marker != "=")
76  {
77  joint = ".";
78  }
79  else
80  {
81  in >> value;
82  v[joint] = value;
83  }
84  if (joint != ".")
85  in >> joint;
86  }
87  }
88  if (!v.empty())
89  {
90  moveit::core::RobotState st = psm->getPlanningScene()->getCurrentState();
92  moveit_msgs::msg::RobotState msg;
94  RCLCPP_INFO(getLogger(), "Parsed start state '%s'", name.c_str());
95  rs->addRobotState(msg, name);
96  }
97  }
98  }
99 }
100 
103 {
104  Eigen::Translation3d pos(Eigen::Vector3d::Zero());
105  Eigen::Quaterniond rot(Eigen::Quaterniond::Identity());
106 
107  bool have_position = false;
108  bool have_orientation = false;
109 
110  std::string name;
111  std::getline(in, name);
112 
113  // The link name is optional, in which case there would be a blank line
114  std::string link_name;
115  std::getline(in, link_name);
116 
117  std::string type;
118  in >> type;
119 
120  while (type != "." && in.good() && !in.eof())
121  {
122  if (type == "xyz")
123  {
124  have_position = true;
125  double x, y, z;
126  in >> x >> y >> z;
127  pos = Eigen::Translation3d(x, y, z);
128  }
129  else if (type == "rpy")
130  {
131  have_orientation = true;
132  double r, p, y;
133  in >> r >> p >> y;
134  rot = Eigen::Quaterniond(Eigen::AngleAxisd(r, Eigen::Vector3d::UnitX()) *
135  Eigen::AngleAxisd(p, Eigen::Vector3d::UnitY()) *
136  Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ()));
137  }
138  else
139  RCLCPP_ERROR(getLogger(), "Unknown link constraint element: '%s'", type.c_str());
140  in >> type;
141  }
142 
143  // Convert to getLine method by eating line break
144  std::string end_link;
145  std::getline(in, end_link);
146 
147  if (have_position && have_orientation)
148  {
149  geometry_msgs::msg::PoseStamped pose;
150  pose.pose = tf2::toMsg(pos * rot);
151  pose.header.frame_id = psm->getRobotModel()->getModelFrame();
152  moveit_msgs::msg::Constraints constr = kinematic_constraints::constructGoalConstraints(link_name, pose);
153  constr.name = name;
154  RCLCPP_INFO(getLogger(), "Parsed link constraint '%s'", name.c_str());
155  cs->addConstraints(constr);
156  }
157 }
158 
161 {
162  int count;
163  in >> count;
164 
165  // Convert to getLine method from here-on, so eat the line break.
166  std::string end_link;
167  std::getline(in, end_link);
168 
169  if (in.good() && !in.eof())
170  {
171  for (int i = 0; i < count; ++i)
172  {
173  std::string type;
174  std::getline(in, type);
175 
176  if (in.good() && !in.eof())
177  {
178  if (type == "link_constraint")
179  {
180  parseLinkConstraint(in, psm, cs);
181  }
182  else
183  {
184  RCLCPP_INFO(getLogger(), "Unknown goal type: '%s'", type.c_str());
185  }
186  }
187  }
188  }
189 }
190 
193 {
194  std::string scene_name;
195  in >> scene_name;
196  while (in.good() && !in.eof())
197  {
198  std::string type;
199  in >> type;
200 
201  if (in.good() && !in.eof())
202  {
203  if (type == "start")
204  {
205  parseStart(in, psm, rs);
206  }
207  else if (type == "goal")
208  {
209  parseGoal(in, psm, cs);
210  }
211  else
212  {
213  RCLCPP_ERROR(getLogger(), "Unknown query type: '%s'", type.c_str());
214  }
215  }
216  }
217 }
218 
219 int main(int argc, char** argv)
220 {
221  rclcpp::init(argc, argv);
222  rclcpp::NodeOptions node_options;
223  node_options.allow_undeclared_parameters(true);
224  node_options.automatically_declare_parameters_from_overrides(true);
225  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("import_from_text_to_warehouse", node_options);
226  moveit::setLogger(node->get_logger());
227 
228  // clang-format off
229  boost::program_options::options_description desc;
230  desc.add_options()("help", "Show help message")("queries", boost::program_options::value<std::string>(),
231  "Name of file containing motion planning queries.")(
232  "scene", boost::program_options::value<std::string>(), "Name of file containing motion planning scene.")(
233  "host", boost::program_options::value<std::string>(),
234  "Host for the DB.")("port", boost::program_options::value<std::size_t>(), "Port for the DB.");
235  // clang-format on
236 
237  boost::program_options::variables_map vm;
238  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
239  boost::program_options::notify(vm);
240 
241  if (vm.count("help") || argc == 1) // show help if no parameters passed
242  {
243  std::cout << desc << '\n';
244  return 1;
245  }
246  // Set up db
247  warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node);
248  if (vm.count("host") && vm.count("port"))
249  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
250  if (!conn->connect())
251  return 1;
252 
253  planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
254  if (!psm.getPlanningScene())
255  {
256  RCLCPP_ERROR(getLogger(), "Unable to initialize PlanningSceneMonitor");
257  return 1;
258  }
259 
263 
264  if (vm.count("scene"))
265  {
266  std::ifstream fin(vm["scene"].as<std::string>().c_str());
267  psm.getPlanningScene()->loadGeometryFromStream(fin);
268  fin.close();
269  moveit_msgs::msg::PlanningScene psmsg;
270  psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
271  pss.addPlanningScene(psmsg);
272  }
273 
274  if (vm.count("queries"))
275  {
276  std::ifstream fin(vm["queries"].as<std::string>().c_str());
277  if (fin.good() && !fin.eof())
278  parseQueries(fin, &psm, &rs, &cs);
279  fin.close();
280  }
281 
282  rclcpp::spin(node);
283  return 0;
284 }
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
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 parseQueries(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::RobotStateStorage *rs, moveit_warehouse::ConstraintsStorage *cs)
void parseGoal(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::ConstraintsStorage *cs)
void parseLinkConstraint(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::ConstraintsStorage *cs)
void parseStart(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::RobotStateStorage *rs)
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition: utils.cpp:145
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 setLogger(const rclcpp::Logger &logger)
Definition: logger.cpp:98
const rclcpp::Logger & getLogger()
Definition: logger.cpp:88
name
Definition: setup.py:7