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