-
Notifications
You must be signed in to change notification settings - Fork 936
/
test_planning_scene.cpp
291 lines (251 loc) · 11.9 KB
/
test_planning_scene.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Ioan Sucan */
#include <gtest/gtest.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/utils/message_checks.h>
#include <moveit/utils/robot_model_test_utils.h>
#include <urdf_parser/urdf_parser.h>
#include <fstream>
#include <sstream>
#include <string>
#include <boost/filesystem/path.hpp>
#include <ros/package.h>
TEST(PlanningScene, LoadRestore)
{
urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
srdf::ModelSharedPtr srdf_model(new srdf::Model());
planning_scene::PlanningScene ps(urdf_model, srdf_model);
moveit_msgs::PlanningScene ps_msg;
ps.getPlanningSceneMsg(ps_msg);
EXPECT_EQ(ps.getName(), ps_msg.name);
EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
ps.setPlanningSceneMsg(ps_msg);
EXPECT_EQ(ps.getName(), ps_msg.name);
EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
}
TEST(PlanningScene, LoadRestoreDiff)
{
urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
srdf::ModelSharedPtr srdf_model(new srdf::Model());
auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
collision_detection::World& world = *ps->getWorldNonConst();
/* add one object to ps's world */
Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
world.addToObject("sphere", shapes::ShapeConstPtr(new shapes::Sphere(0.4)), id);
/* ps can be written to and set from message */
moveit_msgs::PlanningScene ps_msg;
ps_msg.robot_state.is_diff = true;
EXPECT_TRUE(moveit::core::isEmpty(ps_msg));
ps->getPlanningSceneMsg(ps_msg);
ps->setPlanningSceneMsg(ps_msg);
EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
EXPECT_EQ(ps_msg.world.collision_objects[0].id, "sphere");
EXPECT_TRUE(world.hasObject("sphere"));
/* test diff scene on top of ps */
planning_scene::PlanningScenePtr next = ps->diff();
/* world is inherited from ps */
EXPECT_TRUE(next->getWorld()->hasObject("sphere"));
/* object in overlay is only added in overlay */
next->getWorldNonConst()->addToObject("sphere_in_next_only", shapes::ShapeConstPtr(new shapes::Sphere(0.5)), id);
EXPECT_EQ(next->getWorld()->size(), 2u);
EXPECT_EQ(ps->getWorld()->size(), 1u);
/* the worlds used for collision detection contain one and two objects, respectively */
EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 1u);
EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 1u);
EXPECT_EQ(next->getCollisionEnv()->getWorld()->size(), 2u);
EXPECT_EQ(next->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
/* maintained diff contains only overlay object */
next->getPlanningSceneDiffMsg(ps_msg);
EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
/* copy ps to next and apply diff */
next->decoupleParent();
moveit_msgs::PlanningScene ps_msg2;
/* diff is empty now */
next->getPlanningSceneDiffMsg(ps_msg2);
EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0u);
/* next's world contains both objects */
next->getPlanningSceneMsg(ps_msg);
EXPECT_EQ(ps_msg.world.collision_objects.size(), 2u);
ps->setPlanningSceneMsg(ps_msg);
EXPECT_EQ(ps->getWorld()->size(), 2u);
EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 2u);
EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
}
TEST(PlanningScene, MakeAttachedDiff)
{
urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
srdf::ModelSharedPtr srdf_model(new srdf::Model());
auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
/* add a single object to ps's world */
collision_detection::World& world = *ps->getWorldNonConst();
Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
world.addToObject("sphere", shapes::ShapeConstPtr(new shapes::Sphere(0.4)), id);
/* attach object in diff */
planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
moveit_msgs::AttachedCollisionObject att_obj;
att_obj.link_name = "r_wrist_roll_link";
att_obj.object.operation = moveit_msgs::CollisionObject::ADD;
att_obj.object.id = "sphere";
attached_object_diff_scene->processAttachedCollisionObjectMsg(att_obj);
/* object is not in world anymore */
EXPECT_EQ(attached_object_diff_scene->getWorld()->size(), 0u);
/* it became part of the robot state though */
EXPECT_TRUE(attached_object_diff_scene->getCurrentState().hasAttachedBody("sphere"));
collision_detection::CollisionRequest req;
collision_detection::CollisionResult res;
attached_object_diff_scene->checkCollision(req, res);
ps->checkCollision(req, res);
}
TEST(PlanningScene, isStateValid)
{
moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
moveit::core::RobotState current_state = ps->getCurrentState();
if (ps->isStateColliding(current_state, "left_arm"))
{
EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
}
}
TEST(PlanningScene, loadGoodSceneGeometry)
{
moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
std::istringstream good_scene_geometry;
good_scene_geometry.str("foobar_scene\n"
"* foo\n"
"1\n"
"box\n"
"2.58 1.36 0.31\n"
"1.49257 1.00222 0.170051\n"
"0 0 4.16377e-05 1\n"
"0 0 1 0.3\n"
"* bar\n"
"1\n"
"cylinder\n"
"0.02 0.0001\n"
"0.453709 0.499136 0.355051\n"
"0 0 4.16377e-05 1\n"
"1 0 0 1\n"
".\n");
EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
EXPECT_EQ(ps->getName(), "foobar_scene");
EXPECT_TRUE(ps->getWorld()->hasObject("foo"));
EXPECT_TRUE(ps->getWorld()->hasObject("bar"));
EXPECT_FALSE(ps->getWorld()->hasObject("baz")); // Sanity check.
}
TEST(PlanningScene, loadBadSceneGeometry)
{
moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
std::istringstream empty_scene_geometry;
// This should fail since there is no planning scene name and no end of geometry marker.
EXPECT_FALSE(ps->loadGeometryFromStream(empty_scene_geometry));
std::istringstream malformed_scene_geometry;
malformed_scene_geometry.str("malformed_scene_geometry\n"
"* foo\n"
"1\n"
"box\n"
"2.58 1.36\n" /* Only two tokens; should be 3 */
"1.49257 1.00222 0.170051\n"
"0 0 4.16377e-05 1\n"
"0 0 1 0.3\n"
".\n");
EXPECT_FALSE(ps->loadGeometryFromStream(malformed_scene_geometry));
}
TEST(PlanningScene, rememberMetadataWhenAttached)
{
moveit::core::RobotModelPtr robot_model(moveit::core::RobotModelBuilder("empty_robot", "base_link").build());
planning_scene::PlanningScene scene(robot_model);
// prepare planning scene message to add a colored object
moveit_msgs::PlanningScene scene_msg;
scene_msg.robot_model_name = robot_model->getName();
scene_msg.is_diff = true;
scene_msg.robot_state.is_diff = true;
moveit_msgs::CollisionObject co;
co.header.frame_id = "base_link";
co.id = "blue_sphere";
co.operation = moveit_msgs::CollisionObject::ADD;
co.pose.orientation.w = 1.0;
{
// set valid primitive
shape_msgs::SolidPrimitive primitive;
primitive.type = shape_msgs::SolidPrimitive::SPHERE;
primitive.dimensions.push_back(/* SPHERE_RADIUS */ 1.0);
co.primitives.push_back(primitive);
geometry_msgs::Pose pose;
pose.orientation.w = 1.0;
co.primitive_poses.push_back(pose);
}
// meta-data 1: object type
co.type.key = "blue_sphere_type";
co.type.db = "{'type':'CustomDB'}";
scene_msg.world.collision_objects.push_back(co);
// meta-data 2: object color
moveit_msgs::ObjectColor color;
color.id = co.id;
color.color.b = 1.0;
color.color.a = 1.0;
scene_msg.object_colors.push_back(color);
EXPECT_FALSE(scene.hasObjectColor(co.id)) << "scene knows color before adding it(?)";
EXPECT_FALSE(scene.hasObjectType(co.id)) << "scene knows type before adding it(?)";
// add object to scene
scene.usePlanningSceneMsg(scene_msg);
EXPECT_TRUE(scene.hasObjectColor(co.id)) << "scene failed to add object color";
EXPECT_EQ(scene.getObjectColor(co.id), color.color) << "scene added wrong object color";
EXPECT_TRUE(scene.hasObjectType(co.id)) << "scene failed to add object type";
EXPECT_EQ(scene.getObjectType(co.id), co.type) << "scene added wrong object type";
// attach object
moveit_msgs::AttachedCollisionObject aco;
aco.object.operation = moveit_msgs::CollisionObject::ADD;
aco.object.id = co.id;
aco.link_name = robot_model->getModelFrame();
scene.processAttachedCollisionObjectMsg(aco);
EXPECT_EQ(scene.getObjectColor(co.id), color.color) << "scene forgot object color after it got attached";
EXPECT_EQ(scene.getObjectType(co.id), co.type) << "scene forgot object type after it got attached";
// trying to remove object from the scene while it is attached is expected to fail
co.operation = moveit_msgs::CollisionObject::REMOVE;
EXPECT_FALSE(scene.processCollisionObjectMsg(co))
<< "scene removed attached object from collision world (although it's not there)";
// detach again right away
aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
scene.processAttachedCollisionObjectMsg(aco);
EXPECT_EQ(scene.getObjectColor(co.id), color.color) << "scene forgot specified color after attach/detach";
EXPECT_EQ(scene.getObjectType(co.id), co.type) << "scene forgot specified type after attach/detach";
}
int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}