Skip to content

Commit fa93630

Browse files
committed
Merge branch 'master' into ros2
2 parents cfc3b20 + e217ddf commit fa93630

8 files changed

Lines changed: 41 additions & 25 deletions

File tree

.github/workflows/ci.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ jobs:
5151
name: "${{ matrix.env.IMAGE }}${{ matrix.env.NAME && ' • ' || ''}}${{ matrix.env.NAME }}${{ matrix.env.CLANG_TIDY && ' • clang-tidy' || '' }}"
5252
runs-on: ubuntu-latest
5353
steps:
54-
- uses: actions/checkout@v4
54+
- uses: actions/checkout@v6
5555
with:
5656
submodules: recursive
5757

@@ -78,14 +78,14 @@ jobs:
7878
subdir: target_ws/install
7979

8080
- name: Upload test artifacts (on failure)
81-
uses: actions/upload-artifact@v4
81+
uses: actions/upload-artifact@v7
8282
if: failure() && (steps.ici.outputs.run_target_test || steps.ici.outputs.target_test_results)
8383
with:
8484
name: test-results-${{ matrix.env.IMAGE }}${{ matrix.env.NAME && '-' || ''}}${{ matrix.env.NAME }}${{ matrix.env.CLANG_TIDY && '-clang-tidy' || '' }}
8585
path: ${{ env.BASEDIR }}/target_ws/**/test_results/**/*.xml
8686

8787
- name: Upload clang-tidy fixes (on failure)
88-
uses: actions/upload-artifact@v4
88+
uses: actions/upload-artifact@v7
8989
if: failure() && steps.ici.outputs.clang_tidy_checks
9090
with:
9191
name: clang-tidy-fixes.yaml
@@ -106,7 +106,7 @@ jobs:
106106
lcov_capture_args: --ignore-errors=source,gcov,mismatch,negative
107107
ignore: '"*/target_ws/build/*" "*/target_ws/install/*" "*/test/*"'
108108
- name: Upload codecov report
109-
uses: codecov/codecov-action@v3
109+
uses: codecov/codecov-action@v6
110110
if: contains(matrix.env.TARGET_CMAKE_ARGS, '--coverage') && steps.ici.outputs.target_test_results == '0'
111111
with:
112112
files: ${{ env.BASEDIR }}/target_ws/coverage.info

.github/workflows/format.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ jobs:
1313
name: pre-commit
1414
runs-on: ubuntu-latest
1515
steps:
16-
- uses: actions/checkout@v4
16+
- uses: actions/checkout@v6
1717
with:
1818
submodules: recursive
1919
- name: Install clang-format-14

.github/workflows/prerelease.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ jobs:
3434
# free up a lot of stuff from /usr/local
3535
sudo rm -rf /usr/local
3636
df -h
37-
- uses: actions/checkout@v4
37+
- uses: actions/checkout@v6
3838
with:
3939
submodules: recursive
4040
- name: industrial_ci

.pre-commit-config.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
repos:
1616
# Standard hooks
1717
- repo: https://github.com/pre-commit/pre-commit-hooks
18-
rev: v5.0.0
18+
rev: v6.0.0
1919
hooks:
2020
- id: check-added-large-files
2121
- id: check-case-conflict
@@ -29,7 +29,7 @@ repos:
2929
- id: trailing-whitespace
3030

3131
- repo: https://github.com/psf/black
32-
rev: 25.1.0
32+
rev: 26.3.1
3333
hooks:
3434
- id: black
3535
args: ["--line-length", "100"]

core/src/container.cpp

