Skip to content

Commit 7638e5f

Browse files
authored
Merge pull request #495 from ubi-agni/debug-#485
[WIP] Debug/Fix #485
2 parents 275c154 + e163f57 commit 7638e5f

File tree

13 files changed

+188
-40
lines changed

13 files changed

+188
-40
lines changed

core/include/moveit/task_constructor/stage.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -184,6 +184,7 @@ class Stage
184184
void setName(const std::string& name);
185185

186186
uint32_t introspectionId() const;
187+
Introspection* introspection() const;
187188

188189
/** set computation timeout (in seconds)
189190
*

core/include/moveit/task_constructor/stage_p.h

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -301,10 +301,20 @@ class MonitoringGeneratorPrivate : public GeneratorPrivate
301301
};
302302
PIMPL_FUNCTIONS(MonitoringGenerator)
303303

304+
// Print pending pairs of a ConnectingPrivate instance
305+
class ConnectingPrivate;
306+
struct PendingPairsPrinter
307+
{
308+
const ConnectingPrivate* const instance_;
309+
PendingPairsPrinter(const ConnectingPrivate* c) : instance_(c) {}
310+
};
311+
std::ostream& operator<<(std::ostream& os, const PendingPairsPrinter& printer);
312+
304313
class ConnectingPrivate : public ComputeBasePrivate
305314
{
306315
friend class Connecting;
307316
friend struct FallbacksPrivateConnect;
317+
friend std::ostream& operator<<(std::ostream& os, const PendingPairsPrinter& printer);
308318

309319
public:
310320
struct StatePair : std::pair<Interface::const_iterator, Interface::const_iterator>
@@ -337,7 +347,7 @@ class ConnectingPrivate : public ComputeBasePrivate
337347
template <Interface::Direction dir>
338348
bool hasPendingOpposites(const InterfaceState* source, const InterfaceState* target) const;
339349

340-
std::ostream& printPendingPairs(std::ostream& os = std::cerr) const;
350+
PendingPairsPrinter pendingPairsPrinter() const { return PendingPairsPrinter(this); }
341351

342352
private:
343353
// Create a pair of Interface states for pending list, such that the order (start, end) is maintained
@@ -352,5 +362,6 @@ class ConnectingPrivate : public ComputeBasePrivate
352362
ordered<StatePair> pending;
353363
};
354364
PIMPL_FUNCTIONS(Connecting)
365+
355366
} // namespace task_constructor
356367
} // namespace moveit

core/src/container.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ printChildrenInterfaces(const ContainerBasePrivate& container, bool success, con
6666
if (success)
6767
os << ++id << ' ';
6868
if (const auto conn = dynamic_cast<const ConnectingPrivate*>(creator.pimpl()))
69-
conn->printPendingPairs(os);
69+
os << conn->pendingPairsPrinter();
7070
os << std::endl;
7171

7272
for (const auto& child : container.children()) {
@@ -487,7 +487,8 @@ struct SolutionCollector
487487
solutions.emplace_back(std::make_pair(trace, prio));
488488
} else {
489489
for (SolutionBase* successor : next) {
490-
assert(!successor->isFailure()); // We shouldn't have invalid solutions
490+
if (successor->isFailure())
491+
continue; // skip failures
491492
trace.push_back(successor);
492493
traverse(*successor, prio + InterfaceState::Priority(1, successor->cost()));
493494
trace.pop_back();

core/src/introspection.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,8 @@ bool isValidCharInName(char c); // unfortunately this is not declared in ros/na
5555
} // namespace names
5656
} // namespace ros
5757

58+
static const char* LOGGER = "introspection";
59+
5860
namespace moveit {
5961
namespace task_constructor {
6062

@@ -206,6 +208,9 @@ uint32_t Introspection::stageId(const Stage* const s) const {
206208

207209
uint32_t Introspection::solutionId(const SolutionBase& s) {
208210
auto result = impl->id_solution_bimap_.left.insert(std::make_pair(1 + impl->id_solution_bimap_.size(), &s));
211+
if (result.second) // new entry
212+
ROS_DEBUG_STREAM_NAMED(LOGGER, "new solution #" << result.first->first << " (" << s.creator()->name()
213+
<< "): " << s.cost() << " " << s.comment());
209214
return result.first->first;
210215
}
211216

core/src/stage.cpp

Lines changed: 22 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -381,6 +381,9 @@ uint32_t Stage::introspectionId() const {
381381
throw std::runtime_error("Task is not initialized yet or Introspection was disabled.");
382382
return const_cast<const moveit::task_constructor::Introspection*>(pimpl_->introspection_)->stageId(this);
383383
}
384+
Introspection* Stage::introspection() const {
385+
return pimpl_->introspection_;
386+
}
384387

385388
void Stage::forwardProperties(const InterfaceState& source, InterfaceState& dest) {
386389
const PropertyMap& src = source.properties();
@@ -791,20 +794,29 @@ void ConnectingPrivate::newState(Interface::iterator it, Interface::UpdateFlags
791794
assert(it->priority().enabled()); // new solutions are feasible, aren't they?
792795
InterfacePtr other_interface = pullInterface<dir>();
793796
bool have_enabled_opposites = false;
797+
798+
// other interface states to re-enable (post-poned because otherwise order in other_interface changes during loop)
799+
std::vector<Interface::iterator> oit_to_enable;
794800
for (Interface::iterator oit = other_interface->begin(), oend = other_interface->end(); oit != oend; ++oit) {
795801
if (!static_cast<Connecting*>(me_)->compatible(*it, *oit))
796802
continue;
797803

798804
// re-enable the opposing state oit (and its associated solution branch) if its status is ARMED
799805
// https://github.com/ros-planning/moveit_task_constructor/pull/309#issuecomment-974636202
800-
if (oit->priority().status() == InterfaceState::Status::ARMED)
801-
parent_pimpl->setStatus<opposite<dir>()>(me(), &*it, &*oit, InterfaceState::Status::ENABLED);
806+
if (oit->priority().status() == InterfaceState::Status::ARMED) {
807+
oit_to_enable.push_back(oit);
808+
have_enabled_opposites = true;
809+
}
802810
if (oit->priority().enabled())
803811
have_enabled_opposites = true;
804812

805813
// Remember all pending states, regardless of their status!
806814
pending.insert(make_pair<dir>(it, oit));
807815
}
816+
// actually re-enable other interface states, which were scheduled for re-enabling above
817+
for (Interface::iterator oit : oit_to_enable)
818+
parent_pimpl->setStatus<opposite<dir>()>(me(), &*it, &*oit, InterfaceState::Status::ENABLED);
819+
808820
if (!have_enabled_opposites) // prune new state and associated branch if necessary
809821
// pass creator=nullptr to skip hasPendingOpposites() check as we did this here already
810822
parent_pimpl->setStatus<dir>(nullptr, nullptr, &*it, InterfaceState::Status::ARMED);
@@ -823,7 +835,7 @@ void ConnectingPrivate::newState(Interface::iterator it, Interface::UpdateFlags
823835
os << d << " " << this->pullInterface(d) << ": " << *this->pullInterface(d) << std::endl;
824836
}
825837
os << std::setw(15) << " ";
826-
printPendingPairs(os) << std::endl;
838+
os << pendingPairsPrinter() << std::endl;
827839
#endif
828840
}
829841

@@ -853,6 +865,7 @@ template bool ConnectingPrivate::hasPendingOpposites<Interface::BACKWARD>(const
853865
const InterfaceState* start) const;
854866

855867
bool ConnectingPrivate::canCompute() const {
868+
// ROS_DEBUG_STREAM("canCompute " << name() << ": " << pendingPairsPrinter());
856869
// Do we still have feasible pending state pairs?
857870
return !pending.empty() && pending.front().first->priority().enabled() &&
858871
pending.front().second->priority().enabled();
@@ -866,15 +879,16 @@ void ConnectingPrivate::compute() {
866879
static_cast<Connecting*>(me_)->compute(from, to);
867880
}
868881

869-
std::ostream& ConnectingPrivate::printPendingPairs(std::ostream& os) const {
882+
std::ostream& operator<<(std::ostream& os, const PendingPairsPrinter& p) {
883+
const auto* impl = p.instance_;
870884
const char* reset = InterfaceState::colorForStatus(3);
871-
for (const auto& candidate : pending) {
872-
size_t first = getIndex(*starts(), candidate.first);
873-
size_t second = getIndex(*ends(), candidate.second);
885+
for (const auto& candidate : impl->pending) {
886+
size_t first = getIndex(*impl->starts(), candidate.first);
887+
size_t second = getIndex(*impl->ends(), candidate.second);
874888
os << InterfaceState::colorForStatus(candidate.first->priority().status()) << first << reset << ":"
875889
<< InterfaceState::colorForStatus(candidate.second->priority().status()) << second << reset << " ";
876890
}
877-
if (pending.empty())
891+
if (impl->pending.empty())
878892
os << "---";
879893
return os;
880894
}

core/test/CMakeLists.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,10 @@ if (CATKIN_ENABLE_TESTING)
3434
mtc_add_test("gmock" ${ARGN})
3535
endmacro()
3636

37+
mtc_add_gmock(test_mockups.cpp)
3738
mtc_add_gtest(test_stage.cpp)
3839
mtc_add_gtest(test_container.cpp)
39-
mtc_add_gtest(test_serial.cpp)
40+
mtc_add_gmock(test_serial.cpp)
4041
mtc_add_gtest(test_pruning.cpp)
4142
mtc_add_gtest(test_properties.cpp)
4243
mtc_add_gtest(test_cost_terms.cpp)

core/test/stage_mockups.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,19 @@ double PredefinedCosts::cost() const {
4646
return c;
4747
}
4848

49+
void DelayingWrapper::compute() {
50+
if (!delay_.empty()) { // if empty, we don't delay
51+
if (delay_.front() == 0)
52+
delay_.pop_front(); // we can compute() now
53+
else {
54+
--delay_.front(); // continue delaying
55+
return;
56+
}
57+
}
58+
// forward to child, eventually generating multiple solutions at once
59+
WrapperBase::compute();
60+
}
61+
4962
GeneratorMockup::GeneratorMockup(PredefinedCosts&& costs, std::size_t solutions_per_compute)
5063
: Generator{ "GEN" + std::to_string(++id_) }
5164
, costs_{ std::move(costs) }
@@ -86,6 +99,7 @@ void ConnectMockup::compute(const InterfaceState& from, const InterfaceState& to
8699

87100
auto solution{ std::make_shared<SubTrajectory>() };
88101
solution->setCost(costs_.cost());
102+
solution->setComment(std::to_string(from.priority().cost()) + " -> " + std::to_string(to.priority().cost()));
89103
connect(from, to, solution);
90104
}
91105

core/test/stage_mockups.h

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,18 @@ struct PredefinedCosts : CostTerm
3434

3535
constexpr double INF{ std::numeric_limits<double>::infinity() };
3636

37+
/* wrapper stage to delay solutions by a given number of steps */
38+
struct DelayingWrapper : public WrapperBase
39+
{
40+
std::list<unsigned int> delay_;
41+
/* delay list specifies the number of steps each received solution should be delayed */
42+
DelayingWrapper(std::list<unsigned int> delay, Stage::pointer&& child)
43+
: WrapperBase("delayer", std::move(child)), delay_{ std::move(delay) } {}
44+
45+
void compute() override;
46+
void onNewSolution(const SolutionBase& s) override { liftSolution(s); }
47+
};
48+
3749
struct GeneratorMockup : public Generator
3850
{
3951
planning_scene::PlanningScenePtr ps_;
@@ -47,8 +59,8 @@ struct GeneratorMockup : public Generator
4759
// default to one solution to avoid infinity loops
4860
GeneratorMockup(PredefinedCosts&& costs = PredefinedCosts{ std::list<double>{ 0.0 }, true },
4961
std::size_t solutions_per_compute = 1);
50-
GeneratorMockup(std::initializer_list<double> costs)
51-
: GeneratorMockup{ PredefinedCosts{ std::list<double>{ costs }, true } } {}
62+
GeneratorMockup(std::initializer_list<double> costs, std::size_t solutions_per_compute = 1)
63+
: GeneratorMockup{ PredefinedCosts{ std::list<double>{ costs }, true }, solutions_per_compute } {}
5264

5365
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
5466
bool canCompute() const override;

core/test/test_container.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ class InitTest : public ::testing::Test
110110
Container container;
111111
InterfacePtr dummy;
112112

113-
InitTest() : ::testing::Test{}, robot_model{ getModel() }, dummy{ new Interface } {}
113+
InitTest() : ::testing::Test{}, robot_model{ getModel() }, dummy{ std::make_shared<Interface>() } {}
114114

115115
void pushInterface(bool start = true, bool end = true) {
116116
// pretend, that the container is connected

core/test/test_mockups.cpp

Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
#include "stage_mockups.h"
2+
#include <moveit/task_constructor/container_p.h>
3+
4+
using namespace moveit::task_constructor;
5+
6+
struct TestGeneratorMockup : public GeneratorMockup
7+
{
8+
InterfacePtr next_starts_;
9+
InterfacePtr prev_ends_;
10+
11+
using GeneratorMockup::GeneratorMockup;
12+
using GeneratorMockup::init;
13+
14+
void init() {
15+
next_starts_ = std::make_shared<Interface>();
16+
prev_ends_ = std::make_shared<Interface>();
17+
18+
GeneratorMockup::reset();
19+
GeneratorMockup::init(getModel());
20+
21+
GeneratorPrivate* impl = pimpl();
22+
impl->setNextStarts(next_starts_);
23+
impl->setPrevEnds(prev_ends_);
24+
}
25+
};
26+
27+
TEST(GeneratorMockup, compute) {
28+
TestGeneratorMockup gen({ 1.0, 2.0, 3.0 });
29+
gen.init();
30+
31+
for (int i = 0; i < 3; ++i) {
32+
ASSERT_TRUE(gen.canCompute());
33+
gen.compute();
34+
}
35+
EXPECT_FALSE(gen.canCompute());
36+
37+
EXPECT_COSTS(gen.solutions(), ::testing::ElementsAre(1, 2, 3));
38+
}
39+
40+
#define COMPUTE_EXPECT_COSTS(stage, ...) \
41+
{ \
42+
EXPECT_TRUE(stage.canCompute()); \
43+
stage.compute(); \
44+
EXPECT_COSTS(stage.solutions(), ::testing::ElementsAre(__VA_ARGS__)); \
45+
constexpr auto num_elements = std::initializer_list<double>{ __VA_ARGS__ }.size(); \
46+
EXPECT_EQ(runs, num_elements); \
47+
}
48+
49+
TEST(GeneratorMockup, delayed) {
50+
auto gen = std::make_unique<TestGeneratorMockup>(PredefinedCosts({ 1.0, 2.0, 3.0 }));
51+
gen->init();
52+
auto& runs = gen->runs_;
53+
54+
DelayingWrapper w({ 1, 0, 2 }, std::move(gen));
55+
auto prev_ends = std::make_shared<Interface>();
56+
auto next_starts = std::make_shared<Interface>();
57+
58+
WrapperBasePrivate* impl = w.pimpl();
59+
impl->setPrevEnds(prev_ends);
60+
impl->setNextStarts(next_starts);
61+
62+
// 1st compute() is delayed by 1
63+
COMPUTE_EXPECT_COSTS(w);
64+
COMPUTE_EXPECT_COSTS(w, 1);
65+
66+
// 2nd compute() is not delayed
67+
COMPUTE_EXPECT_COSTS(w, 1, 2);
68+
69+
// 1st compute() is delayed by 2
70+
COMPUTE_EXPECT_COSTS(w, 1, 2);
71+
COMPUTE_EXPECT_COSTS(w, 1, 2);
72+
COMPUTE_EXPECT_COSTS(w, 1, 2, 3);
73+
74+
EXPECT_FALSE(w.canCompute());
75+
}
76+
#undef COMPUTE_EXPECT_COSTS

0 commit comments

Comments
 (0)