promise to not modify solutions

This commit is contained in:
Robert Haschke 2017-12-13 12:17:31 +01:00
parent e9363919e8
commit 104e52eb48
7 changed files with 11 additions and 11 deletions

View File

@ -68,7 +68,7 @@ public:
virtual bool compute() = 0;
/// called by a (direct) child when a new solution becomes available
virtual void onNewSolution(SolutionBase& t) = 0;
virtual void onNewSolution(const SolutionBase& s) = 0;
protected:
ContainerBase(ContainerBasePrivate* impl);
@ -96,7 +96,7 @@ public:
protected:
/// called by a (direct) child when a new solution becomes available
void onNewSolution(SolutionBase &s) override;
void onNewSolution(const SolutionBase &s) override;
/// function type used for traversing solutions
/// For each sub solution (current), the trace from the start as well as the
@ -142,7 +142,7 @@ protected:
ParallelContainerBase(ParallelContainerBasePrivate* impl);
/// called by a (direct) child when a new solution becomes available
void onNewSolution(SolutionBase &s) override;
void onNewSolution(const SolutionBase &s) override;
/// callback for new start states (received externally)
virtual void onNewStartState(const InterfaceState &external) = 0;

View File

@ -158,7 +158,7 @@ PIMPL_FUNCTIONS(SerialContainer)
* have separate incoming/outgoing trajectories */
class WrappedSolution : public SolutionBase {
public:
explicit WrappedSolution(StagePrivate* creator, SolutionBase* wrapped)
explicit WrappedSolution(StagePrivate* creator, const SolutionBase* wrapped)
: SolutionBase(creator, wrapped->cost()), wrapped_(wrapped)
{}
void fillMessage(moveit_task_constructor_msgs::Solution &solution,
@ -167,7 +167,7 @@ public:
}
private:
SolutionBase* wrapped_;
const SolutionBase* wrapped_;
};

View File

@ -92,7 +92,7 @@ public:
inline void setPrevEnds(const InterfacePtr& prev_ends) { prev_ends_ = prev_ends; }
inline void setNextStarts(const InterfacePtr& next_starts) { next_starts_ = next_starts; }
void newSolution(SolutionBase &current);
void newSolution(const SolutionBase &current);
protected:
Stage* const me_; // associated/owning Stage instance

View File

@ -120,7 +120,7 @@ protected:
void initScene();
bool canCompute() const override;
bool compute() override;
void onNewSolution(SolutionBase &s) override;
void onNewSolution(const SolutionBase &s) override;
private:
std::string id_;

View File

@ -233,7 +233,7 @@ struct SolutionCollector {
const StagePrivate* const stopping_stage;
};
void SerialContainer::onNewSolution(SolutionBase &current)
void SerialContainer::onNewSolution(const SolutionBase &current)
{
const StagePrivate *creator = current.creator();
auto& children = pimpl()->children();
@ -495,7 +495,7 @@ ParallelContainerBasePrivate::ParallelContainerBasePrivate(ParallelContainerBase
}));
}
void ParallelContainerBase::onNewSolution(SolutionBase &s)
void ParallelContainerBase::onNewSolution(const SolutionBase &s)
{
auto impl = pimpl();
WrappedSolution wrapped(impl, &s);

View File

@ -102,7 +102,7 @@ void StagePrivate::validate() const {
if (errors) throw errors;
}
void StagePrivate::newSolution(SolutionBase &solution)
void StagePrivate::newSolution(const SolutionBase &solution)
{
for (const auto& cb : solution_cbs_)
cb(solution);

View File

@ -235,7 +235,7 @@ void Task::publishAllSolutions(bool wait)
introspection_->publishAllSolutions(wait);
}
void Task::onNewSolution(SolutionBase &s)
void Task::onNewSolution(const SolutionBase &s)
{
pimpl()->newSolution(s);
if (introspection_)