Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Airdrop Connection Test #155

Merged
merged 7 commits into from
Apr 18, 2024
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,12 @@
// `sudo usermod -aG dialout tuas && newgrp && bash`
// "runArgs": ["--device=/dev/ttyACM0"],

// Enable network mode host if on Linux and testing airdrop connectivity
// "appPort": [ "45906:45906/udp", "45907:45907/udp" ], // port forward airdrop ports for local testing
// "runArgs": [
// "--network=host"
// ],

"customizations": {
"vscode": {
"settings": {
Expand Down
24 changes: 16 additions & 8 deletions include/airdrop/packet.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <stdint.h>

/**********************************************************************************************
* LAST UPDATED: 2024/02/29
* LAST UPDATED: 2024/04/15 by Tyler Lentz
*
* This file defines the packet definitions for Airdrop communications. It is used in two
* separate repositories:
Expand All @@ -27,18 +27,23 @@
#define AD_OBC_PORT 45906 // OBC listens on this port, so payloads send to this
#define AD_PAYLOAD_PORT 45907 // Payloads listen on this port, so OBC sends to this

// All of the values in here are 1 byte long, which means we do not have to worry about
// the endianness of the information as it is sent over the wire. If we ever add values more
// than one byte long, we'll have to worry about this.

// gcc specific packing syntax. Technically this should already be packed because it is just
// two one-byte values, but just making sure.
// Normal packet, which applies for every kind of packet that is not an ad_latlng_packet
struct __attribute__((packed)) ad_packet {
uint8_t hdr;
uint8_t data;
};
typedef struct ad_packet ad_packet_t;

// Separate kind of packet sent by OBC to Payloads to specify drop location
// for indirect drop
struct __attribute__((packed)) ad_latlng_packet {
uint8_t hdr;
uint8_t bottle;
double lat;
double lng;
};
typedef struct ad_latlng_packet ad_latlng_packet_t;

enum ad_packet_hdr {
// Continually sent by the payloads to confirm they are still operational
// and can talk to the OBC
Expand All @@ -47,6 +52,7 @@ enum ad_packet_hdr {
// Handshake to establish connection
SET_MODE = 1,
ACK_MODE = 2,
RESET_MODE = 3, // TODO:

// Direct Drop
DROP_NOW = 100,
Expand All @@ -56,6 +62,8 @@ enum ad_packet_hdr {
ACK_SIGNAL = 201,
REVOKE = 202,
ACK_REVOKE = 203,
SEND_LATLNG = 204, // special packet format!
ACK_LATLNG = 205,

// Direct & Indirect
ABOUT_TO_RELEASE = 255,
Expand Down Expand Up @@ -84,7 +92,6 @@ inline int validate_packet_as(enum ad_packet_hdr hdr, ad_packet_t packet) {
}

switch (packet.hdr) {
case HEARTBEAT:
case ACK_MODE:
return 1;
case SET_MODE:
Expand All @@ -95,6 +102,7 @@ inline int validate_packet_as(enum ad_packet_hdr hdr, ad_packet_t packet) {
case REVOKE:
case ACK_REVOKE:
case ABOUT_TO_RELEASE:
case HEARTBEAT:
return (packet.data >= BOTTLE_A && packet.data <= BOTTLE_E);
default:
return 0;
Expand Down
1 change: 1 addition & 0 deletions include/network/airdrop_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ class AirdropClient {
~AirdropClient();

bool send(ad_packet_t packet);
bool send(ad_latlng_packet_t packet);
// Receives oldest packet since last receive() call, ignoring any
// HEARTBEAT packets as those are parsed by the client itself
// and exposed through the TODO function.
Expand Down
1 change: 1 addition & 0 deletions include/network/airdrop_sockets.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ ad_int_result_t set_socket_nonblocking(int sock_fd);
// Either returns an error string or the number of bytes sent.
// IMPORTANT: must have previously called set_send_thread from curr thread.
ad_int_result_t send_ad_packet(ad_socket_t socket, ad_packet_t packet);
ad_int_result_t send_ad_latlng_packet(ad_socket_t socket, ad_latlng_packet_t packet);

// Receive packet and place into buf, which is of length buf_len.
// Either returns an error string or the number of bytes read.
Expand Down
2 changes: 1 addition & 1 deletion protos
Submodule protos updated 1 files
+8 −0 obc.proto
24 changes: 24 additions & 0 deletions src/network/airdrop_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,8 @@ void AirdropClient::_establishConnection() {
LOG_F(INFO, "Payload connection established in %s mode",
(this->mode == DIRECT_DROP) ? "Direct" : "Indirect");

send_ad_packet(this->socket, make_ad_packet(ad_packet_hdr::ACK_MODE, *this->mode));

this->worker_future = std::async(std::launch::async, &AirdropClient::_receiveWorker, this);
}

Expand All @@ -72,6 +74,20 @@ bool AirdropClient::send(ad_packet_t packet) {
return true;
}

bool AirdropClient::send(ad_latlng_packet_t packet) {
set_send_thread();

auto res = send_ad_latlng_packet(this->socket, packet);
if (res.is_err) {
LOG_F(ERROR, "%s", res.data.err);
return false;
}

// TODO: helper to go from packet -> str
LOG_F(INFO, "Sent airdrop latlng packet: %hhu %hhu", packet.hdr, packet.bottle);
return true;
}

std::optional<ad_packet_t> AirdropClient::receive() {
Lock lock(this->recv_mut);

Expand Down Expand Up @@ -159,6 +175,12 @@ void AirdropClient::_receiveWorker() {
continue; // heartbeat, so we should not put it in the queue
}

if (packet.hdr == SET_MODE) {
send_ad_packet(this->socket, make_ad_packet(ad_packet_hdr::ACK_MODE, *this->mode));
LOG_F(INFO, "Received extra SET_MODE, reacking");
continue;
}

Lock lock(this->recv_mut);
this->recv_queue.emplace(packet);
}
Expand All @@ -174,5 +196,7 @@ bool AirdropClient::_parseHeartbeats(ad_packet_t packet) {
// subtract 1 to get the index into the lastHeartbeat array.
this->last_heartbeat[packet.data - 1] = getUnixTime_ms();

LOG_F(INFO, "Packet heartbeat from %d", packet.data);

return true;
}
20 changes: 20 additions & 0 deletions src/network/airdrop_sockets.c
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,26 @@ ad_int_result_t send_ad_packet(ad_socket_t socket, ad_packet_t packet) {
AD_RETURN_SUCC_RESULT(int, bytes_sent);
}

ad_int_result_t send_ad_latlng_packet(ad_socket_t socket, ad_latlng_packet_t packet) {
struct sockaddr_in SEND_ADDR = {
.sin_family = AF_INET,
.sin_port = htons(socket.send_port),
.sin_addr = INADDR_BROADCAST,
.sin_zero = {0},
};

static char err[AD_ERR_LEN];
int bytes_sent = sendto(socket.fd, (void*) &packet, sizeof(ad_latlng_packet_t), 0,
(struct sockaddr*) &SEND_ADDR, sizeof(SEND_ADDR));

if (bytes_sent < 0) {
snprintf(&err[0], AD_ERR_LEN, "send failed: %s", strerror_l(errno, _send_locale));
AD_RETURN_ERR_RESULT(int, err);
}

AD_RETURN_SUCC_RESULT(int, bytes_sent);
}

ad_int_result_t recv_ad_packet(ad_socket_t socket, void* buf, size_t buf_len) {
static char err[AD_ERR_LEN];
struct sockaddr_in RECV_ADDR = {
Expand Down
5 changes: 5 additions & 0 deletions src/network/mock/airdrop_sockets.c
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,11 @@ ad_int_result_t send_ad_packet(ad_socket_t socket, ad_packet_t packet) {
AD_RETURN_SUCC_RESULT(int, sizeof(ad_packet_t));
}

ad_int_result_t send_ad_latlng_packet(ad_socket_t socket, ad_latlng_packet_t packet) {
// TODO: Mock sending ad_latlng_packets
fprintf(stderr, "ERR: haven't yet implemented sending ad latlng packets in mock");
}

ad_int_result_t recv_ad_packet(ad_socket_t socket, void* buf, size_t buf_len) {
static char err[1] = "";

Expand Down
8 changes: 5 additions & 3 deletions tests/unit/airdrop_client/airdrop_client_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,10 +85,12 @@ TEST(AirdropClientTest, ObcSendToPayload) {
});

ad_packet_t p = { 0 };
while (num_received < NUM_TO_SEND) {
while (num_received < NUM_TO_SEND + 1) {
recv_ad_packet(payload_socket, &p, sizeof(ad_packet_t));
ASSERT_EQ(p.hdr, SIGNAL);
ASSERT_EQ(p.data, num_received);
if (num_received != 0) { // ignore first because will be ack_mode
ASSERT_EQ(p.hdr, SIGNAL);
ASSERT_EQ(p.data, num_received - 1);
}
num_received++;
}
}