Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
5502e91
updates
Jng468 Nov 1, 2025
e2f2713
ros service set up and potentially working
Jng468 Nov 1, 2025
1b73e86
updates
Jng468 Nov 15, 2025
cee8a79
Merge branch 'main' into dev-620
Jng468 Nov 15, 2025
616b342
merge changes
Jng468 Nov 15, 2025
04a459a
update
Jng468 Nov 16, 2025
d9a8e72
fixes
Jng468 Nov 16, 2025
3ce7463
Merge branch 'main' into dev-620
Jng468 Nov 22, 2025
b403ddf
Added echo response
Apps247 Jan 10, 2026
e7b2da6
Updated comments
Apps247 Jan 10, 2026
de89ade
Improved debug print message
Apps247 Jan 10, 2026
09966cb
Improved debug print message
Apps247 Jan 10, 2026
5457354
Merge branch 'main' into dev-620
Jng468 Jan 10, 2026
78e6cf0
Merge remote-tracking branch 'origin/dev-620' into user/Apps247/714-n…
Apps247 Jan 10, 2026
14a993f
Changed ros service to use debugSend function
Apps247 Jan 10, 2026
81b8cdf
Changed ros service to use debugSendAT
Apps247 Jan 10, 2026
034eb7f
Add ros user to dialout group in container
lross03 Jan 11, 2026
78edcc0
Separated debug_send_data ros service from regular send_data. Also ad…
Apps247 Jan 15, 2026
946f88c
Commented out \r character check
Apps247 Jan 24, 2026
ac9206c
Switched from cout/cerr to ros logging in debugSendAT
Apps247 Jan 25, 2026
a647cc0
Clear incoming serial buffer before attempting send or debugSendAT
Apps247 Jan 29, 2026
c6e3fa4
Merge remote-tracking branch 'origin/main' into user/Apps247/714-new-…
Apps247 Jan 31, 2026
90905e9
Added skeleton for clearSerialBuffer
Apps247 Feb 7, 2026
108bae8
Fixed clearSerialBuffer
Apps247 Feb 7, 2026
5db0896
Added clearSerialBuffer calls to send()
Apps247 Feb 7, 2026
4399255
Commented out temporary logging
Apps247 Feb 7, 2026
1765919
Cleaned code
Apps247 Feb 7, 2026
1ffff36
Changed cout calls to logging callbacks so they can show on ros2 logs
Apps247 Feb 7, 2026
66f6ae2
Merge remote-tracking branch 'origin/main' into user/Apps247/714-new-…
Apps247 Feb 7, 2026
6878352
Remove sudo
lross03 Feb 7, 2026
6699146
Remove commented-out AT::Line
lross03 Feb 7, 2026
35f98bd
Merge branch 'main' into user/Apps247/714-new-create-debug-send-at-fu…
lross03 Feb 7, 2026
a3b478f
Merge branch 'main' into user/Apps247/714-new-create-debug-send-at-fu…
lross03 Feb 14, 2026
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
4 changes: 4 additions & 0 deletions .devcontainer/docker-compose.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,10 @@ services:
network_mode: host
privileged: true
user: ros
group_add:
- dialout
devices:
- /dev/ttyS0:/dev/ttyS0
# ports:
# website
#### We do not use anymore. We pulled website development out of docker in PR #614
Expand Down
2 changes: 1 addition & 1 deletion scripts/test.sh
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ if [[ "$PACKAGE" == "network_systems" || "$PACKAGE" == "" ]]; then

NET_DIR=src/network_systems
if [ -d $NET_DIR ]; then
./scripts/run_virtual_iridium.sh &> /dev/null &
./scripts/run_virtual_iridium.sh &> /tmp/virtual_iridium.log &
pushd $NET_DIR
./scripts/sailbot_db sailbot_db --clear
./scripts/sailbot_db sailbot_db --populate
Expand Down
1 change: 1 addition & 0 deletions src/network_systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ set(ROS_DEPS
rclcpp
std_msgs
custom_interfaces
std_srvs
)
find_package(ament_cmake REQUIRED)
foreach(dep IN LISTS ROS_DEPS)
Expand Down
1 change: 1 addition & 0 deletions src/network_systems/lib/cmn_hdrs/shared_constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ namespace SYSTEM_MODE
{
static const std::string PROD = "production";
static const std::string DEV = "development";
static const std::string TEST_SAT = "test_satellite";
}; // namespace SYSTEM_MODE

constexpr unsigned int MAX_LOCAL_TO_REMOTE_PAYLOAD_SIZE_BYTES = 340;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ set(module local_transceiver)

set(link_libs
${PROTOBUF_LINK_LIBS}
CURL::libcurl
)

