alb_requester.cpp
Go to the documentation of this file.
1 // Local headers
2 #include "alb_requester.h"
3 #include "alb_common.h"
4 #include "alb_curl_helper.h"
5 
7 {
8  defineServices(node);
9 }
10 
12 {
13  // Define the curl address.
14  std::string ip_v4;
15  ros::NodeHandle private_node("~");
16 
17  if (!private_node.hasParam(ALBCommon::k_alb_ip)) {
18  ROS_ERROR("[AlbRequester] IP address not defined");
19  return false;
20  }
21 
22  private_node.getParam(ALBCommon::k_alb_ip, ip_v4);
23  ip_address = ip_v4;
24 
25  return true;
26 }
27 
29 {
30  // Processing services.
39 
40  // Storage services.
47 }
48 
49 bool AlbRequester::restartProcessingCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
50 {
51  AlbCurlHelper helper(ip_address);
52 
53  if (!helper.executeProcessing(AlbCurlHelper::processing_service_e::Restart)) {
54  response.success = false;
55  response.message = helper.getErrorMessage();
56  return true;
57  }
58 
59  AlbCurlHelper helperRun(ip_address);
60  bool running = false;
61  if (!helperRun.isProcessingRunning(running)) {
62  response.success = false;
63  response.message = helperRun.getErrorMessage();
64  return true;
65  }
66 
67  if (running) {
68  response.success = true;
69  response.message = std::string("Processing successfully restarted on ALB.");
70  } else {
71  response.success = false;
72  response.message = std::string("Unable to restart processing on ALB.");
73  }
74 
75  return true;
76 }
77 
78 bool AlbRequester::stopProcessingCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
79 {
80  AlbCurlHelper helper(ip_address);
81 
82  if (!helper.executeProcessing(AlbCurlHelper::processing_service_e::Stop)) {
83  response.success = false;
84  response.message = helper.getErrorMessage();
85  return true;
86  }
87 
88  AlbCurlHelper helperRun(ip_address);
89  bool running = false;
90  if (!helperRun.isProcessingRunning(running)) {
91  response.success = false;
92  response.message = helperRun.getErrorMessage();
93  return true;
94  }
95 
96  if (!running) {
97  response.success = true;
98  response.message = std::string("Processing successfully stopped on ALB.");
99  } else {
100  response.success = false;
101  response.message = std::string("Unable to stop processing on ALB.");
102  }
103 
104  return true;
105 }
106 
107 bool AlbRequester::getConfigCallback(outsight_alb_driver::AlbConfig::Request &request,
108  outsight_alb_driver::AlbConfig::Response &response)
109 {
110  AlbCurlHelper helper(ip_address);
111 
112  if (!helper.executeProcessingConfig(AlbCurlHelper::processing_config_e::Get, request)) {
113  response.success = false;
114  response.message = helper.getErrorMessage();
115  return true;
116  }
117 
118  response.success = true;
119  response.message = std::string("Successfully get the config.");
120 
121  return true;
122 }
123 
124 bool AlbRequester::putConfigCallback(outsight_alb_driver::AlbConfig::Request &request,
125  outsight_alb_driver::AlbConfig::Response &response)
126 {
127  AlbCurlHelper helper(ip_address);
128 
129  if (!helper.executeProcessingConfig(AlbCurlHelper::processing_config_e::Put, request)) {
130  response.success = false;
131  response.message = helper.getErrorMessage();
132  return true;
133  }
134 
135  response.success = true;
136  response.message = std::string("Successfully put the config.");
137 
138  return true;
139 }
140 
141 bool AlbRequester::downloadFileCallback(outsight_alb_driver::AlbFile::Request &request,
142  outsight_alb_driver::AlbFile::Response &response)
143 {
144  AlbCurlHelper helper(ip_address);
145 
146  if (!helper.executeStorage(AlbCurlHelper::storage_service_e::Download, request)) {
147  response.success = false;
148  response.message = helper.getErrorMessage();
149  return true;
150  }
151 
152  response.success = true;
153  response.message = std::string("File successfully downloaded.");
154 
155  return true;
156 }
157 
158 bool AlbRequester::uploadFileCallback(outsight_alb_driver::AlbFile::Request &request,
159  outsight_alb_driver::AlbFile::Response &response)
160 {
161  AlbCurlHelper helper(ip_address);
162 
163  if (!helper.executeStorage(AlbCurlHelper::storage_service_e::Upload, request)) {
164  response.success = false;
165  response.message = helper.getErrorMessage();
166  return true;
167  }
168 
169  response.success = true;
170  response.message = std::string("File successfully uploaded.");
171 
172  return true;
173 }
174 
175 bool AlbRequester::listFilesCallback(outsight_alb_driver::AlbFile::Request &request,
176  outsight_alb_driver::AlbFile::Response &response)
177 {
178  AlbCurlHelper helper(ip_address);
179 
180  if (!helper.executeStorage(AlbCurlHelper::storage_service_e::List, request)) {
181  response.success = false;
182  response.message = helper.getErrorMessage();
183  return true;
184  }
185 
186  response.success = true;
187  response.message = std::string("Files successfully displayed.");
188 
189  return true;
190 }
bool downloadFileCallback(outsight_alb_driver::AlbFile::Request &request, outsight_alb_driver::AlbFile::Response &response)
Service callback to download a file from the ALB.
ros::ServiceServer processing_service_get_config
Definition: alb_requester.h:58
ros::ServiceServer processing_service_stop
Definition: alb_requester.h:57
AlbRequester(ros::NodeHandle &node)
bool isProcessingRunning(bool &running)
Check if processing is running.
ros::ServiceServer processing_service_put_config
Definition: alb_requester.h:59
bool stopProcessingCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
Service callback to kill the processing.
ros::ServiceServer storage_service_download
Definition: alb_requester.h:61
constexpr const char * k_alb_ip
Definition: alb_common.h:18
bool restartProcessingCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
Service callback to start the processing.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool putConfigCallback(outsight_alb_driver::AlbConfig::Request &request, outsight_alb_driver::AlbConfig::Response &response)
Service callback to put the ALB configuration.
bool getParam(const std::string &key, std::string &s) const
constexpr const char * k_alb_processing_restart
Definition: alb_common.h:41
ros::ServiceServer storage_service_list
Definition: alb_requester.h:63
bool executeProcessingConfig(const processing_config_e &service, outsight_alb_driver::AlbConfig::Request &request)
Execute the processing command for the configuration.
constexpr const char * k_alb_storage_download
Definition: alb_common.h:46
bool getConfigCallback(outsight_alb_driver::AlbConfig::Request &request, outsight_alb_driver::AlbConfig::Response &response)
Service callback to get the ALB configuration.
ros::ServiceServer storage_service_upload
Definition: alb_requester.h:62
constexpr const char * k_alb_storage_list
Definition: alb_common.h:48
constexpr const char * k_alb_processing_stop
Definition: alb_common.h:42
bool hasParam(const std::string &key) const
ros::ServiceServer processing_service_restart
Definition: alb_requester.h:56
bool init(void)
Initialize the ALB requester.
bool executeProcessing(const processing_service_e service)
Execute the processing command.
constexpr const char * k_alb_processing_put_config
Definition: alb_common.h:44
bool uploadFileCallback(outsight_alb_driver::AlbFile::Request &request, outsight_alb_driver::AlbFile::Response &response)
Service callback to upload a file to the ALB.
const std::string getErrorMessage(void) const
Get the error message.
bool listFilesCallback(outsight_alb_driver::AlbFile::Request &request, outsight_alb_driver::AlbFile::Response &response)
Service callback to list files in the ALB.
Class to handle the curl ALB requests.
bool executeStorage(const storage_service_e service, outsight_alb_driver::AlbFile::Request &request)
Execute the storage command.
void defineServices(ros::NodeHandle &node)
Define the ALB services.
constexpr const char * k_alb_storage_upload
Definition: alb_common.h:47
constexpr const char * k_alb_processing_get_config
Definition: alb_common.h:43
#define ROS_ERROR(...)
std::string ip_address
Definition: alb_requester.h:54


outsight_alb_driver
Author(s): Outsight
autogenerated on Fri Oct 14 2022 02:29:51