Go to the documentation of this file.
47 class RemoteSolutionModel;
52 class RemoteTaskModel :
public BaseTaskModel
62 inline Node*
node(
const QModelIndex&
index)
const;
63 QModelIndex
index(
const Node* n)
const;
65 Node*
node(uint32_t stage_id)
const;
67 void setSolutionData(
const moveit_task_constructor_msgs::SolutionInfo& info);
72 QObject*
parent =
nullptr);
75 int rowCount(
const QModelIndex&
parent = QModelIndex())
const override;
77 QModelIndex
index(
int row,
int column,
const QModelIndex&
parent = QModelIndex())
const override;
78 QModelIndex
parent(
const QModelIndex&
index)
const override;
80 QVariant
data(
const QModelIndex&
index,
int role = Qt::DisplayRole)
const override;
81 bool setData(
const QModelIndex&
index,
const QVariant& value,
int role = Qt::EditRole)
override;
109 inline bool operator<(
const Data& other)
const {
return this->
id < other.id; }
121 double max_cost_ = std::numeric_limits<double>::infinity();
122 std::vector<DataList::iterator>
sorted_;
124 inline bool isVisible(
const Data& item)
const;
135 int rowCount(
const QModelIndex& parent = QModelIndex())
const override;
136 int columnCount(
const QModelIndex& parent = QModelIndex())
const override;
137 QVariant
headerData(
int section, Qt::Orientation orientation,
int role)
const override;
138 QVariant
data(
const QModelIndex& index,
int role = Qt::DisplayRole)
const override;
139 void sort(
int column, Qt::SortOrder order)
override;
142 void processSolutionIDs(
const std::vector<uint32_t>& successful,
const std::vector<uint32_t>& failed,
143 size_t num_failed,
double total_compute_time);
void setSolutionData(uint32_t id, float cost, const QString &comment)
void processSolutionIDs(const std::vector< uint32_t > &ids, bool successful)
QVariant data(const QModelIndex &index, int role=Qt::DisplayRole) const override
Qt::SortOrder sort_order_
Node * node(const QModelIndex &index) const
std::vector< DataList::iterator > sorted_
ros::ServiceClient get_solution_client_
~RemoteTaskModel() override
int rowCount(const QModelIndex &parent=QModelIndex()) const override
RemoteTaskModel(ros::NodeHandle &nh, const std::string &service_name, const planning_scene::PlanningSceneConstPtr &scene, rviz::DisplayContext *display_context, QObject *parent=nullptr)
int rowCount(const QModelIndex &parent=QModelIndex()) const override
DisplaySolutionPtr getSolution(const QModelIndex &index) override
get solution for given solution index
RemoteSolutionModel(QObject *parent=nullptr)
rviz::PropertyTreeModel * getPropertyModel(const QModelIndex &index) override
get property model for given stage index
Data(uint32_t id, float cost, uint32_t cost_rank, const QString &name=QString())
bool operator<(const Data &other) const
QModelIndex index(const Node *n) const
RemoteSolutionModel * getSolutionModel(uint32_t stage_id) const
void processStageDescriptions(const moveit_task_constructor_msgs::TaskDescription::_stages_type &msg)
std::list< Data > DataList
QModelIndex indexFromStageId(size_t id) const override
retrieve model index associated with given stage id
std::map< uint32_t, DisplaySolutionPtr > id_to_solution_
double total_compute_time_
bool isVisible(const Data &item) const
uint numSuccessful() const
int columnCount(const QModelIndex &parent=QModelIndex()) const override
void sort(int column, Qt::SortOrder order) override
bool setData(const QModelIndex &index, const QVariant &value, int role=Qt::EditRole) override
void processStageStatistics(const moveit_task_constructor_msgs::TaskStatistics::_stages_type &msg)
QVariant data(const QModelIndex &index, int role=Qt::DisplayRole) const override
std::map< uint32_t, Node * > id_to_stage_
double totalComputeTime() const
DisplaySolutionPtr processSolutionMessage(const moveit_task_constructor_msgs::Solution &msg)
void setSolutionData(const moveit_task_constructor_msgs::SolutionInfo &info)
QModelIndex parent(const QModelIndex &index) const override
QVariant headerData(int section, Qt::Orientation orientation, int role) const override
visualization
Author(s): Robert Haschke
autogenerated on Thu Feb 27 2025 03:39:51