Skip to content

Commit

Permalink
update airdrop protocol (#153)
Browse files Browse the repository at this point in the history
* update airdrop protocol

* fix lint
  • Loading branch information
Tyler-Lentz authored Apr 15, 2024
1 parent c465d2e commit 1f2a558
Show file tree
Hide file tree
Showing 7 changed files with 56 additions and 8 deletions.
21 changes: 14 additions & 7 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 @@ -56,6 +61,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
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
14 changes: 14 additions & 0 deletions src/network/airdrop_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,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
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

0 comments on commit 1f2a558

Please sign in to comment.