Skip to content
This repository has been archived by the owner on Mar 23, 2024. It is now read-only.

Commit

Permalink
Implemented binary send() functions for local tr.
Browse files Browse the repository at this point in the history
  • Loading branch information
Jng468 committed Nov 25, 2023
1 parent 412383b commit e60dcd9
Show file tree
Hide file tree
Showing 3 changed files with 71 additions and 52 deletions.
20 changes: 10 additions & 10 deletions projects/local_transceiver/inc/local_transceiver.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#pragma once

#include <custom_interfaces/msg/detail/gps__struct.hpp>
#include <mutex>
#include <string>

Expand Down Expand Up @@ -91,8 +92,7 @@ class LocalTransceiver
* @tparam T of type custom_interfaces::msg::T
* @param sensor new sensor data
*/
template <typename T>
void onNewSensorData(T sensor);
void onNewSensorData(custom_interfaces::msg::GPS sensor);

/**
* @brief Send current data to the serial port and to the remote server
Expand Down Expand Up @@ -134,14 +134,6 @@ class LocalTransceiver
*/
void send(const std::string & cmd);

/**
* @brief Formats binary data to be sent to the satellite according to the AT command specification
*
* @param data data binary string to be sent
* @return Formatted message to be written to serial
*/
static std::string createOutMsg(const std::string & data);

/**
* @brief Parse the message received from the remote server
*
Expand All @@ -164,4 +156,12 @@ class LocalTransceiver
* @return false if invalid
*/
bool checkOK();

/**
* @brief Compute a checksum
*
* @param data data string
* @return checksum as a string
*/
static std::string checksum(const std::string & data);
};
71 changes: 34 additions & 37 deletions projects/local_transceiver/src/local_transceiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <boost/asio/streambuf.hpp>
#include <boost/asio/write.hpp>
#include <boost/system/error_code.hpp>
#include <custom_interfaces/msg/detail/gps__struct.hpp>
#include <exception>
#include <mutex>
#include <stdexcept>
Expand All @@ -25,7 +26,6 @@ LocalTransceiver::SensorBuf::SensorBuf(){};

