mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
fixed some clang warnings
This commit is contained in:
parent
b60047318a
commit
1403fc9830
@ -232,7 +232,7 @@ protected:
|
|||||||
Wrapper(WrapperPrivate* impl, pointer &&child = Stage::pointer());
|
Wrapper(WrapperPrivate* impl, pointer &&child = Stage::pointer());
|
||||||
|
|
||||||
/// called by a (direct) child when a new solution becomes available
|
/// called by a (direct) child when a new solution becomes available
|
||||||
void onNewSolution(const SolutionBase &s) = 0;
|
void onNewSolution(const SolutionBase &s) override = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
} }
|
} }
|
||||||
|
|||||||
@ -296,12 +296,12 @@ DisplaySolutionPtr RemoteTaskModel::processSolutionMessage(const moveit_task_con
|
|||||||
for (const auto& sub : msg.sub_solution) {
|
for (const auto& sub : msg.sub_solution) {
|
||||||
if (sub.id == 0) continue;
|
if (sub.id == 0) continue;
|
||||||
if (RemoteSolutionModel *m = getSolutionModel(sub.stage_id))
|
if (RemoteSolutionModel *m = getSolutionModel(sub.stage_id))
|
||||||
m->setData(sub.id, sub.cost, QString());
|
m->setSolutionData(sub.id, sub.cost, QString());
|
||||||
}
|
}
|
||||||
for (const auto& sub : msg.sub_trajectory) {
|
for (const auto& sub : msg.sub_trajectory) {
|
||||||
if (sub.id == 0) continue;
|
if (sub.id == 0) continue;
|
||||||
if (RemoteSolutionModel *m = getSolutionModel(sub.stage_id))
|
if (RemoteSolutionModel *m = getSolutionModel(sub.stage_id))
|
||||||
m->setData(sub.id, sub.cost, QString::fromStdString(sub.name));
|
m->setSolutionData(sub.id, sub.cost, QString::fromStdString(sub.name));
|
||||||
}
|
}
|
||||||
|
|
||||||
// caching is only enabled for top-level solutions (stage_id == 1)
|
// caching is only enabled for top-level solutions (stage_id == 1)
|
||||||
@ -449,7 +449,7 @@ QVariant RemoteSolutionModel::data(const QModelIndex &index, int role) const
|
|||||||
return QVariant();
|
return QVariant();
|
||||||
}
|
}
|
||||||
|
|
||||||
void RemoteSolutionModel::setData(uint32_t id, float cost, const QString &name)
|
void RemoteSolutionModel::setSolutionData(uint32_t id, float cost, const QString &name)
|
||||||
{
|
{
|
||||||
auto it = detail::findById(data_, id);
|
auto it = detail::findById(data_, id);
|
||||||
if (it == data_.end()) return;
|
if (it == data_.end()) return;
|
||||||
|
|||||||
@ -52,7 +52,7 @@ class RemoteSolutionModel;
|
|||||||
*/
|
*/
|
||||||
class RemoteTaskModel : public BaseTaskModel {
|
class RemoteTaskModel : public BaseTaskModel {
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
class Node;
|
struct Node;
|
||||||
Node* const root_;
|
Node* const root_;
|
||||||
planning_scene::PlanningSceneConstPtr scene_;
|
planning_scene::PlanningSceneConstPtr scene_;
|
||||||
ros::ServiceClient* get_solution_client_ = nullptr;
|
ros::ServiceClient* get_solution_client_ = nullptr;
|
||||||
@ -133,9 +133,9 @@ public:
|
|||||||
int columnCount(const QModelIndex &parent = QModelIndex()) const override;
|
int columnCount(const QModelIndex &parent = QModelIndex()) const override;
|
||||||
QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
|
QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
|
||||||
QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const override;
|
QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const override;
|
||||||
void sort(int column, Qt::SortOrder order);
|
void sort(int column, Qt::SortOrder order) override;
|
||||||
|
|
||||||
void setData(uint32_t id, float cost, const QString &name);
|
void setSolutionData(uint32_t id, float cost, const QString &name);
|
||||||
void processSolutionIDs(const std::vector<uint32_t> &successful, const std::vector<uint32_t> &failed, size_t num_failed);
|
void processSolutionIDs(const std::vector<uint32_t> &successful, const std::vector<uint32_t> &failed, size_t num_failed);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@ -145,7 +145,7 @@ public:
|
|||||||
void setStageFactory(const StageFactoryPtr &factory);
|
void setStageFactory(const StageFactoryPtr &factory);
|
||||||
bool dropMimeData(const QMimeData *mime, Qt::DropAction action, int row, int column, const QModelIndex &parent) override;
|
bool dropMimeData(const QMimeData *mime, Qt::DropAction action, int row, int column, const QModelIndex &parent) override;
|
||||||
Qt::DropActions supportedDropActions() const override;
|
Qt::DropActions supportedDropActions() const override;
|
||||||
Qt::ItemFlags flags(const QModelIndex &index) const;
|
Qt::ItemFlags flags(const QModelIndex &index) const override;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
@ -165,8 +165,8 @@ public:
|
|||||||
|
|
||||||
void setAutoHideSections(const QList<int> §ions);
|
void setAutoHideSections(const QList<int> §ions);
|
||||||
|
|
||||||
void setModel(QAbstractItemModel *model);
|
void setModel(QAbstractItemModel *model) override;
|
||||||
QSize viewportSizeHint() const;
|
QSize viewportSizeHint() const override;
|
||||||
void resizeEvent(QResizeEvent *event) override;
|
void resizeEvent(QResizeEvent *event) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@ -80,7 +80,7 @@ public:
|
|||||||
|
|
||||||
void setMimeTypes(const QStringList& mime_types);
|
void setMimeTypes(const QStringList& mime_types);
|
||||||
QStringList mimeTypes() const override;
|
QStringList mimeTypes() const override;
|
||||||
bool dropMimeData(const QMimeData *mime, Qt::DropAction action, int row, int column, const QModelIndex &parent);
|
bool dropMimeData(const QMimeData *mime, Qt::DropAction action, int row, int column, const QModelIndex &parent) override;
|
||||||
|
|
||||||
bool removeRows(int row, int count, const QModelIndex &parent = QModelIndex()) override;
|
bool removeRows(int row, int count, const QModelIndex &parent = QModelIndex()) override;
|
||||||
|
|
||||||
|
|||||||
@ -81,7 +81,7 @@ public:
|
|||||||
|
|
||||||
void setMimeTypes(const QStringList& mime_types);
|
void setMimeTypes(const QStringList& mime_types);
|
||||||
QStringList mimeTypes() const override;
|
QStringList mimeTypes() const override;
|
||||||
bool dropMimeData(const QMimeData *mime, Qt::DropAction action, int row, int column, const QModelIndex &parent);
|
bool dropMimeData(const QMimeData *mime, Qt::DropAction action, int row, int column, const QModelIndex &parent) override;
|
||||||
|
|
||||||
bool removeRows(int row, int count, const QModelIndex &parent = QModelIndex()) override;
|
bool removeRows(int row, int count, const QModelIndex &parent = QModelIndex()) override;
|
||||||
|
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user