set(inc_dirs
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <boost/asio/streambuf.hpp>
#include <functional>
#include <string>

#include "at_cmds.h"
Expand Down Expand Up @@ -29,6 +30,17 @@ class LocalTransceiver
friend class TestLocalTransceiver_checkCache_Test;

public:
// Logging callback types
using LogCallback = std::function<void(const std::string &)>;

/**
* @brief Set logging callbacks for debug and error messages
*
* @param debug_cb Callback for debug messages
* @param error_cb Callback for error messages
*/
void setLogCallbacks(LogCallback debug_cb, LogCallback error_cb);

/**
* @brief Update the sensor with new GPS data
*
Expand Down Expand Up @@ -104,6 +116,17 @@ class LocalTransceiver
*/
bool send();

/**
* @brief Debug helper that sends a small payload through the same
* flow used by `send()` but using the provided bytes. Useful for
* testing without serializing the full sensors protobuf.
* ticket #714
*
* @param data payload to send
* @return true on success, false on failure
*/
bool debugSendAT(const std::string & data);

/**
* @brief Send a debug command and return the output
*
Expand Down Expand Up @@ -150,6 +173,9 @@ class LocalTransceiver
boost::asio::serial_port serial_;
// underlying sensors object
Polaris::Sensors sensors_;
// Logging callbacks
LogCallback log_debug_;
LogCallback log_error_;

/**
* @brief Send a command to the serial port
Expand All @@ -170,6 +196,13 @@ class LocalTransceiver

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

/**
* @brief Drain/clear any pending data in the serial buffer to remove stale data
* from previous iterations or operations. This helps prevent data from one attempt/operation
* from interfering with subsequent reads.
*/
void clearSerialBuffer();

/**
* @brief Parse the message received from the remote server
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,12 @@ void LocalTransceiver::updateSensor(msg::LPathData localData)

Sensors LocalTransceiver::sensors() { return sensors_; }

void LocalTransceiver::setLogCallbacks(LogCallback debug_cb, LogCallback error_cb)
{
log_debug_ = debug_cb;
log_error_ = error_cb;
}

LocalTransceiver::LocalTransceiver(const std::string & port_name, const uint32_t baud_rate) : serial_(io_, port_name)
{
serial_.set_option(bio::serial_port_base::baud_rate(baud_rate));
Expand Down Expand Up @@ -129,6 +135,8 @@ bool LocalTransceiver::send()

static constexpr int MAX_NUM_RETRIES = 20; // allow retries because the connection is imperfect
for (int i = 0; i < MAX_NUM_RETRIES; i++) {
clearSerialBuffer(); // Clear any stale data from previous iteration

if (!send(at_write_cmd)) {
continue;
}
Expand Down Expand Up @@ -166,8 +174,9 @@ bool LocalTransceiver::send()
continue;
}

clearSerialBuffer(); // Clear any data that may have come in while waiting for SBDIX response, to ensure the following readRsp gets a clean response

if (!rcvRsps({
AT::Line("\r"),
sbdix_cmd,
AT::Line(AT::DELIMITER),
})) {
Expand Down Expand Up @@ -197,6 +206,144 @@ bool LocalTransceiver::send()
return false;
}

bool LocalTransceiver::debugSendAT(const std::string & data)
{
if (data.size() >= MAX_LOCAL_TO_REMOTE_PAYLOAD_SIZE_BYTES) {
if (log_error_) {
log_error_(
"Debug message/data too large: " + std::to_string(data.size()) + " bytes, but with a limit of " +
std::to_string(MAX_LOCAL_TO_REMOTE_PAYLOAD_SIZE_BYTES) + " bytes");
}
return false;
}

if (log_debug_) {
log_debug_("Debug: Sending " + std::to_string(data.size()) + " bytes via debugSendAT");
}

std::string write_bin_cmd_str = AT::write_bin::CMD + std::to_string(data.size());
AT::Line at_write_cmd(write_bin_cmd_str);

static constexpr int MAX_NUM_RETRIES = 20;
for (int i = 0; i < MAX_NUM_RETRIES; i++) {
if (log_debug_) {
log_debug_("Debug: clearing buffer (attempt " + std::to_string(i) + ")");
}
clearSerialBuffer(); // Clear any stale data from previous iteration

if (log_debug_) {
log_debug_("Debug: cleared buffer, sending write command (attempt " + std::to_string(i) + ")");
}
if (!send(at_write_cmd)) {
if (log_error_) {
log_error_("Debug: failed to send write command (attempt " + std::to_string(i) + ")");
}
continue;
}
if (log_debug_) {
log_debug_("Debug: sent write command (attempt " + std::to_string(i) + "): " + at_write_cmd.str_);
}

if (!rcvRsps({
at_write_cmd,
AT::Line(AT::DELIMITER),
AT::Line(AT::RSP_READY),
AT::Line("\n"),
})) {
if (log_error_) {
log_error_("Debug: did not receive ready prompt (attempt " + std::to_string(i) + ")");
}
continue;
}
if (log_debug_) {
log_debug_("Debug: received ready prompt (attempt " + std::to_string(i) + ")");
}

std::string msg_str = data + checksum(data);
AT::Line msg(msg_str);
if (!send(msg)) {
if (log_error_) {
log_error_("Debug: failed to send payload (attempt " + std::to_string(i) + ")");
}
continue;
}
if (log_debug_) {
log_debug_("Debug: sent payload (attempt " + std::to_string(i) + "): " + msg.str_);
}

if (!rcvRsps({
AT::Line(AT::DELIMITER),
AT::Line(AT::write_bin::rsp::SUCCESS),
AT::Line("\n"),
AT::Line(AT::DELIMITER),
AT::Line(AT::STATUS_OK),
AT::Line("\n"),
})) {
if (log_error_) {
log_error_("Debug: write did not complete successfully (attempt " + std::to_string(i) + ")");
}
continue;
}
if (log_debug_) {
log_debug_("Debug: write completed successfully (attempt " + std::to_string(i) + ")");
}

clearSerialBuffer();

static const AT::Line sbdix_cmd = AT::Line(AT::SBD_SESSION);
if (!send(sbdix_cmd)) {
if (log_error_) {
log_error_("Debug: failed to send SBDIX command (attempt " + std::to_string(i) + ")");
}
continue;
}
if (log_debug_) {
log_debug_("Debug: sent SBDIX command (attempt " + std::to_string(i) + "): " + sbdix_cmd.str_);
}

if (!rcvRsps({
sbdix_cmd,
AT::Line(AT::DELIMITER),
})) {
if (log_error_) {
log_error_("Debug: did not receive SBDIX response header (attempt " + std::to_string(i) + ")");
}
continue;
}
if (log_debug_) {
log_debug_("Debug: received SBDIX response header (attempt " + std::to_string(i) + ")");
}

auto opt_rsp = readRsp();
if (!opt_rsp) {
if (log_error_) {
log_error_("Debug: readRsp returned no response (attempt " + std::to_string(i) + ")");
}
continue;
}
if (log_debug_) {
log_debug_("Debug: readRsp received response (attempt " + std::to_string(i) + "): " + opt_rsp.value());
}

std::string opt_rsp_val = opt_rsp.value();
std::vector<std::string> sbd_status_vec;
boost::algorithm::split(sbd_status_vec, opt_rsp_val, boost::is_any_of(AT::DELIMITER));

AT::SBDStatusRsp rsp(sbd_status_vec[0]);
if (rsp.MOSuccess()) {
if (log_debug_) {
log_debug_("Debug: debugSendAT transmitted successfully");
}
return true;
}
}

if (log_error_) {
log_error_("Debug: Failed to transmit debug payload to satellite");
}
return false;
}

std::optional<std::string> LocalTransceiver::debugSend(const std::string & cmd)
{
AT::Line at_cmd(cmd);
Expand All @@ -215,6 +362,7 @@ void LocalTransceiver::cacheGlobalWaypoints(std::string receivedDataBuffer)
std::filesystem::path cache_temp{CACHE_TEMP_PATH};
std::ofstream writeFile(CACHE_TEMP_PATH, std::ios::binary);
if (!writeFile) {
// Note: This is a static method, so no logging callback available
std::cerr << "Failed to create temp cache file" << std::endl;
}
writeFile.write(receivedDataBuffer.data(), static_cast<std::streamsize>(receivedDataBuffer.size()));
Expand Down Expand Up @@ -387,6 +535,11 @@ bool LocalTransceiver::rcvRsp(const AT::Line & expected_rsp)
std::cerr << "Expected to read: \"" << expected_rsp.str_ << "\"\nbut read: \"" << outstr << "\"" << std::endl;
return false;
}

if (log_debug_) {
log_debug_("Debug: received expected response: " + outstr + "\n");
}

return true;
}

Expand All @@ -410,6 +563,7 @@ std::optional<std::string> LocalTransceiver::readRsp()

std::string rsp_str = streambufToStr(buf);
rsp_str.pop_back(); // Remove the "\n"

return rsp_str;
}

Expand All @@ -433,3 +587,41 @@ std::string LocalTransceiver::streambufToStr(bio::streambuf & buf)
buf.consume(buf.size());
return str;
}

void LocalTransceiver::clearSerialBuffer()
{
int fd = serial_.lowest_layer().native_handle();
int old_flags = fcntl(fd, F_GETFL, 0);
fcntl(fd, F_SETFL, old_flags | O_NONBLOCK);

const std::size_t SERIAL_BUFFER_SIZE = 1024;
std::vector<char> buf(SERIAL_BUFFER_SIZE);

while (true) {
ssize_t bytes_read = ::read(fd, buf.data(), buf.size());
if (bytes_read > 0) {
if (log_debug_) {
log_debug_("Cleared " + std::to_string(bytes_read) + " bytes from serial buffer.");
}
continue;
}
if (bytes_read == 0) {
if (log_debug_) {
log_debug_("Serial buffer cleared successfully.");
}
break;
}
if (errno == EAGAIN || errno == EWOULDBLOCK) {
if (log_debug_) {
log_debug_("No more data to read from serial buffer.");
}
break;
}
if (log_error_) {
log_error_("Failed to read from serial port with error: " + std::to_string(errno));
}
break;
}

fcntl(fd, F_SETFL, old_flags); // Restore original flags
}
Loading