void LocalTransceiver::SensorBuf::updateSensor(msg::GPS gps)
{
std::lock_guard<std::mutex> lock(buf_mtx_);
sensors_.mutable_gps()->set_heading(gps.heading.heading);
sensors_.mutable_gps()->set_latitude(gps.lat_lon.latitude);
sensors_.mutable_gps()->set_longitude(gps.lat_lon.longitude);
Expand All @@ -34,7 +34,6 @@ void LocalTransceiver::SensorBuf::updateSensor(msg::GPS gps)

void LocalTransceiver::SensorBuf::updateSensor(msg::AISShips ships)
{
std::lock_guard<std::mutex> lock(buf_mtx_);
sensors_.clear_ais_ships();
for (const msg::HelperAISShip & ship : ships.ships) {
Sensors::Ais * new_ship = sensors_.add_ais_ships();
Expand All @@ -49,11 +48,7 @@ void LocalTransceiver::SensorBuf::updateSensor(msg::AISShips ships)
}
}

Sensors LocalTransceiver::SensorBuf::sensors()
{
std::lock_guard<std::mutex> lock(buf_mtx_);
return sensors_;
}
Sensors LocalTransceiver::SensorBuf::sensors() { return sensors_; }

LocalTransceiver::LocalTransceiver(const std::string & port_name, const uint32_t baud_rate) : serial_(io_, port_name)
{
Expand All @@ -67,17 +62,11 @@ LocalTransceiver::~LocalTransceiver()

void LocalTransceiver::stop()
{
std::lock_guard<std::mutex> lock(serial_mtx_);
// TODO(Jng468): Flush the serial port
serial_.cancel();
serial_.close(); // Can throw an exception so cannot be put in the destructor
}

template <typename T>
void LocalTransceiver::onNewSensorData(T sensor)
{

sensor_buf_.updateSensor(sensor);
}
void LocalTransceiver::onNewSensorData(msg::GPS sensor) { sensor_buf_.updateSensor(sensor); }

bool LocalTransceiver::send()
{
Expand All @@ -99,14 +88,14 @@ bool LocalTransceiver::send()
"No implementation to handle this!";
throw std::length_error(err_string);
}
std::string msg = createOutMsg(data);

std::lock_guard<std::mutex> lock(serial_mtx_);

static constexpr int MAX_NUM_RETRIES = 20;
for (int i = 0; i < MAX_NUM_RETRIES; i++) {
// TODO(Jng468): Send the binary data
send(msg);
std::string sbdwbCommand = "AT+SBDWB=" + std::to_string(data.size()) + "\r";
send(sbdwbCommand + data + "\r");

std::string checksumCommand = std::to_string(data.size()) + checksum(data) + "\r";
send(data + "+" + checksumCommand + "\r");

// Check SBD Session status to see if data was sent successfully
send(AT::SBD_SESSION);
Expand All @@ -129,33 +118,29 @@ bool LocalTransceiver::send()
std::string LocalTransceiver::debugSend(const std::string & cmd)
{
send(cmd);
// TODO(Jng468): Get the output and return it
return "PLACEHOLDER";

std::string response = readLine(); // Read and capture the response
readLine(); // Check if there is an empty line after respones
return response;
}

std::string LocalTransceiver::receive()
{
// TODO(Jng468)
(void)serial_; // Remove this line when implemented
std::string msg = "placeholder";
return msg;
std::string receivedData = readLine();
return receivedData;
}

void LocalTransceiver::send(const std::string & cmd) { bio::write(serial_, bio::buffer(cmd, cmd.size())); }

std::string LocalTransceiver::createOutMsg(const std::string & data)
{
// TODO(Jng468)
std::string msg = "Prepend command header + any others stuff" + data + " Append other stuff";
return msg;
}

std::string LocalTransceiver::parseInMsg(const std::string & msg)
{
// TODO(Jng468)
(void)msg;
// Separate data from payload header and other formatting
std::string data = "placeholder";
const std::string header = "AT+SBDWB=";
const std::string footer = "\r";

size_t headerPos = msg.find(header);
size_t footerPos = msg.find(footer);

std::string data = msg.substr(headerPos + header.size(), footerPos - headerPos - header.size());
return data;
}

Expand All @@ -172,3 +157,15 @@ bool LocalTransceiver::checkOK()
std::string status = readLine();
return status == AT::STATUS_OK;
}

std::string LocalTransceiver::checksum(const std::string & data)
{
uint16_t counter = 0;
for (char c : data) {
counter += static_cast<uint8_t>(c);
}

std::stringstream ss;
ss << std::hex << std::setw(4) << std::setfill('0') << counter;
return ss.str();
}
32 changes: 27 additions & 5 deletions projects/local_transceiver/test/test_local_transceiver.cpp
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
/* IMPORTANT: Make sure only one instance of network_systems/scripts/run_virtual_iridium.sh is running */

#include <boost/system/system_error.hpp>

#include "cmn_hdrs/shared_constants.h"
#include "gtest/gtest.h"
#include "local_transceiver.h"
#include "sensors.pb.h"

class TestLocalTransceiver : public ::testing::Test
{
protected:

// TestLocalTransceiver() : lcl_trns_(LocalTransceiver(LOCAL_TRANSCEIVER_TEST_PORT, SATELLITE_BAUD_RATE)) {}
TestLocalTransceiver()
{
try {
Expand All @@ -25,10 +25,32 @@ class TestLocalTransceiver : public ::testing::Test
delete lcl_trns_;
}

~TestLocalTransceiver() override { delete lcl_trns_; }
LocalTransceiver * lcl_trns_;
};

TEST_F(TestLocalTransceiver, PlaceholderTest) { std::cout << "PLACEHOLDER" << std::endl; }
/**
* @brief Verify debugSendTest sends something to the terminal
*/
TEST_F(TestLocalTransceiver, debugSendTest)
{
std::string testDebug = "showsUp";
lcl_trns_->debugSend(testDebug);
}

/**
* @brief Send a binary string to virtual_iridium and verify it is received
* Uses gps custom interface
*/
TEST_F(TestLocalTransceiver, sendGpsTest)
{
constexpr float holder = 14.3;

custom_interfaces::msg::GPS gps;
gps.heading.set__heading(holder);
gps.lat_lon.set__latitude(holder);
gps.lat_lon.set__longitude(holder);
gps.speed.set__speed(holder);

TEST_F(TestLocalTransceiver, PlaceholderTest2) { std::cout << "PLACEHOLDER" << std::endl; }
lcl_trns_->onNewSensorData(gps);
lcl_trns_->send();
}

0 comments on commit e60dcd9

Please sign in to comment.