4
4
#include < moveit/task_constructor/stages/move_relative.h>
5
5
#include < moveit/task_constructor/stages/fixed_state.h>
6
6
#include < moveit/task_constructor/solvers/cartesian_path.h>
7
+ #include < moveit/task_constructor/solvers/pipeline_planner.h>
7
8
8
9
#include < moveit/planning_scene/planning_scene.h>
9
10
#include < moveit/robot_trajectory/robot_trajectory.h>
13
14
14
15
#include < gtest/gtest.h>
15
16
17
+ #ifndef TYPED_TEST_SUITE // for Melodic
18
+ #define TYPED_TEST_SUITE (SUITE, TYPES ) TYPED_TEST_CASE(SUITE, TYPES)
19
+ #endif
20
+
16
21
using namespace moveit ::task_constructor;
17
22
using namespace planning_scene ;
18
23
using namespace moveit ::core;
19
24
20
25
constexpr double TAU{ 2 * M_PI };
21
26
constexpr double EPS{ 5e-5 };
22
27
28
+ template <typename Planner>
29
+ std::shared_ptr<Planner> create ();
30
+ template <>
31
+ solvers::CartesianPathPtr create<solvers::CartesianPath>() {
32
+ return std::make_shared<solvers::CartesianPath>();
33
+ }
34
+ template <>
35
+ solvers::PipelinePlannerPtr create<solvers::PipelinePlanner>() {
36
+ auto p = std::make_shared<solvers::PipelinePlanner>(" pilz_industrial_motion_planner" );
37
+ p->setPlannerId (" LIN" );
38
+ p->setProperty (" max_velocity_scaling_factor" , 0.1 );
39
+ p->setProperty (" max_acceleration_scaling_factor" , 0.1 );
40
+ return p;
41
+ }
42
+
23
43
// provide a basic test fixture that prepares a Task
44
+ template <typename Planner = solvers::CartesianPath>
24
45
struct PandaMoveRelative : public testing ::Test
25
46
{
26
47
Task t;
27
48
stages::MoveRelative* move;
28
49
PlanningScenePtr scene;
50
+ std::shared_ptr<Planner> planner;
29
51
30
52
const JointModelGroup* group;
31
53
32
- PandaMoveRelative () {
54
+ PandaMoveRelative () : planner(create<Planner>()) {
33
55
t.setRobotModel (loadModel ());
34
56
35
57
group = t.getRobotModel ()->getJointModelGroup (" panda_arm" );
@@ -39,31 +61,44 @@ struct PandaMoveRelative : public testing::Test
39
61
scene->getCurrentStateNonConst ().setToDefaultValues (t.getRobotModel ()->getJointModelGroup (" panda_arm" ), " ready" );
40
62
t.add (std::make_unique<stages::FixedState>(" start" , scene));
41
63
42
- auto move_relative = std::make_unique<stages::MoveRelative>(" move" , std::make_shared<solvers::CartesianPath>() );
64
+ auto move_relative = std::make_unique<stages::MoveRelative>(" move" , planner );
43
65
move_relative->setGroup (group->getName ());
44
66
move = move_relative.get ();
45
67
t.add (std::move (move_relative));
46
68
}
47
69
};
48
-
49
- moveit_msgs::AttachedCollisionObject createAttachedObject ( const std::string& id) {
50
- moveit_msgs::AttachedCollisionObject aco;
51
- aco. link_name = " panda_hand " ;
52
- aco. object . header .frame_id = aco. link_name ;
53
- aco. object . operation = aco. object .ADD ;
54
- aco. object .id = id;
55
- aco. object .primitives .resize (1 , [] {
70
+ using PandaMoveRelativeCartesian = PandaMoveRelative<solvers::CartesianPath>;
71
+
72
+ moveit_msgs::CollisionObject createObject ( const std::string& id, const geometry_msgs::Pose& pose) {
73
+ moveit_msgs::CollisionObject co ;
74
+ co. header .frame_id = " panda_hand " ;
75
+ co. operation = co .ADD ;
76
+ co .id = id;
77
+ co .primitives .resize (1 , [] {
56
78
shape_msgs::SolidPrimitive p;
57
79
p.type = p.SPHERE ;
58
80
p.dimensions .resize (1 );
59
81
p.dimensions [p.SPHERE_RADIUS ] = 0.01 ;
60
82
return p;
61
83
}());
62
84
85
+ co.pose = pose;
86
+ return co;
87
+ }
88
+
89
+ moveit_msgs::CollisionObject createObject (const std::string& id) {
63
90
geometry_msgs::Pose p;
64
91
p.position .x = 0.1 ;
65
92
p.orientation .w = 1.0 ;
66
- aco.object .pose = p;
93
+
94
+ return createObject (id, p);
95
+ }
96
+
97
+ moveit_msgs::AttachedCollisionObject createAttachedObject (const std::string& id) {
98
+ moveit_msgs::AttachedCollisionObject aco;
99
+ aco.link_name = " panda_hand" ;
100
+ aco.object = createObject (id);
101
+
67
102
return aco;
68
103
}
69
104
@@ -79,13 +114,13 @@ void expect_const_position(const SolutionBaseConstPtr& solution, const std::stri
79
114
}
80
115
}
81
116
82
- #define EXPECT_CONST_POSITION (...) \
83
- { \
84
- SCOPED_TRACE (" expect_constant_position (" #__VA_ARGS__ " )" ); \
85
- expect_const_position (__VA_ARGS__); \
117
+ #define EXPECT_CONST_POSITION (...) \
118
+ { \
119
+ SCOPED_TRACE (" expect_const_position (" #__VA_ARGS__ " )" ); \
120
+ expect_const_position (__VA_ARGS__); \
86
121
}
87
122
88
- TEST_F (PandaMoveRelative , cartesianRotateEEF) {
123
+ TEST_F (PandaMoveRelativeCartesian , cartesianRotateEEF) {
89
124
move->setDirection ([] {
90
125
geometry_msgs::TwistStamped twist;
91
126
twist.header .frame_id = " world" ;
@@ -97,7 +132,7 @@ TEST_F(PandaMoveRelative, cartesianRotateEEF) {
97
132
EXPECT_CONST_POSITION (move->solutions ().front (), group->getOnlyOneEndEffectorTip ()->getName ());
98
133
}
99
134
100
- TEST_F (PandaMoveRelative , cartesianCircular) {
135
+ TEST_F (PandaMoveRelativeCartesian , cartesianCircular) {
101
136
const std::string tip = " panda_hand" ;
102
137
auto offset = Eigen::Translation3d (0 , 0 , 0.1 );
103
138
move->setIKFrame (offset, tip);
@@ -112,7 +147,7 @@ TEST_F(PandaMoveRelative, cartesianCircular) {
112
147
EXPECT_CONST_POSITION (move->solutions ().front (), tip, Eigen::Isometry3d (offset));
113
148
}
114
149
115
- TEST_F (PandaMoveRelative , cartesianRotateAttachedIKFrame) {
150
+ TEST_F (PandaMoveRelativeCartesian , cartesianRotateAttachedIKFrame) {
116
151
const std::string attached_object{ " attached_object" };
117
152
scene->processAttachedCollisionObjectMsg (createAttachedObject (attached_object));
118
153
move->setIKFrame (attached_object);
@@ -128,6 +163,35 @@ TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) {
128
163
EXPECT_CONST_POSITION (move->solutions ().front (), attached_object);
129
164
}
130
165
166
+ using PlannerTypes = ::testing::Types<solvers::CartesianPath, solvers::PipelinePlanner>;
167
+ TYPED_TEST_SUITE (PandaMoveRelative, PlannerTypes);
168
+ TYPED_TEST (PandaMoveRelative, cartesianCollisionMinMaxDistance) {
169
+ if (std::is_same<TypeParam, solvers::PipelinePlanner>::value)
170
+ GTEST_SKIP (); // Pilz PipelinePlanner current fails this test (see #538)
171
+
172
+ const std::string object{ " object" };
173
+ geometry_msgs::Pose object_pose;
174
+ object_pose.position .z = 0.4 ;
175
+ object_pose.orientation .w = 1.0 ;
176
+
177
+ this ->scene ->processCollisionObjectMsg (createObject (object, object_pose));
178
+
179
+ this ->move ->setIKFrame (" panda_hand" );
180
+ geometry_msgs::Vector3Stamped v;
181
+ v.header .frame_id = " panda_hand" ;
182
+ v.vector .z = 0.5 ;
183
+ this ->move ->setDirection (v);
184
+ EXPECT_FALSE (this ->t .plan ()) << " Plan should fail due to collision" ;
185
+
186
+ this ->t .reset ();
187
+ v.vector .z = 1.0 ;
188
+ this ->move ->setDirection (v);
189
+ this ->move ->setMinMaxDistance (0.1 , 0.5 );
190
+ EXPECT_TRUE (this ->t .plan ()) << " Plan should succeed due to min distance reached" ;
191
+ auto trajectory = std::dynamic_pointer_cast<const SubTrajectory>(this ->move ->solutions ().front ());
192
+ EXPECT_TRUE (this ->scene ->isPathValid (*trajectory->trajectory (), " panda_arm" , false ));
193
+ }
194
+
131
195
int main (int argc, char ** argv) {
132
196
testing::InitGoogleTest (&argc, argv);
133
197
ros::init (argc, argv, " move_relative_test" );
0 commit comments