18 ROS_ERROR(
"[AlbRequester] IP address not defined");
54 response.success =
false;
62 response.success =
false;
68 response.success =
true;
69 response.message = std::string(
"Processing successfully restarted on ALB.");
71 response.success =
false;
72 response.message = std::string(
"Unable to restart processing on ALB.");
83 response.success =
false;
91 response.success =
false;
97 response.success =
true;
98 response.message = std::string(
"Processing successfully stopped on ALB.");
100 response.success =
false;
101 response.message = std::string(
"Unable to stop processing on ALB.");
108 outsight_alb_driver::AlbConfig::Response &response)
113 response.success =
false;
118 response.success =
true;
119 response.message = std::string(
"Successfully get the config.");
125 outsight_alb_driver::AlbConfig::Response &response)
130 response.success =
false;
135 response.success =
true;
136 response.message = std::string(
"Successfully put the config.");
142 outsight_alb_driver::AlbFile::Response &response)
146 if (!helper.
executeStorage(AlbCurlHelper::storage_service_e::Download, request)) {
147 response.success =
false;
152 response.success =
true;
153 response.message = std::string(
"File successfully downloaded.");
159 outsight_alb_driver::AlbFile::Response &response)
163 if (!helper.
executeStorage(AlbCurlHelper::storage_service_e::Upload, request)) {
164 response.success =
false;
169 response.success =
true;
170 response.message = std::string(
"File successfully uploaded.");
176 outsight_alb_driver::AlbFile::Response &response)
180 if (!helper.
executeStorage(AlbCurlHelper::storage_service_e::List, request)) {
181 response.success =
false;
186 response.success =
true;
187 response.message = std::string(
"Files successfully displayed.");
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
ros::ServiceServer processing_service_stop
AlbRequester(ros::NodeHandle &node)
bool isProcessingRunning(bool &running)
Check if processing is running.
ros::ServiceServer processing_service_put_config
bool stopProcessingCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
Service callback to kill the processing.
ros::ServiceServer storage_service_download
constexpr const char * k_alb_ip
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
ros::ServiceServer storage_service_list
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
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
constexpr const char * k_alb_storage_list
constexpr const char * k_alb_processing_stop
bool hasParam(const std::string &key) const
ros::ServiceServer processing_service_restart
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
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
constexpr const char * k_alb_processing_get_config