Skip to content

Commit 9ea1692

Browse files
authored
Correctly report failures instead of issueing console warnings
Don't use command-line warnings, but spawn failure solutions.
1 parent 8318546 commit 9ea1692

File tree

11 files changed

+55
-26
lines changed

11 files changed

+55
-26
lines changed

core/include/moveit/task_constructor/container.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ class ContainerBase : public Stage
8080

8181
virtual bool canCompute() const = 0;
8282
virtual void compute() = 0;
83-
void explainFailure(std::ostream& os) const override;
83+
bool explainFailure(std::ostream& os) const override;
8484

8585
/// called by a (direct) child when a new solution becomes available
8686
virtual void onNewSolution(const SolutionBase& s) = 0;

core/include/moveit/task_constructor/stage.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -242,7 +242,7 @@ class Stage
242242
/// Should we generate failure solutions? Note: Always report a failure!
243243
bool storeFailures() const;
244244

245-
virtual void explainFailure(std::ostream& os) const;
245+
virtual bool explainFailure(std::ostream& /*os*/) const { return false; };
246246

247247
/// Get the stage's property map
248248
PropertyMap& properties();

core/include/moveit/task_constructor/task.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ class Task : protected WrapperBase
137137
void printState(std::ostream& os = std::cout) const;
138138

139139
/// print an explanation for a planning failure to os
140-
void explainFailure(std::ostream& os = std::cout) const override;
140+
bool explainFailure(std::ostream& os = std::cout) const override;
141141

142142
size_t numSolutions() const { return solutions().size(); }
143143
const ordered<SolutionBaseConstPtr>& solutions() const { return stages()->solutions(); }

core/src/container.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -452,18 +452,21 @@ void ContainerBase::init(const moveit::core::RobotModelConstPtr& robot_model) {
452452
throw errors;
453453
}
454454