Lines changed: 15 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -328,7 +328,7 @@ void ContainerBasePrivate::liftSolution(const SolutionBasePtr& solution, const I
328328

329329
ContainerBase::ContainerBase(ContainerBasePrivate* impl) : Stage(impl) {
330330
auto& p = properties();
331-
p.declare<bool>("pruning", std::string("enable pruning?")).configureInitFrom(Stage::PARENT, "pruning");
331+
p.declare<bool>("pruning", false, std::string("enable pruning?")).configureInitFrom(Stage::PARENT, "pruning");
332332
}
333333

334334
size_t ContainerBase::numChildren() const {
@@ -535,24 +535,24 @@ void SerialContainer::onNewSolution(const SolutionBase& current) {
535535
SolutionCollector<Interface::BACKWARD> incoming(num_before, current);
536536
SolutionCollector<Interface::FORWARD> outgoing(num_after, current);
537537

538-
// collect (and sort) all solutions spanning from start to end of this container
539-
ordered<SolutionSequencePtr> sorted;
538+
// collect (and lift) all solutions spanning from start to end of this container
540539
for (auto& in : incoming.solutions) {
541540
for (auto& out : outgoing.solutions) {
542541
InterfaceState::Priority prio = in.second + InterfaceState::Priority(1u, current.cost()) + out.second;
543542
assert(prio.enabled());
544543
// found a complete solution path connecting start to end?
545544
if (prio.depth() == children.size()) {
546-
SolutionSequence::container_type solution;
547-
solution.reserve(children.size());
545+
SolutionSequence::container_type seq;
546+
seq.reserve(children.size());
548547
// insert incoming solutions in reverse order
549-
solution.insert(solution.end(), in.first.rbegin(), in.first.rend());
548+
seq.insert(seq.end(), in.first.rbegin(), in.first.rend());
550549
// insert current solution
551-
solution.push_back(&current);
550+
seq.push_back(&current);
552551
// insert outgoing solutions in normal order
553-
solution.insert(solution.end(), out.first.begin(), out.first.end());
554-
// store solution in sorted list
555-
sorted.insert(std::make_shared<SolutionSequence>(std::move(solution), prio.cost(), this));
552+
seq.insert(seq.end(), out.first.begin(), out.first.end());
553+
// create SolutionSequence and lift it to external interface
554+
auto solution = std::make_shared<SolutionSequence>(std::move(seq), prio.cost(), this);
555+
impl->liftSolution(solution, solution->internalStart(), solution->internalEnd());
556556
}
557557
if (prio.depth() > 1) {
558558
// update state priorities along the whole partial solution path
@@ -562,10 +562,6 @@ void SerialContainer::onNewSolution(const SolutionBase& current) {
562562
}
563563
}
564564
// printChildrenInterfaces(*this->pimpl(), true, *current.creator());
565-
566-
// finally, store + announce new solutions to external interface
567-
for (const auto& solution : sorted)
568-
impl->liftSolution(solution, solution->internalStart(), solution->internalEnd());
569565
}
570566

571567
SerialContainer::SerialContainer(SerialContainerPrivate* impl) : ContainerBase(impl) {}
@@ -1035,6 +1031,11 @@ bool FallbacksPrivatePropagator::nextJob() {
10351031
}
10361032

10371033
// When arriving here, we have a valid job_ and a current_ child to feed it. Let's do that.
1034+
if (dir_ == Interface::FORWARD)
1035+
setStatus<Interface::BACKWARD>(nullptr, nullptr, &*job_, InterfaceState::Status::ENABLED);
1036+
else
1037+
setStatus<Interface::FORWARD>(nullptr, nullptr, &*job_, InterfaceState::Status::ENABLED);
1038+
10381039
copyState(dir_, job_, (*current_)->pimpl()->pullInterface(dir_), Interface::UpdateFlags());
10391040
return true;
10401041
}

core/src/stage.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ void InitStageException::append(InitStageException& other) {
8686
}
8787

8888
const char* InitStageException::what() const noexcept {
89-
static const char* msg = "Error initializing stage(s). RCLCPP_ERROR_STREAM(e) for details.";
89+
static const char* msg = "mtc::InitStageException. Use RCLCPP_ERROR_STREAM(exc) for details.";
9090
return msg;
9191
}
9292

@@ -821,7 +821,7 @@ void ConnectingPrivate::newState(Interface::iterator it, Interface::UpdateFlags
821821
for (Interface::iterator oit : oit_to_enable)
822822
parent_pimpl->setStatus<opposite<dir>()>(me(), &*it, &*oit, InterfaceState::Status::ENABLED);
823823

824-
if (!have_enabled_opposites) // prune new state and associated branch if necessary
824+
if (!have_enabled_opposites && parent()->pruning()) // prune new state and associated branch if necessary
825825
// pass creator=nullptr to skip hasPendingOpposites() check as we did this here already
826826
parent_pimpl->setStatus<dir>(nullptr, nullptr, &*it, InterfaceState::Status::ARMED);
827827
}

core/src/task.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -95,7 +95,6 @@ const ContainerBase* TaskPrivate::stages() const {
9595

9696
Task::Task(const std::string& ns, bool introspection, ContainerBase::pointer&& container)
9797
: WrapperBase(new TaskPrivate(this, ns), std::move(container)) {
98-
setPruning(false);
9998
setTimeout(std::numeric_limits<double>::max());
10099

101100
// monitor state on commandline

core/test/test_fallback.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -196,3 +196,19 @@ TEST_F(FallbacksFixtureConnect, connectStageInsideFallbacks) {
196196
EXPECT_TRUE(t.plan());
197197
EXPECT_COSTS(t.solutions(), testing::ElementsAre(11, 12, 22, 121));
198198
}
199+
200+
TEST_F(FallbacksFixtureConnect, connectInsideSerialInsideFallbacks) {
201+
t.add(std::make_unique<GeneratorMockup>(PredefinedCosts({ 0.0 })));
202+
auto fallbacks = std::make_unique<Fallbacks>("Fallbacks");
203+
auto serial = std::make_unique<SerialContainer>("Serial1");
204+
serial->add(std::make_unique<ForwardMockup>(PredefinedCosts::constant(0.0)));
205+
serial->add(std::make_unique<ConnectMockup>(PredefinedCosts::constant(1.0)));
206+
serial->add(std::make_unique<BackwardMockup>(PredefinedCosts::constant(INF)));
207+
serial->add(std::make_unique<GeneratorMockup>(PredefinedCosts::single(2.0)));
208+
fallbacks->add(std::move(serial));
209+
fallbacks->add(std::make_unique<ForwardMockup>(PredefinedCosts::constant(4.0)));
210+
211+
t.add(std::move(fallbacks));
212+
EXPECT_TRUE(t.plan());
213+
EXPECT_COSTS(t.solutions(), testing::ElementsAre(4.0));
214+
}

0 commit comments

Comments
 (0)