Skip to content

Commit

Permalink
Merge pull request #1615 from amilcarlucas/pr/erase-logs
Browse files Browse the repository at this point in the history
This adds functionality to erase all logs on the SD card via mavlink
  • Loading branch information
vooon committed Sep 6, 2021
2 parents 71b24cd + dac2f26 commit c977812
Showing 1 changed file with 18 additions and 1 deletion.
19 changes: 18 additions & 1 deletion mavros_extras/src/plugins/log_transfer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <mavros_msgs/LogRequestData.h>
#include <mavros_msgs/LogRequestEnd.h>
#include <mavros_msgs/LogRequestList.h>
#include <std_srvs/Trigger.h>

namespace mavros {
namespace extra_plugins {
Expand All @@ -25,6 +26,8 @@ class LogTransferPlugin : public plugin::PluginBase {
&LogTransferPlugin::log_request_data_cb, this);
log_request_end_srv = nh.advertiseService("raw/log_request_end",
&LogTransferPlugin::log_request_end_cb, this);
log_request_erase_srv = nh.advertiseService("raw/log_request_erase",
&LogTransferPlugin::log_request_erase_cb, this);
}

Subscriptions get_subscriptions() override
Expand All @@ -38,7 +41,7 @@ class LogTransferPlugin : public plugin::PluginBase {
private:
ros::NodeHandle nh;
ros::Publisher log_entry_pub, log_data_pub;
ros::ServiceServer log_request_list_srv, log_request_data_srv, log_request_end_srv;
ros::ServiceServer log_request_list_srv, log_request_data_srv, log_request_end_srv, log_request_erase_srv;

void handle_log_entry(const mavlink::mavlink_message_t*, mavlink::common::msg::LOG_ENTRY& le)
{
Expand Down Expand Up @@ -115,6 +118,20 @@ class LogTransferPlugin : public plugin::PluginBase {
}
return true;
}

bool log_request_erase_cb(std_srvs::Trigger::Request &,
std_srvs::Trigger::Response &res)
{
mavlink::common::msg::LOG_ERASE msg;
m_uas->msg_set_target(msg);
try {
UAS_FCU(m_uas)->send_message(msg);
} catch (std::length_error&) {
res.success = false;
}
res.success = true;
return true;
}
};
} // namespace extra_plugins
} // namespace mavros
Expand Down

0 comments on commit c977812

Please sign in to comment.