17 ROS_INFO(
"request: get_available_memory=%s, erase_memory=%s, read_memory=%s, read_file=%d, get_files=%s",
18 req.get_available_memory ?
"true" :
"false",
19 req.erase_memory ?
"true" :
"false",
20 req.read_memory ?
"true" :
"false",
22 req.get_files ?
"true" :
"false"
25 if (req.get_available_memory) {
26 if (!received_command.get_available_memory) {
27 received_command.get_available_memory =
true;
28 ROS_INFO(
"Trying getting Available Memory.");
30 if (muse_v2->
serial->getAvailableMemory() > 0) {
31 res.memory = muse_v2->
serial->getAvailableMemory();
33 ROS_INFO(
"Sending back Available Memory.");
37 if (req.erase_memory) {
38 if (!received_command.erase_memory) {
39 received_command.erase_memory =
true;
42 if (muse_v2->
serial->eraseMemory()) {
43 res.memory_erased =
true;
50 if (!received_command.get_files) {
51 received_command.get_files =
true;
52 ROS_INFO(
"Trying getting file names list.");
54 if (!muse_v2->
serial->getFiles().empty()) {
55 vector<pair<int, string>> file_names = muse_v2->
serial->getFiles();
57 for (
const auto& file : file_names)
58 res.file_list.push_back(file.second);
59 ROS_INFO(
"Sending back File names.");
64 if (req.read_file != 0) {
65 if (received_command.read_file == 0) {
66 received_command.read_file = req.read_file;
72 if (muse_v2->
serial->readFile(req.read_file).empty()) {
73 ROS_INFO(
"File not found. Please check the list of available files.");
74 res.file_stored =
false;
79 if (!muse_v2->
serial->getFiles().empty()) {
80 vector<pair<int, string>> file_names = muse_v2->
serial->getFiles();
81 vector<Log> logs = muse_v2->
serial->readFile(req.read_file);
82 string dest_file =
ros::package::getPath(
"muse_v2_driver") +
"/config/" + file_names.at(req.read_file - 1).second +
".txt";
83 if (muse_v2->
serial->storeLogs(dest_file, logs)) {
84 res.file_stored =
true;
85 res.dest_path = dest_file;
86 ROS_INFO(
"Data stored at %s", dest_file.c_str());
94 if (req.read_memory) {
95 if (received_command.read_memory ==
false) {
96 received_command.read_memory =
true;
105 if (muse_v2->
serial->getFiles().empty()) {
107 res.number_of_files_stored = 0;
112 vector<pair<int, string>> file_names = muse_v2->
serial->getFiles();
114 while (i < file_names.size()) {
115 ROS_INFO_STREAM(
"Processing file " << i + 1 <<
" of " << file_names.size() <<
": " << file_names.at(i).second <<
".txt");
117 if (muse_v2->
serial->readFile(req.read_file).empty()) {
118 ROS_INFO(
"File %d not properly read", i + 1);
119 res.corrupt_stored_list.push_back(i);
122 std::vector<Log> logs = muse_v2->
serial->readFile(req.read_file);
123 ROS_INFO(
"# of logs to store: %lu", logs.size());
125 std::string dest_file = dest_path + file_names.at(i).second +
".txt";
126 if (muse_v2->
serial->storeLogs(dest_file, logs)) {
128 ROS_INFO(
"Data stored at %s", dest_file.c_str());
135 res.number_of_files_stored = file_stored;
136 res.dest_path = dest_path;