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.h>
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 <ros/ros.h>
49 
50 static const std::string ROBOT_DESCRIPTION = "robot_description";
51 
54 {
55  int count;
56  in >> count;
57  if (in.good() && !in.eof())
58  {
59  for (int i = 0; i < count; ++i)
60  {
61  std::map<std::string, double> v;
62  std::string name;
63  in >> name;
64  if (in.good() && !in.eof())
65  {
66  std::string joint;
67  std::string marker;
68  double value;
69  in >> joint;
70  while (joint != "." && in.good() && !in.eof())
71  {
72  in >> marker;
73  if (marker != "=")
74  joint = ".";
75  else
76  {
77  in >> value;
78  v[joint] = value;
79  }
80  if (joint != ".")
81  in >> joint;
82  }
83  }
84  if (!v.empty())
85  {
86  robot_state::RobotState st = psm->getPlanningScene()->getCurrentState();
87  st.setVariablePositions(v);
88  moveit_msgs::RobotState msg;
89  robot_state::robotStateToRobotStateMsg(st, msg);
90  ROS_INFO("Parsed start state '%s'", name.c_str());
91  rs->addRobotState(msg, name);
92  }
93  }
94  }
95 }
96 
99 {
100  Eigen::Translation3d pos(Eigen::Vector3d::Zero());
101  Eigen::Quaterniond rot(Eigen::Quaterniond::Identity());
102 
103  bool have_position = false;
104  bool have_orientation = false;
105 
106  std::string name;
107  std::getline(in, name);
108 
109  // The link name is optional, in which case there would be a blank line
110  std::string link_name;
111  std::getline(in, link_name);
112 
113  std::string type;
114  in >> type;
115 
116  while (type != "." && in.good() && !in.eof())
117  {
118  if (type == "xyz")
119  {
120  have_position = true;
121  double x, y, z;
122  in >> x >> y >> z;
123  pos = Eigen::Translation3d(x, y, z);
124  }
125  else if (type == "rpy")
126  {
127  have_orientation = true;
128  double r, p, y;
129  in >> r >> p >> y;
130  rot = Eigen::Quaterniond(Eigen::AngleAxisd(r, Eigen::Vector3d::UnitX()) *
131  Eigen::AngleAxisd(p, Eigen::Vector3d::UnitY()) *
132  Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ()));
133  }
134  else
135  ROS_ERROR("Unknown link constraint element: '%s'", type.c_str());
136  in >> type;
137  }
138 
139  // Convert to getLine method by eating line break
140  std::string end_link;
141  std::getline(in, end_link);
142 
143  if (have_position && have_orientation)
144  {
145  geometry_msgs::PoseStamped pose;
146  pose.pose = tf2::toMsg(pos * rot);
147  pose.header.frame_id = psm->getRobotModel()->getModelFrame();
148  moveit_msgs::Constraints constr = kinematic_constraints::constructGoalConstraints(link_name, pose);
149  constr.name = name;
150  ROS_INFO("Parsed link constraint '%s'", name.c_str());
151  cs->addConstraints(constr);
152  }
153 }
154 
157 {
158  int count;
159  in >> count;
160 
161  // Convert to getLine method from here-on, so eat the line break.
162  std::string end_link;
163  std::getline(in, end_link);
164 
165  if (in.good() && !in.eof())
166  {
167  for (int i = 0; i < count; ++i)
168  {
169  std::string type;
170  std::getline(in, type);
171 
172  if (in.good() && !in.eof())
173  {
174  if (type == "link_constraint")
175  parseLinkConstraint(in, psm, cs);
176  else
177  ROS_ERROR("Unknown goal type: '%s'", type.c_str());
178  }
179  }
180  }
181 }
182 
185 {
186  std::string scene_name;
187  in >> scene_name;
188  while (in.good() && !in.eof())
189  {
190  std::string type;
191  in >> type;
192 
193  if (in.good() && !in.eof())
194  {
195  if (type == "start")
196  parseStart(in, psm, rs);
197  else if (type == "goal")
198  parseGoal(in, psm, cs);
199  else
200  ROS_ERROR("Unknown query type: '%s'", type.c_str());
201  }
202  }
203 }
204 
205 int main(int argc, char** argv)
206 {
207  ros::init(argc, argv, "import_from_text_to_warehouse", ros::init_options::AnonymousName);
208 
209  boost::program_options::options_description desc;
210  desc.add_options()("help", "Show help message")("queries", boost::program_options::value<std::string>(),
211  "Name of file containing motion planning queries.")(
212  "scene", boost::program_options::value<std::string>(), "Name of file containing motion planning scene.")(
213  "host", boost::program_options::value<std::string>(),
214  "Host for the DB.")("port", boost::program_options::value<std::size_t>(), "Port for the DB.");
215 
216  boost::program_options::variables_map vm;
217  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
218  boost::program_options::notify(vm);
219 
220  if (vm.count("help") || argc == 1) // show help if no parameters passed
221  {
222  std::cout << desc << std::endl;
223  return 1;
224  }
225  // Set up db
227  if (vm.count("host") && vm.count("port"))
228  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
229  if (!conn->connect())
230  return 1;
231 
233  spinner.start();
234 
235  ros::NodeHandle nh;
237  if (!psm.getPlanningScene())
238  {
239  ROS_ERROR("Unable to initialize PlanningSceneMonitor");
240  return 1;
241  }
242 
246 
247  if (vm.count("scene"))
248  {
249  std::ifstream fin(vm["scene"].as<std::string>().c_str());
250  psm.getPlanningScene()->loadGeometryFromStream(fin);
251  fin.close();
252  moveit_msgs::PlanningScene psmsg;
253  psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
254  pss.addPlanningScene(psmsg);
255  }
256 
257  if (vm.count("queries"))
258  {
259  std::ifstream fin(vm["queries"].as<std::string>().c_str());
260  if (fin.good() && !fin.eof())
261  parseQueries(fin, &psm, &rs, &cs);
262  fin.close();
263  }
264 
265  return 0;
266 }
void parseQueries(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::RobotStateStorage *rs, moveit_warehouse::ConstraintsStorage *cs)
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="")
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void parseGoal(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::ConstraintsStorage *cs)
const robot_model::RobotModelConstPtr & getRobotModel() const
#define ROS_ERROR(...)
void parseLinkConstraint(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::ConstraintsStorage *cs)
double y
void spinner()
static const std::string ROBOT_DESCRIPTION
const planning_scene::PlanningScenePtr & getPlanningScene()
void parseStart(std::istream &in, planning_scene_monitor::PlanningSceneMonitor *psm, moveit_warehouse::RobotStateStorage *rs)
warehouse_ros::DatabaseConnection::Ptr loadDatabase()
Load a database connection.
moveit_msgs::Constraints constructGoalConstraints(const robot_state::RobotState &state, const robot_model::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
#define ROS_INFO(...)
double z
void addPlanningScene(const moveit_msgs::PlanningScene &scene)
B toMsg(const A &a)
double x
r
int main(int argc, char **argv)


warehouse
Author(s): Ioan Sucan
autogenerated on Fri Aug 20 2021 03:01:32