455-
void ContainerBase::explainFailure(std::ostream& os) const {
455+
bool ContainerBase::explainFailure(std::ostream& os) const {
456456
for (const auto& stage : pimpl()->children()) {
457457
if (!stage->solutions().empty())
458458
continue; // skip deeper traversal, this stage produced solutions
459459
if (stage->numFailures()) {
460460
os << stage->name() << " (0/" << stage->numFailures() << ")";
461-
stage->explainFailure(os);
461+
if (!stage->failures().empty())
462+
os << ": " << stage->failures().front()->comment();
462463
os << '\n';
463-
break;
464+
return true;
464465
}
465-
stage->explainFailure(os); // recursively process children
466+
if (stage->explainFailure(os)) // recursively process children
467+
return true;
466468
}
469+
return false;
467470
}
468471

469472
std::ostream& operator<<(std::ostream& os, const ContainerBase& container) {

core/src/stage.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -436,11 +436,6 @@ bool Stage::storeFailures() const {
436436
return pimpl()->storeFailures();
437437
}
438438

439-
void Stage::explainFailure(std::ostream& os) const {
440-
if (!failures().empty())
441-
os << ": " << failures().front()->comment();
442-
}
443-
444439
PropertyMap& Stage::properties() {
445440
return pimpl()->properties_;
446441
}

core/src/stages/compute_ik.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -251,16 +251,23 @@ void ComputeIK::compute() {
251251
const moveit::core::JointModelGroup* jmg = nullptr;
252252
std::string msg;
253253

254+
auto report_failure = [&s, this](const std::string& msg) {
255+
planning_scene::PlanningScenePtr scene = s.start()->scene()->diff();
256+
SubTrajectory solution;
257+
solution.markAsFailure(msg);
258+
spawn(InterfaceState(scene), std::move(solution));
259+
};
260+
254261
if (!validateEEF(props, robot_model, eef_jmg, &msg)) {
255-
ROS_WARN_STREAM_NAMED("ComputeIK", msg);
262+
report_failure(msg);
256263
return;
257264
}
258265
if (!validateGroup(props, robot_model, eef_jmg, jmg, &msg)) {
259-
ROS_WARN_STREAM_NAMED("ComputeIK", msg);
266+
report_failure(msg);
260267
return;
261268
}
262269
if (!eef_jmg && !jmg) {
263-
ROS_WARN_STREAM_NAMED("ComputeIK", "Neither eef nor group are well defined");
270+
report_failure(msg);
264271
return;
265272
}
266273
properties().property("timeout").setDefaultValue(jmg->getDefaultIKTimeout());
@@ -274,8 +281,7 @@ void ComputeIK::compute() {
274281
tf2::fromMsg(target_pose_msg.pose, target_pose);
275282
if (target_pose_msg.header.frame_id != scene->getPlanningFrame()) {
276283
if (!scene->knowsFrameTransform(target_pose_msg.header.frame_id)) {
277-
ROS_WARN_STREAM_NAMED("ComputeIK",
278-
"Unknown reference frame for target pose: " << target_pose_msg.header.frame_id);
284+
report_failure(fmt::format("Unknown reference frame for target pose: '{}'", target_pose_msg.header.frame_id));
279285
return;
280286
}
281287
// transform target_pose w.r.t. planning frame
@@ -290,7 +296,7 @@ void ComputeIK::compute() {
290296
// determine IK link from eef/group
291297
if (!(link = eef_jmg ? robot_model->getLinkModel(eef_jmg->getEndEffectorParentGroup().second) :
292298
jmg->getOnlyOneEndEffectorTip())) {
293-
ROS_WARN_STREAM_NAMED("ComputeIK", "Failed to derive IK target link");
299+
report_failure("Failed to derive IK target link");
294300
return;
295301
}
296302
ik_pose_msg.header.frame_id = link->getName();
@@ -301,8 +307,7 @@ void ComputeIK::compute() {
301307
tf2::fromMsg(ik_pose_msg.pose, ik_pose);
302308

303309
if (!scene->getCurrentState().knowsFrameTransform(ik_pose_msg.header.frame_id)) {
304-
ROS_WARN_STREAM_NAMED("ComputeIK",
305-
fmt::format("ik frame unknown in robot: '{}'", ik_pose_msg.header.frame_id));
310+
report_failure(fmt::format("ik frame unknown in robot: '{}'", ik_pose_msg.header.frame_id));
306311
return;
307312
}
308313
ik_pose = scene->getCurrentState().getFrameTransform(ik_pose_msg.header.frame_id) * ik_pose;

core/src/stages/current_state.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
/* Authors: Michael Goerner, Luca Lach, Robert Haschke */
3737

3838
#include <chrono>
39+
#include <fmt/format.h>
3940

4041
#include <moveit/task_constructor/stages/current_state.h>
4142
#include <moveit/task_constructor/storage.h>
@@ -96,7 +97,13 @@ void CurrentState::compute() {
9697
return;
9798
}
9899
}
99-
ROS_WARN("failed to acquire current PlanningScene");
100+
if (storeFailures()) {
101+
SubTrajectory solution;
102+
solution.markAsFailure(
103+
fmt::format("Failed to acquire current PlanningScene within timeout of {}s", timeout.toSec()));
104+
spawn(InterfaceState(scene_), std::move(solution));
105+
} else
106+
ROS_WARN_STREAM_NAMED("CurrentState", "Failed to acquire current PlanningScene");
100107
}
101108
} // namespace stages
102109
} // namespace task_constructor

core/src/stages/fixed_cartesian_poses.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@
3434

3535
/* Authors: Robert Haschke */
3636

37+
#include <fmt/format.h>
38+
3739
#include <moveit/task_constructor/stages/fixed_cartesian_poses.h>
3840
#include <moveit/task_constructor/storage.h>
3941
#include <moveit/task_constructor/cost_terms.h>
@@ -86,7 +88,12 @@ void FixedCartesianPoses::compute() {
8688
if (pose.header.frame_id.empty())
8789
pose.header.frame_id = scene->getPlanningFrame();
8890
else if (!scene->knowsFrameTransform(pose.header.frame_id)) {
89-
ROS_WARN_NAMED("FixedCartesianPoses", "Unknown frame: '%s'", pose.header.frame_id.c_str());
91+
if (storeFailures()) {
92+
SubTrajectory trajectory;
93+
trajectory.markAsFailure(fmt::format("Unknown frame: '{}'", pose.header.frame_id));
94+
spawn(InterfaceState(scene), std::move(trajectory));
95+
} else
96+
ROS_WARN_NAMED("FixedCartesianPoses", "Unknown frame: '%s'", pose.header.frame_id.c_str());
9097
continue;
9198
}
9299

core/src/stages/generate_pose.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040
#include <moveit/task_constructor/marker_tools.h>
4141
#include <moveit/planning_scene/planning_scene.h>
4242
#include <rviz_marker_tools/marker_creation.h>
43+
#include <fmt/format.h>
4344

4445
namespace moveit {
4546
namespace task_constructor {
@@ -77,7 +78,12 @@ void GeneratePose::compute() {
7778
if (target_pose.header.frame_id.empty())
7879
target_pose.header.frame_id = scene->getPlanningFrame();
7980
else if (!scene->knowsFrameTransform(target_pose.header.frame_id)) {
80-
ROS_WARN_NAMED("GeneratePose", "Unknown frame: '%s'", target_pose.header.frame_id.c_str());
81+
if (storeFailures()) {
82+
SubTrajectory trajectory;
83+
trajectory.markAsFailure(fmt::format("Unknown frame: '{}'", target_pose.header.frame_id));
84+
spawn(InterfaceState(scene), std::move(trajectory));
85+
} else
86+
ROS_WARN_NAMED("GeneratePose", "Unknown frame: '%s'", target_pose.header.frame_id.c_str());
8187
return;
8288
}
8389

core/src/stages/generate_random_pose.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include <Eigen/Geometry>
4444
#include <tf2_eigen/tf2_eigen.h>
4545

46+
#include <fmt/format.h>
4647
#include <chrono>
4748

4849
namespace {
@@ -94,7 +95,12 @@ void GenerateRandomPose::compute() {
9495
if (seed_pose.header.frame_id.empty())
9596
seed_pose.header.frame_id = scene->getPlanningFrame();
9697
else if (!scene->knowsFrameTransform(seed_pose.header.frame_id)) {
97-
ROS_WARN_NAMED("GenerateRandomPose", "Unknown frame: '%s'", seed_pose.header.frame_id.c_str());
98+
if (storeFailures()) {
99+
SubTrajectory trajectory;
100+
trajectory.markAsFailure(fmt::format("Unknown frame: '{}'", seed_pose.header.frame_id));
101+
spawn(InterfaceState(scene), std::move(trajectory));
102+
} else
103+
ROS_WARN_NAMED("GenerateRandomPose", "Unknown frame: '%s'", seed_pose.header.frame_id.c_str());
98104
return;
99105
}
100106

0 commit comments

Comments
 (0)