mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-09-27 00:29:13 +08:00
transmit and display computation in rviz
This commit is contained in:
parent
aa11b66824
commit
fa9b177575
@ -198,6 +198,7 @@ void Introspection::fillStageStatistics(const Stage& stage, moveit_task_construc
|
||||
for (const auto& solution : stage.failures())
|
||||
s.failed.push_back(solutionId(*solution));
|
||||
|
||||
s.total_compute_time = stage.getTotalComputeTime();
|
||||
s.num_failed = stage.numFailures();
|
||||
}
|
||||
|
||||
|
@ -10,3 +10,5 @@ uint32[] solved
|
||||
uint32[] failed
|
||||
# number of failed solutions (if failed is empty)
|
||||
uint32 num_failed
|
||||
# total computation time in seconds
|
||||
float64 total_compute_time
|
||||
|
@ -254,6 +254,8 @@ QVariant RemoteTaskModel::data(const QModelIndex& index, int role) const {
|
||||
return n->solutions_->numSuccessful();
|
||||
case 2:
|
||||
return n->solutions_->numFailed();
|
||||
case 3:
|
||||
return n->solutions_->totalComputeTime();
|
||||
}
|
||||
break;
|
||||
case Qt::ForegroundRole:
|
||||
@ -353,7 +355,7 @@ void RemoteTaskModel::processStageStatistics(const moveit_task_constructor_msgs:
|
||||
continue;
|
||||
}
|
||||
Node* n = it->second;
|
||||
n->solutions_->processSolutionIDs(s.solved, s.failed, s.num_failed);
|
||||
n->solutions_->processSolutionIDs(s.solved, s.failed, s.num_failed, s.total_compute_time);
|
||||
|
||||
// emit notify about model changes when node was already visited
|
||||
if (n->node_flags_ & WAS_VISITED) {
|
||||
@ -622,7 +624,8 @@ void RemoteSolutionModel::sortInternal() {
|
||||
|
||||
// process solution ids received in stage statistics
|
||||
void RemoteSolutionModel::processSolutionIDs(const std::vector<uint32_t>& successful,
|
||||
const std::vector<uint32_t>& failed, size_t num_failed) {
|
||||
const std::vector<uint32_t>& failed, size_t num_failed,
|
||||
double total_compute_time) {
|
||||
// append new items to the end of data_
|
||||
processSolutionIDs(successful, true);
|
||||
processSolutionIDs(failed, false);
|
||||
@ -636,6 +639,7 @@ void RemoteSolutionModel::processSolutionIDs(const std::vector<uint32_t>& succes
|
||||
// but it may report the overall number of failures
|
||||
num_failed_data_ = failed.size(); // needed to compute number of successes
|
||||
num_failed_ = std::max(num_failed, num_failed_data_);
|
||||
total_compute_time_ = total_compute_time;
|
||||
|
||||
sortInternal();
|
||||
}
|
||||
|
@ -118,6 +118,7 @@ class RemoteSolutionModel : public QAbstractTableModel
|
||||
DataList data_;
|
||||
size_t num_failed_data_ = 0; // number of failed solutions in data_
|
||||
size_t num_failed_ = 0; // number of reported failures
|
||||
double total_compute_time_ = 0.0;
|
||||
|
||||
// solutions ordered (by default according to cost)
|
||||
int sort_column_ = -1;
|
||||
@ -134,6 +135,7 @@ public:
|
||||
|
||||
uint numSuccessful() const { return data_.size() - num_failed_data_; }
|
||||
uint numFailed() const { return num_failed_; }
|
||||
double totalComputeTime() const { return total_compute_time_; }
|
||||
|
||||
int rowCount(const QModelIndex& parent = QModelIndex()) const override;
|
||||
int columnCount(const QModelIndex& parent = QModelIndex()) const override;
|
||||
@ -143,6 +145,6 @@ public:
|
||||
|
||||
void setSolutionData(uint32_t id, float cost, const QString& comment);
|
||||
void processSolutionIDs(const std::vector<uint32_t>& successful, const std::vector<uint32_t>& failed,
|
||||
size_t num_failed);
|
||||
size_t num_failed, double total_compute_time);
|
||||
};
|
||||
}
|
||||
|
@ -65,6 +65,8 @@ QVariant TaskListModel::horizontalHeader(int column, int role) {
|
||||
return tr(u8"✓");
|
||||
case 2:
|
||||
return tr(u8"✗");
|
||||
case 3:
|
||||
return tr("time");
|
||||
}
|
||||
break;
|
||||
|
||||
@ -87,6 +89,8 @@ QVariant TaskListModel::horizontalHeader(int column, int role) {
|
||||
case 2:
|
||||
return tr("failed solution attempts");
|
||||
case 3:
|
||||
return tr("total computation time [s]");
|
||||
case 4:
|
||||
return tr("pending");
|
||||
}
|
||||
break;
|
||||
|
@ -89,7 +89,7 @@ public:
|
||||
QObject* parent = nullptr)
|
||||
: QAbstractItemModel(parent), scene_(scene), display_context_(display_context) {}
|
||||
|
||||
int columnCount(const QModelIndex& parent = QModelIndex()) const override { return 3; }
|
||||
int columnCount(const QModelIndex& parent = QModelIndex()) const override { return 4; }
|
||||
QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
|
||||
QVariant data(const QModelIndex& index, int role) const override;
|
||||
|
||||
@ -150,7 +150,7 @@ public:
|
||||
void setSolutionClient(ros::ServiceClient* client);
|
||||
void setActiveTaskModel(BaseTaskModel* model) { active_task_model_ = model; }
|
||||
|
||||
int columnCount(const QModelIndex& parent = QModelIndex()) const override { return 3; }
|
||||
int columnCount(const QModelIndex& parent = QModelIndex()) const override { return 4; }
|
||||
static QVariant horizontalHeader(int column, int role);
|
||||
QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
|
||||
QVariant data(const QModelIndex& index, int role) const override;
|
||||
|
@ -25,7 +25,7 @@ protected:
|
||||
}
|
||||
void processAndValidate(RemoteSolutionModel& model, const std::vector<uint32_t>& success_ids,
|
||||
const std::vector<uint32_t>& failure_ids) {
|
||||
model.processSolutionIDs(success_ids, failure_ids, failure_ids.size());
|
||||
model.processSolutionIDs(success_ids, failure_ids, failure_ids.size(), 0.0);
|
||||
|
||||
std::vector<uint32_t> cost_ordered_ids(success_ids.begin(), success_ids.end());
|
||||
std::vector<uint32_t> sorted_failure_ids(failure_ids.begin(), failure_ids.end());
|
||||
|
@ -78,7 +78,7 @@ protected:
|
||||
void validate(QAbstractItemModel& model, const std::initializer_list<const char*>& expected) {
|
||||
// validate root index
|
||||
ASSERT_EQ(model.rowCount(), static_cast<int>(expected.size()));
|
||||
EXPECT_EQ(model.columnCount(), 3);
|
||||
EXPECT_EQ(model.columnCount(), 4);
|
||||
EXPECT_EQ(model.parent(QModelIndex()), QModelIndex());
|
||||
|
||||
// validate first-level items
|
||||
@ -97,7 +97,7 @@ protected:
|
||||
|
||||
// validate children
|
||||
ASSERT_EQ(model.rowCount(idx), children);
|
||||
EXPECT_EQ(model.columnCount(idx), 3);
|
||||
EXPECT_EQ(model.columnCount(idx), 4);
|
||||
EXPECT_EQ(model.rowCount(model.index(row, 1)), 0);
|
||||
|
||||
// validate second-level items
|
||||
@ -110,7 +110,7 @@ protected:
|
||||
|
||||
EXPECT_EQ(model.data(childIdx).toString().toStdString(), std::to_string(child));
|
||||
EXPECT_EQ(model.rowCount(childIdx), 0);
|
||||
EXPECT_EQ(model.columnCount(childIdx), 3);
|
||||
EXPECT_EQ(model.columnCount(childIdx), 4);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user