logger.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 
4 
5 int main(int argc, char** argv)
6 {
7  ros::init(argc, argv, "logger");
8 
10 
12 
13  mem.setupInputCommands(n);
14 
15  ros::ServiceClient client = n.serviceClient<muse_v2_driver::MemoryManagement>("logger");
16 
17  if (mem.input_command == mem.default_command_list) {
18  ROS_ERROR("No request found.");
19  ros::shutdown();
20  return -1;
21  }
22 
23  muse_v2_driver::MemoryManagement srv;
24 
26  srv.request.get_available_memory = true;
27 
29  srv.request.erase_memory = true;
30 
31  if (mem.input_command.get_files)
32  srv.request.get_files = true;
33 
34  if (mem.input_command.read_file != 0)
35  srv.request.read_file = mem.input_command.read_file;
36 
37  if (mem.input_command.read_memory) {
38  srv.request.get_files = true;
39  srv.request.read_memory = true;
40  }
41 
42 
43  if (client.call(srv))
44  {
45  if (srv.request.get_available_memory)
46  ROS_INFO("Available memory (KB): %.2f", (float)(srv.response.memory / 1024));
47 
48  if (srv.request.erase_memory)
49  ROS_INFO("Memory erased: %s", srv.response.memory_erased ? "true" : "false");
50 
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++)
54  {
55  ROS_INFO_STREAM("(" << i+1 <<", " << boost::posix_time::from_iso_string(srv.response.file_list.at(i)) << ")");
56  }
57  }
58 
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);
62  else
63  ROS_INFO("File not stored. Please check the list of available files.");
64  }
65 
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);
69  else
70  ROS_INFO("Not able to store any file.");
71 
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++)
75  {
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))) << ")");
77  }
78  }
79  }
80 
81  }
82  else
83  {
84  ROS_ERROR("Failed to call Logger service.");
85  return 1;
86  }
87 
88  return 0;
89 }
muse_v2_driver::Memory::setupInputCommands
void setupInputCommands(ros::NodeHandle &node)
Definition: Memory.cpp:3
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::shutdown
ROSCPP_DECL void shutdown()
muse_v2_driver::Memory::CommandList::read_memory
bool read_memory
Definition: Memory.h:30
muse_v2_driver::Memory::input_command
CommandList input_command
Definition: Memory.h:47
muse_v2_driver::Memory::CommandList::erase_memory
bool erase_memory
Definition: Memory.h:29
ros::ServiceClient
muse_v2_driver::Memory::default_command_list
struct muse_v2_driver::Memory::CommandList default_command_list
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
muse_v2_driver::Memory
Definition: Memory.h:21
muse_v2_driver::Memory::CommandList::get_available_memory
bool get_available_memory
Definition: Memory.h:28
Memory.h
muse_v2_driver::Memory::CommandList::read_file
int read_file
Definition: Memory.h:31
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ROS_INFO
#define ROS_INFO(...)
main
int main(int argc, char **argv)
Definition: logger.cpp:5
ros::NodeHandle
muse_v2_driver::Memory::CommandList::get_files
bool get_files
Definition: Memory.h:32


muse_v2_driver
Author(s): Elisa Tosello , Roberto Bortoletto
autogenerated on Thu Jan 20 2022 03:24:53