Skip to content

Commit 5720b83

Browse files
Connect: ensure end-state matches goal state (moveit#532)
1 parent 7638e5f commit 5720b83

File tree

3 files changed

+40
-2
lines changed

3 files changed

+40
-2
lines changed

core/include/moveit/task_constructor/stages/connect.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ class Connect : public Connecting
7676
using GroupPlannerVector = std::vector<std::pair<std::string, solvers::PlannerInterfacePtr> >;
7777
Connect(const std::string& name = "connect", const GroupPlannerVector& planners = {});
7878

79+
void setMaxDistance(double max_distance) { setProperty("max_distance", max_distance); }
7980
void setPathConstraints(moveit_msgs::Constraints path_constraints) {
8081
setProperty("path_constraints", std::move(path_constraints));
8182
}

core/src/stages/connect.cpp

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,7 @@ Connect::Connect(const std::string& name, const GroupPlannerVector& planners) :
5555

5656
auto& p = properties();
5757
p.declare<MergeMode>("merge_mode", WAYPOINTS, "merge mode");
58+
p.declare<double>("max_distance", 1e-4, "maximally accepted distance between end and goal sate");
5859
p.declare<moveit_msgs::Constraints>("path_constraints", moveit_msgs::Constraints(),
5960
"constraints to maintain during trajectory");
6061
properties().declare<TimeParameterizationPtr>("merge_time_parameterization",
@@ -136,6 +137,7 @@ void Connect::compute(const InterfaceState& from, const InterfaceState& to) {
136137
const auto& props = properties();
137138
double timeout = this->timeout();
138139
MergeMode mode = props.get<MergeMode>("merge_mode");
140+
double max_distance = props.get<double>("max_distance");
139141
const auto& path_constraints = props.get<moveit_msgs::Constraints>("path_constraints");
140142

141143
const moveit::core::RobotState& final_goal_state = to.scene()->getCurrentState();
@@ -146,6 +148,7 @@ void Connect::compute(const InterfaceState& from, const InterfaceState& to) {
146148
intermediate_scenes.push_back(start);
147149

148150
bool success = false;
151+
std::string comment;
149152
std::vector<double> positions;
150153
for (const GroupPlannerVector::value_type& pair : planner_) {
151154
// set intermediate goal state
@@ -164,6 +167,12 @@ void Connect::compute(const InterfaceState& from, const InterfaceState& to) {
164167
if (!success)
165168
break;
166169

170+
if (trajectory->getLastWayPoint().distance(goal_state, jmg) > max_distance) {
171+
success = false;
172+
comment = "Trajectory end-point deviates too much from goal state";
173+
break;
174+
}
175+
167176
// continue from reached state
168177
start = end;
169178
}
@@ -174,7 +183,7 @@ void Connect::compute(const InterfaceState& from, const InterfaceState& to) {
174183
if (!solution) // success == false or merging failed: store sequentially
175184
solution = makeSequential(sub_trajectories, intermediate_scenes, from, to);
176185
if (!success) // error during sequential planning
177-
solution->markAsFailure();
186+
solution->markAsFailure(comment);
178187
connect(from, to, solution);
179188
}
180189

core/test/test_move_to.cpp

Lines changed: 29 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,10 @@
33

44
#include <moveit/task_constructor/task.h>
55
#include <moveit/task_constructor/stages/move_to.h>
6+
#include <moveit/task_constructor/stages/connect.h>
67
#include <moveit/task_constructor/stages/fixed_state.h>
78
#include <moveit/task_constructor/solvers/joint_interpolation.h>
9+
#include <moveit/task_constructor/solvers/cartesian_path.h>
810

911
#include <moveit/planning_scene/planning_scene.h>
1012

@@ -149,7 +151,33 @@ TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) {
149151
EXPECT_ONE_SOLUTION;
150152
}
151153

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
153181
TEST(Task, taskMoveConstructor) {
154182
auto create_task = [] {
155183
moveit::core::RobotModelConstPtr robot_model = getModel();

0 commit comments

Comments
 (0)