Skip to content

Commit

Permalink
Insert deduplication into endpoint handling
Browse files Browse the repository at this point in the history
  • Loading branch information
Julian Kent committed Feb 3, 2021
1 parent 02bfdad commit e8f517d
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 1 deletion.
9 changes: 8 additions & 1 deletion src/mavlink-router/endpoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ int Endpoint::handle_read()

while ((r = read_msg(&buf, &target_sysid, &target_compid, &src_sysid,
&src_compid, &msg_id)) > 0) {
if (allowed_by_filter(msg_id) && allowed_by_dropout())
if (allowed_by_filter(msg_id) && allowed_by_dropout() && allowed_by_dedup(&buf))
Mainloop::get_instance().route_msg(&buf, target_sysid, target_compid,
src_sysid, src_compid, msg_id);
}
Expand Down Expand Up @@ -374,6 +374,13 @@ bool Endpoint::allowed_by_dropout()
return true;
}

bool Endpoint::allowed_by_dedup(const buffer* buf)
{
if (Mainloop::get_instance().add_check_dedup(buf)) {
return false;
}
return true;
}

void Endpoint::postprocess_msg(int target_sysid, int target_compid, uint8_t src_sysid,
uint8_t src_compid, uint32_t msg_id)
Expand Down
3 changes: 3 additions & 0 deletions src/mavlink-router/endpoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,12 @@ class Endpoint : public Pollable {
bool allowed_by_filter(uint32_t msg_id);
void add_message_to_filter(uint32_t msg_id) { _message_filter.push_back(msg_id); }
void add_message_to_nodelay(uint32_t msg_id) { _message_nodelay.push_back(msg_id); }

bool allowed_by_dropout();
void set_dropout_percentage (uint32_t dropout_percentage) { _dropout_percentage = dropout_percentage; }

bool allowed_by_dedup(const buffer* buf);

void start_expire_timer();

void reset_expire_timer();
Expand Down
10 changes: 10 additions & 0 deletions src/mavlink-router/mainloop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -394,6 +394,16 @@ static bool _print_statistics_timeout_cb(void *data)
return true;
}

bool Mainloop::add_check_dedup(const buffer* buf)
{
Dedup::PacketStatus status = _dedup.add_check_packet(buf->data, buf->len);
if (status == Dedup::PacketStatus::NEW_PACKET_OR_TIMED_OUT) {
return true;
}
return false;
}


bool Mainloop::remove_dynamic_endpoint(Endpoint *endpoint)
{
if (!endpoint) {
Expand Down
5 changes: 5 additions & 0 deletions src/mavlink-router/mainloop.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@

#include "binlog.h"
#include "comm.h"
#include "dedup.h"
#include "endpoint.h"
#include "timeout.h"
#include "ulog.h"
Expand Down Expand Up @@ -86,6 +87,8 @@ class Mainloop {
bool remove_dynamic_endpoint(const dynamic_command& command);
bool remove_dynamic_endpoint(Endpoint *endpoint);

bool add_check_dedup(const buffer* buf);

void print_statistics();

int epollfd = -1;
Expand Down Expand Up @@ -135,6 +138,8 @@ class Mainloop {

Timeout *_timeouts = nullptr;

Dedup _dedup;

std::atomic<bool> _should_exit {false};

struct {
Expand Down

0 comments on commit e8f517d

Please sign in to comment.