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

Commit

Permalink
Local transceiver: ROS Subscription and sendData test (#94)
Browse files Browse the repository at this point in the history
* Starter code for LocalTransceiver implementation

Attempt 1 to rebase

* Run virtual iridium inside unit test (broken)

Attempt 2 to rebase

* Remove autorun virtual iridium inside test

Attempt 3 to rebase

* Cleanup

* Fix clang-tidy errors

Attempt 4 to rebase

* Update at_cmds starter

Attempt 5 to rebase

* Implemented binary send() functions for local tr.

* Updated sensors and minor changes

* Added other sensors

* Updates :)

* More updates

* Local transciever tests work in progress

* Checksum issues

* Writing mostly works

* Write sucess

* Local transceiver Subscription work in progress :)

* Compatibility with Virtual Iridium confirmed

* Send flow confirmed

* Fix file perms

* Update scripts README.md

* Completed sendData test and ROS subscription

* remove visul verification test

* temp commit to debug CI

* Fix failing test

---------

Co-authored-by: hhenry01 <[email protected]>
  • Loading branch information
Jng468 and hhenry01 authored Mar 9, 2024
1 parent ab76d9e commit 0f4f67b
Show file tree
Hide file tree
Showing 10 changed files with 494 additions and 104 deletions.
1 change: 1 addition & 0 deletions functions.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -51,5 +51,6 @@ function(make_unit_test module srcs link_libs inc_dirs compile_defs)
add_dependencies(${test_module} ${AUTOGEN_TARGETS})
# Make the unit test runnable with CTest (invoked via test.sh)
add_test(NAME ${test_module} COMMAND ${test_module})
set_tests_properties(${test_module} PROPERTIES TIMEOUT 60) # 1 minute per test timeout
endif()
endfunction()
1 change: 1 addition & 0 deletions projects/local_transceiver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ set(inc_dirs
set(compile_defs
LOCAL_TRANSCEIVER_TEST_PORT="$ENV{LOCAL_TRANSCEIVER_TEST_PORT}"
RUN_VIRTUAL_IRIDIUM_SCRIPT_PATH="$ENV{ROS_WORKSPACE}/src/network_systems/scripts/run_virtual_iridium.sh"
RUN_HTTP_ECHO_SERVER_CMD="python3 $ENV{ROS_WORKSPACE}/src/network_systems/scripts/http_echo_server.py"
)

set(srcs
Expand Down
81 changes: 65 additions & 16 deletions projects/local_transceiver/inc/at_cmds.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,26 +4,61 @@
// Section numbers in this header file refer to this document

#include <cstdint>
#include <sstream>
#include <string>
#include <vector>

namespace AT
{
const std::string DELIMITER = "\r";

const std::string DELIMITER = "\r\n";
const std::string STATUS_OK = "OK";
const std::string RSP_READY = "READY";

const std::string CHECK_CONN = "AT";
const std::string SBD_SESSION = "AT+SBDIX"; // 5.144

namespace write_bin // 5.154
{
const std::string CMD = "AT+SBDWB=";

const std::string CHECK_CONN = "AT" + DELIMITER;
const std::string SBD_SESSION = "AT+SBDIX" + DELIMITER; // 5.144
namespace rsp
{
const std::string SUCCESS = "0";
const std::string TIMEOUT = "1";
const std::string BAD_CHECKSUM = "2";
const std::string WRONG_SIZE = "3";
} // namespace rsp
} // namespace write_bin

/**
* @brief Simple Line struct to help enforce DRY when dealing with strings while performing reads and writes
*
*/
struct Line
{
/**
* @param str valid AT command or response string
*/
inline explicit Line(const std::string & str)
: str_((str == AT::DELIMITER || str == "\n" || str == "\r") ? str : (str + "\r"))
{
}
// In most cases, str_ will just be the input str to the constructor + "\r"
// AT::DELIMITER, \n, and \r are exceptions, and remain the same
const std::string str_;
};

/**
* Struct representing the response to the CHECK_STATUS command
* 5.144
*/
struct SBDStatusResponse // TODO(Jng468): Implement this class
struct SBDStatusRsp // TODO(Jng468): Implement this class
{
static constexpr uint8_t MO_SUCCESS_START = 0;
static constexpr uint8_t MO_SUCCESS_END = 5;
static constexpr uint8_t MO_SUCCESS_END = 4;

uint8_t MO_status_;
uint8_t MO_status_; // indicates if MO message is transferred successfully [1, 4]
uint16_t MOMSN_;
uint8_t MT_status_;
uint16_t MTMSN_;
Expand All @@ -33,17 +68,31 @@ struct SBDStatusResponse // TODO(Jng468): Implement this class
/**
* @brief Construct a new Status Response object
*
* @param rsp_string string of format "+SBDIX:<MO status>,<MOMSN>,<MT status>,<MTMSN>,<MT length>,<MTqueued>""
* @param rsp_string string of format "+SBDIX:<MO status>,<MOMSN>,<MT status>,<MTMSN>,<MT length>,<MTqueued>"
*/
explicit SBDStatusResponse(const std::string & rsp_string)
explicit SBDStatusRsp(const std::string & rsp_string)
{
(void)rsp_string;
MO_status_ = 0;
MOMSN_ = 0;
MT_status_ = 0;
MTMSN_ = 0;
MT_len_ = 0;
MT_queued_ = 0;
size_t begin_point = rsp_string.find(':');
std::string data = rsp_string.substr(begin_point + 1);
std::vector<std::string> tokens;

size_t start = 0;
size_t end;
while ((end = data.find(',', start)) != std::string::npos) {
tokens.push_back(data.substr(start, end - start));
start = end + 1;
}
tokens.push_back(data.substr(start));

// assign index numbers
enum { MO_STATUS_INDEX, MOMSN_INDEX, MT_STATUS_INDEX, MTMSN_INDEX, MT_LEN_INDEX, MT_QUEUED_INDEX };

MO_status_ = std::stoi(tokens[MO_STATUS_INDEX]);
MOMSN_ = std::stoi(tokens[MOMSN_INDEX]);
MT_status_ = std::stoi(tokens[MT_STATUS_INDEX]);
MTMSN_ = std::stoi(tokens[MTMSN_INDEX]);
MT_len_ = std::stoi(tokens[MT_LEN_INDEX]);
MT_queued_ = std::stoi(tokens[MT_QUEUED_INDEX]);
};

/**
Expand All @@ -52,7 +101,7 @@ struct SBDStatusResponse // TODO(Jng468): Implement this class
* @return true on success
* @return false on failure
*/
bool MOSuccess() const { return MO_status_ < MO_SUCCESS_END; }
bool MOSuccess() const { return MO_status_ <= MO_SUCCESS_END; }
};

} // namespace AT
67 changes: 42 additions & 25 deletions projects/local_transceiver/inc/local_transceiver.h
Original file line number Diff line number Diff line change
@@ -1,16 +1,18 @@
#pragma once

#include <boost/asio/io_service.hpp>
#include <boost/asio/serial_port.hpp>
#include <custom_interfaces/msg/ais_ships.hpp>
#include <custom_interfaces/msg/batteries.hpp>
#include <custom_interfaces/msg/generic_sensors.hpp>
#include <custom_interfaces/msg/gps.hpp>
#include <custom_interfaces/msg/l_path_data.hpp>
#include <custom_interfaces/msg/wind_sensors.hpp>
#include <rclcpp/node.hpp>
#include <boost/asio/streambuf.hpp>
#include <string>

#include "at_cmds.h"
#include "boost/asio/io_service.hpp"
#include "boost/asio/serial_port.hpp"
#include "custom_interfaces/msg/ais_ships.hpp"
#include "custom_interfaces/msg/batteries.hpp"
#include "custom_interfaces/msg/generic_sensors.hpp"
#include "custom_interfaces/msg/gps.hpp"
#include "custom_interfaces/msg/l_path_data.hpp"
#include "custom_interfaces/msg/wind_sensors.hpp"
#include "rclcpp/node.hpp"
#include "sensors.pb.h"

namespace msg = custom_interfaces::msg;
Expand Down Expand Up @@ -109,9 +111,9 @@ class LocalTransceiver
* @brief Send a debug command and return the output
*
* @param cmd string to send to the serial port
* @return output of the sent cmd
* @return response to the sent command as a string if successful, std::nullopt on failure
*/
std::string debugSend(const std::string & cmd);
std::optional<std::string> debugSend(const std::string & cmd);

/**
* @brief Retrieve the latest message from the remote server via the serial port
Expand All @@ -121,6 +123,12 @@ class LocalTransceiver
std::string receive();

private:
// Serial port read/write timeout
constexpr static const struct timeval TIMEOUT
{
0, // seconds
200000 // microseconds
};
// boost io service - required for boost::asio operations
boost::asio::io_service io_;
// serial port data where is sent and received
Expand All @@ -133,36 +141,45 @@ class LocalTransceiver
*
* @param cmd command to send
*/
void send(const std::string & cmd);
bool send(const AT::Line & cmd);

/**
* @brief Parse the message received from the remote server
* @brief Read responses from serial
*
* @param msg message received from the remote server
* @return the data byte string payload from the message
* @param expected_rsps expected responses
* @return true if all expected responses are read successfully, false otherwise
*/
static std::string parseInMsg(const std::string & msg);
bool rcvRsps(std::initializer_list<const AT::Line> expected_rsps);

bool rcvRsp(const AT::Line & expected_rsp);

std::optional<std::string> readRsp();

/**
* @brief Read a line from serial
* @brief Parse the message received from the remote server
*
* @return line
* @param msg message received from the remote server
* @return the data byte string payload from the message
*/
std::string readLine();
static std::string parseInMsg(const std::string & msg);

/**
* @brief Check that the last command sent to serial was valid
* @brief Convert a boost::asio::streambuf into a string
* @warning Flushes the streambuf object
*
* @return true if valid
* @return false if invalid
* @param buf streambuf to convert
* @return buf contents as a string
*/
bool checkOK();
static std::string streambufToStr(boost::asio::streambuf & buf);

/**
* @brief Compute a checksum
* @brief Compute the checksum of a binary data string.
* The checksum is the least significant 2 bytes of the
* sum of all bytes in the data string, where each character
* is one byte.
*
* @param data data string
* @return checksum as a string
* @return checksum value
*/
static std::string checksum(const std::string & data);
};
Loading

0 comments on commit 0f4f67b

Please sign in to comment.