manager.h
Go to the documentation of this file.
1 #ifndef LABEL_MANAGER_H_
2 #define LABEL_MANAGER_H_
3 
4 #include <vector>
5 
6 #include <ros/ros.h>
7 #include <mesh_msgs/MeshFaceClusterStamped.h>
8 #include <mesh_msgs/GetLabeledClusters.h>
9 #include <label_manager/GetLabelGroups.h>
10 #include <label_manager/GetLabeledClusterGroup.h>
11 #include <label_manager/DeleteLabel.h>
12 
13 namespace label_manager
14 {
15 
17 {
18 public:
19  LabelManager(ros::NodeHandle& nodeHandle);
20 
21 private:
29 
30  std::string folderPath;
31 
32  void clusterLabelCallback(const mesh_msgs::MeshFaceClusterStamped::ConstPtr& msg);
34  mesh_msgs::GetLabeledClusters::Request& req,
35  mesh_msgs::GetLabeledClusters::Response& res);
37  label_manager::GetLabelGroups::Request& req,
38  label_manager::GetLabelGroups::Response& res);
40  label_manager::GetLabeledClusterGroup::Request& req,
41  label_manager::GetLabeledClusterGroup::Response& res);
43  label_manager::DeleteLabel::Request& req,
44  label_manager::DeleteLabel::Response& res);
45 
46  bool writeIndicesToFile(const std::string& fileName, const std::vector<uint>& indices, const bool append);
47  std::vector<uint> readIndicesFromFile(const std::string& fileName);
48  std::string getFileName(const std::string& uuid, const std::string& label);
49 };
50 
51 }
52 
53 #endif
ros::Publisher
label_manager::LabelManager::service_getLabelGroups
bool service_getLabelGroups(label_manager::GetLabelGroups::Request &req, label_manager::GetLabelGroups::Response &res)
Definition: manager.cpp:141
ros.h
label_manager::LabelManager::nh
ros::NodeHandle nh
Definition: manager.h:22
label_manager::LabelManager::clusterLabelCallback
void clusterLabelCallback(const mesh_msgs::MeshFaceClusterStamped::ConstPtr &msg)
Definition: manager.cpp:55
label_manager::LabelManager::newClusterLabelPub
ros::Publisher newClusterLabelPub
Definition: manager.h:24
label_manager::LabelManager::srv_delete_label
ros::ServiceServer srv_delete_label
Definition: manager.h:28
ros::ServiceServer
label_manager::LabelManager::folderPath
std::string folderPath
Definition: manager.h:30
label_manager::LabelManager::writeIndicesToFile
bool writeIndicesToFile(const std::string &fileName, const std::vector< uint > &indices, const bool append)
Definition: manager.cpp:235
label_manager::LabelManager::srv_get_label_groups
ros::ServiceServer srv_get_label_groups
Definition: manager.h:26
label_manager::LabelManager::service_getLabeledClusterGroup
bool service_getLabeledClusterGroup(label_manager::GetLabeledClusterGroup::Request &req, label_manager::GetLabeledClusterGroup::Response &res)
Definition: manager.cpp:200
label_manager::LabelManager::clusterLabelSub
ros::Subscriber clusterLabelSub
Definition: manager.h:23
label_manager
Definition: manager.h:13
label_manager::LabelManager
Definition: manager.h:16
label_manager::LabelManager::service_getLabeledClusters
bool service_getLabeledClusters(mesh_msgs::GetLabeledClusters::Request &req, mesh_msgs::GetLabeledClusters::Response &res)
Definition: manager.cpp:104
label_manager::LabelManager::service_deleteLabel
bool service_deleteLabel(label_manager::DeleteLabel::Request &req, label_manager::DeleteLabel::Response &res)
Definition: manager.cpp:181
label_manager::LabelManager::getFileName
std::string getFileName(const std::string &uuid, const std::string &label)
Definition: manager.cpp:307
label_manager::LabelManager::readIndicesFromFile
std::vector< uint > readIndicesFromFile(const std::string &fileName)
Definition: manager.cpp:285
label_manager::LabelManager::srv_get_labeled_clusters
ros::ServiceServer srv_get_labeled_clusters
Definition: manager.h:25
label_manager::LabelManager::LabelManager
LabelManager(ros::NodeHandle &nodeHandle)
Definition: manager.cpp:13
ros::NodeHandle
ros::Subscriber
label_manager::LabelManager::srv_get_labeled_cluster_group
ros::ServiceServer srv_get_labeled_cluster_group
Definition: manager.h:27


label_manager
Author(s): Sebastian Pütz , Jan Philipp Vogtherr
autogenerated on Sun Jan 21 2024 04:06:15