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


warehouse
Author(s): Ioan Sucan
autogenerated on Thu Nov 21 2024 03:25:01