Go to the documentation of this file.
18 ROS_ERROR(
"[AlbRequester] IP address not defined");
69 response.message = std::string(
"Processing successfully restarted on ALB.");
72 response.message = std::string(
"Unable to restart processing on ALB.");
98 response.message = std::string(
"Processing successfully stopped on ALB.");
101 response.message = std::string(
"Unable to stop processing on ALB.");
108 outsight_alb_driver::AlbConfig::Response &response)
119 response.message = std::string(
"Successfully get the config.");
125 outsight_alb_driver::AlbConfig::Response &response)
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)) {
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)) {
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)) {
187 response.message = std::string(
"Files successfully displayed.");
const std::string response
constexpr const char * k_alb_processing_put_config
constexpr const char * k_alb_storage_download
ros::ServiceServer storage_service_upload
constexpr const char * k_alb_processing_restart
bool getParam(const std::string &key, bool &b) const
constexpr const char * k_alb_ip
ros::ServiceServer processing_service_restart
bool listFilesCallback(outsight_alb_driver::AlbFile::Request &request, outsight_alb_driver::AlbFile::Response &response)
Service callback to list files in the ALB.
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
Class to handle the curl ALB requests.
bool stopProcessingCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
Service callback to kill the processing.
const std::string getErrorMessage(void) const
Get the error message.
bool executeProcessingConfig(const processing_config_e &service, outsight_alb_driver::AlbConfig::Request &request)
Execute the processing command for the configuration.
void defineServices(ros::NodeHandle &node)
Define the ALB services.
bool putConfigCallback(outsight_alb_driver::AlbConfig::Request &request, outsight_alb_driver::AlbConfig::Response &response)
Service callback to put the ALB configuration.
bool executeStorage(const storage_service_e service, outsight_alb_driver::AlbFile::Request &request)
Execute the storage command.
bool executeProcessing(const processing_service_e service)
Execute the processing command.
bool hasParam(const std::string &key) const
AlbRequester(ros::NodeHandle &node)
constexpr const char * k_alb_storage_list
constexpr const char * k_alb_storage_upload
bool restartProcessingCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
Service callback to start the processing.
constexpr const char * k_alb_processing_get_config
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_download
ros::ServiceServer storage_service_list
constexpr const char * k_alb_processing_stop
bool init(void)
Initialize the ALB requester.
bool uploadFileCallback(outsight_alb_driver::AlbFile::Request &request, outsight_alb_driver::AlbFile::Response &response)
Service callback to upload a file to the ALB.
ros::ServiceServer processing_service_stop
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
bool isProcessingRunning(bool &running)
Check if processing is running.
ros::ServiceServer processing_service_put_config