Skip to content

End-state deviates from goal state #532

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 8 commits into from
Feb 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions core/include/moveit/task_constructor/stages/connect.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ class Connect : public Connecting
using GroupPlannerVector = std::vector<std::pair<std::string, solvers::PlannerInterfacePtr> >;
Connect(const std::string& name = "connect", const GroupPlannerVector& planners = {});

void setMaxDistance(double max_distance) { setProperty("max_distance", max_distance); }
void setPathConstraints(moveit_msgs::Constraints path_constraints) {
setProperty("path_constraints", std::move(path_constraints));
}
Expand Down
11 changes: 10 additions & 1 deletion core/src/stages/connect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ Connect::Connect(const std::string& name, const GroupPlannerVector& planners) :

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

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

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

if (trajectory->getLastWayPoint().distance(goal_state, jmg) > max_distance) {
success = false;
comment = "Trajectory end-point deviates too much from goal state";
break;
}

// continue from reached state
start = end;
}
Expand All @@ -174,7 +183,7 @@ void Connect::compute(const InterfaceState& from, const InterfaceState& to) {
if (!solution) // success == false or merging failed: store sequentially
solution = makeSequential(sub_trajectories, intermediate_scenes, from, to);
if (!success) // error during sequential planning
solution->markAsFailure();
solution->markAsFailure(comment);
connect(from, to, solution);
}

Expand Down
30 changes: 29 additions & 1 deletion core/test/test_move_to.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,10 @@

#include <moveit/task_constructor/task.h>
#include <moveit/task_constructor/stages/move_to.h>
#include <moveit/task_constructor/stages/connect.h>
#include <moveit/task_constructor/stages/fixed_state.h>
#include <moveit/task_constructor/solvers/joint_interpolation.h>
#include <moveit/task_constructor/solvers/cartesian_path.h>

#include <moveit/planning_scene/planning_scene.h>

Expand Down Expand Up @@ -149,7 +151,33 @@ TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) {
EXPECT_ONE_SOLUTION;
}

// This test require a running rosmaster
// Using a Cartesian interpolation planner targeting a joint-space goal, which is
// transformed into a Cartesian goal by FK, should fail if the two poses are on different
// IK solution branches. In this case, the end-state, although reaching the Cartesian goal,
// will strongly deviate from the joint-space goal.
TEST(Panda, connectCartesianBranchesFails) {
Task t;
t.setRobotModel(loadModel());
auto scene = std::make_shared<PlanningScene>(t.getRobotModel());
scene->getCurrentStateNonConst().setToDefaultValues();
scene->getCurrentStateNonConst().setToDefaultValues(t.getRobotModel()->getJointModelGroup("panda_arm"), "ready");
t.add(std::make_unique<stages::FixedState>("start", scene));

stages::Connect::GroupPlannerVector planner = { { "panda_arm", std::make_shared<solvers::CartesianPath>() } };
t.add(std::make_unique<stages::Connect>("connect", planner));

// target an elbow-left instead of an elbow-right solution (different solution branch)
scene = scene->diff();
scene->getCurrentStateNonConst().setJointGroupPositions(
"panda_arm", std::vector<double>({ 2.72, 0.78, -2.63, -2.35, 0.36, 1.57, 0.48 }));

t.add(std::make_unique<stages::FixedState>("end", scene));
EXPECT_FALSE(t.plan());
EXPECT_STREQ(t.findChild("connect")->failures().front()->comment().c_str(),
"Trajectory end-point deviates too much from goal state");
}

// This test requires a running rosmaster
TEST(Task, taskMoveConstructor) {
auto create_task = [] {
moveit::core::RobotModelConstPtr robot_model = getModel();
Expand Down