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


warehouse
Author(s): Ioan Sucan
autogenerated on Wed Jul 10 2019 04:04:05