5 int main(
int argc,
char** argv)
23 muse_v2_driver::MemoryManagement srv;
26 srv.request.get_available_memory =
true;
29 srv.request.erase_memory =
true;
32 srv.request.get_files =
true;
38 srv.request.get_files =
true;
39 srv.request.read_memory =
true;
45 if (srv.request.get_available_memory)
46 ROS_INFO(
"Available memory (KB): %.2f", (
float)(srv.response.memory / 1024));
48 if (srv.request.erase_memory)
49 ROS_INFO(
"Memory erased: %s", srv.response.memory_erased ?
"true" :
"false");
51 if (srv.request.get_files) {
52 ROS_INFO(
"List of available files:");
53 for (
int i = 0; i < srv.response.file_list.size(); i++)
55 ROS_INFO_STREAM(
"(" << i+1 <<
", " << boost::posix_time::from_iso_string(srv.response.file_list.at(i)) <<
")");
59 if (srv.request.read_file != 0) {
60 if (srv.response.file_stored)
61 ROS_INFO_STREAM(
"File " << std::to_string(srv.request.read_file) <<
" stored at " << srv.response.dest_path);
63 ROS_INFO(
"File not stored. Please check the list of available files.");
66 if (srv.request.read_memory) {
67 if (srv.response.number_of_files_stored > 0)
68 ROS_INFO(
"# of files stored: %d", srv.response.number_of_files_stored);
70 ROS_INFO(
"Not able to store any file.");
72 if (srv.response.corrupt_stored_list.size() != 0) {
73 ROS_INFO(
"Among them, corrupted files follow:");
74 for (
int i = 0; i < srv.response.corrupt_stored_list.size(); i++)
76 ROS_INFO_STREAM(
"(" << srv.response.corrupt_stored_list.at(i)+1 <<
", " << boost::posix_time::from_iso_string(srv.response.file_list.at(srv.response.corrupt_stored_list.at(i))) <<
")");
84 ROS_ERROR(
"Failed to call Logger service.");