|
3 | 3 |
|
4 | 4 | #include <moveit/task_constructor/task.h> |
5 | 5 | #include <moveit/task_constructor/stages/move_to.h> |
| 6 | +#include <moveit/task_constructor/stages/connect.h> |
6 | 7 | #include <moveit/task_constructor/stages/fixed_state.h> |
7 | 8 | #include <moveit/task_constructor/solvers/joint_interpolation.h> |
| 9 | +#include <moveit/task_constructor/solvers/cartesian_path.h> |
8 | 10 |
|
9 | 11 | #include <moveit/planning_scene/planning_scene.h> |
10 | 12 |
|
@@ -149,7 +151,33 @@ TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) { |
149 | 151 | EXPECT_ONE_SOLUTION; |
150 | 152 | } |
151 | 153 |
|
152 | | -// This test require a running rosmaster |
| 154 | +// Using a Cartesian interpolation planner targeting a joint-space goal, which is |
| 155 | +// transformed into a Cartesian goal by FK, should fail if the two poses are on different |
| 156 | +// IK solution branches. In this case, the end-state, although reaching the Cartesian goal, |
| 157 | +// will strongly deviate from the joint-space goal. |
| 158 | +TEST(Panda, connectCartesianBranchesFails) { |
| 159 | + Task t; |
| 160 | + t.setRobotModel(loadModel()); |
| 161 | + auto scene = std::make_shared<PlanningScene>(t.getRobotModel()); |
| 162 | + scene->getCurrentStateNonConst().setToDefaultValues(); |
| 163 | + scene->getCurrentStateNonConst().setToDefaultValues(t.getRobotModel()->getJointModelGroup("panda_arm"), "ready"); |
| 164 | + t.add(std::make_unique<stages::FixedState>("start", scene)); |
| 165 | + |
| 166 | + stages::Connect::GroupPlannerVector planner = { { "panda_arm", std::make_shared<solvers::CartesianPath>() } }; |
| 167 | + t.add(std::make_unique<stages::Connect>("connect", planner)); |
| 168 | + |
| 169 | + // target an elbow-left instead of an elbow-right solution (different solution branch) |
| 170 | + scene = scene->diff(); |
| 171 | + scene->getCurrentStateNonConst().setJointGroupPositions( |
| 172 | + "panda_arm", std::vector<double>({ 2.72, 0.78, -2.63, -2.35, 0.36, 1.57, 0.48 })); |
| 173 | + |
| 174 | + t.add(std::make_unique<stages::FixedState>("end", scene)); |
| 175 | + EXPECT_FALSE(t.plan()); |
| 176 | + EXPECT_STREQ(t.findChild("connect")->failures().front()->comment().c_str(), |
| 177 | + "Trajectory end-point deviates too much from goal state"); |
| 178 | +} |
| 179 | + |
| 180 | +// This test requires a running rosmaster |
153 | 181 | TEST(Task, taskMoveConstructor) { |
154 | 182 | auto create_task = [] { |
155 | 183 | moveit::core::RobotModelConstPtr robot_model = getModel(); |
|
0 commit comments