Skip to content

Commit 3b4ea48

Browse files
Add unittest cartesianCollisionMinMaxDistance (#538)
... to illustrate that MoveRelative's min-max constraint fails with PipelinePlanners (e.g. Pilz) returning a partially invalid trajectory: MTC does not truncate the trajectory to its valid part and thus fails, even if the valid part fits the given min-max range. This logic is only supported for the CartesianPath planner for now. Co-authored-by: Robert Haschke <[email protected]>
1 parent 92efc14 commit 3b4ea48

File tree

2 files changed

+83
-19
lines changed

2 files changed

+83
-19
lines changed

core/test/move_relative.test

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<launch>
2-
<include file="$(find moveit_resources_panda_moveit_config)/launch/planning_context.launch">
2+
<include file="$(find moveit_resources_panda_moveit_config)/launch/move_group.launch">
33
<arg name="load_robot_description" value="true"/>
44
</include>
55

core/test/test_move_relative.cpp

Lines changed: 82 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
#include <moveit/task_constructor/stages/move_relative.h>
55
#include <moveit/task_constructor/stages/fixed_state.h>
66
#include <moveit/task_constructor/solvers/cartesian_path.h>
7+
#include <moveit/task_constructor/solvers/pipeline_planner.h>
78

89
#include <moveit/planning_scene/planning_scene.h>
910
#include <moveit/robot_trajectory/robot_trajectory.h>
@@ -13,23 +14,44 @@
1314

1415
#include <gtest/gtest.h>
1516

17+
#ifndef TYPED_TEST_SUITE // for Melodic
18+
#define TYPED_TEST_SUITE(SUITE, TYPES) TYPED_TEST_CASE(SUITE, TYPES)
19+
#endif
20+
1621
using namespace moveit::task_constructor;
1722
using namespace planning_scene;
1823
using namespace moveit::core;
1924

2025
constexpr double TAU{ 2 * M_PI };
2126
constexpr double EPS{ 5e-5 };
2227

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+
2343
// provide a basic test fixture that prepares a Task
44+
template <typename Planner = solvers::CartesianPath>
2445
struct PandaMoveRelative : public testing::Test
2546
{
2647
Task t;
2748
stages::MoveRelative* move;
2849
PlanningScenePtr scene;
50+
std::shared_ptr<Planner> planner;
2951

3052
const JointModelGroup* group;
3153

32-
PandaMoveRelative() {
54+
PandaMoveRelative() : planner(create<Planner>()) {
3355
t.setRobotModel(loadModel());
3456

3557
group = t.getRobotModel()->getJointModelGroup("panda_arm");
@@ -39,31 +61,44 @@ struct PandaMoveRelative : public testing::Test
3961
scene->getCurrentStateNonConst().setToDefaultValues(t.getRobotModel()->getJointModelGroup("panda_arm"), "ready");
4062
t.add(std::make_unique<stages::FixedState>("start", scene));
4163

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);
4365
move_relative->setGroup(group->getName());
4466
move = move_relative.get();
4567
t.add(std::move(move_relative));
4668
}
4769
};
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, [] {
5678
shape_msgs::SolidPrimitive p;
5779
p.type = p.SPHERE;
5880
p.dimensions.resize(1);
5981
p.dimensions[p.SPHERE_RADIUS] = 0.01;
6082
return p;
6183
}());
6284

85+
co.pose = pose;
86+
return co;
87+
}
88+
89+
moveit_msgs::CollisionObject createObject(const std::string& id) {
6390
geometry_msgs::Pose p;
6491
p.position.x = 0.1;
6592
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+
67102
return aco;
68103
}
69104

@@ -79,13 +114,13 @@ void expect_const_position(const SolutionBaseConstPtr& solution, const std::stri
79114
}
80115
}
81116

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__); \
86121
}
87122

88-
TEST_F(PandaMoveRelative, cartesianRotateEEF) {
123+
TEST_F(PandaMoveRelativeCartesian, cartesianRotateEEF) {
89124
move->setDirection([] {
90125
geometry_msgs::TwistStamped twist;
91126
twist.header.frame_id = "world";
@@ -97,7 +132,7 @@ TEST_F(PandaMoveRelative, cartesianRotateEEF) {
97132
EXPECT_CONST_POSITION(move->solutions().front(), group->getOnlyOneEndEffectorTip()->getName());
98133
}
99134

100-
TEST_F(PandaMoveRelative, cartesianCircular) {
135+
TEST_F(PandaMoveRelativeCartesian, cartesianCircular) {
101136
const std::string tip = "panda_hand";
102137
auto offset = Eigen::Translation3d(0, 0, 0.1);
103138
move->setIKFrame(offset, tip);
@@ -112,7 +147,7 @@ TEST_F(PandaMoveRelative, cartesianCircular) {
112147
EXPECT_CONST_POSITION(move->solutions().front(), tip, Eigen::Isometry3d(offset));
113148
}
114149

115-
TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) {
150+
TEST_F(PandaMoveRelativeCartesian, cartesianRotateAttachedIKFrame) {
116151
const std::string attached_object{ "attached_object" };
117152
scene->processAttachedCollisionObjectMsg(createAttachedObject(attached_object));
118153
move->setIKFrame(attached_object);
@@ -128,6 +163,35 @@ TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) {
128163
EXPECT_CONST_POSITION(move->solutions().front(), attached_object);
129164
}
130165

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+
131195
int main(int argc, char** argv) {
132196
testing::InitGoogleTest(&argc, argv);
133197
ros::init(argc, argv, "move_relative_test");

0 commit comments

Comments
 (0)