Skip to content

Commit

Permalink
latest changes
Browse files Browse the repository at this point in the history
  • Loading branch information
hhenry01 committed Mar 9, 2024
1 parent 3b6a51e commit 7d15338
Show file tree
Hide file tree
Showing 19 changed files with 690 additions and 128 deletions.
4 changes: 3 additions & 1 deletion src/network_systems/functions.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,13 @@ function(make_exe module srcs link_libs inc_dirs compile_defs)
add_executable(${bin_module} ${srcs})
target_compile_definitions(${bin_module} PUBLIC ${compile_defs})
ament_target_dependencies(${bin_module} PUBLIC ${ROS_DEPS})
target_link_libraries(${bin_module} PUBLIC ${link_libs} boost_program_options)
target_link_libraries(${bin_module} PUBLIC ${link_libs} boost_program_options net_node)
target_include_directories(
${bin_module} PUBLIC
${CMAKE_CURRENT_LIST_DIR}/inc
${CMAKE_SOURCE_DIR}/lib
${inc_dirs}
${net_node_inc_dir}
)
add_dependencies(${bin_module} ${AUTOGEN_TARGETS})
install(TARGETS ${bin_module} DESTINATION lib/${PROJECT_NAME})
Expand All @@ -50,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 src/network_systems/lib/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
add_subdirectory(cmn_hdrs)
add_subdirectory(net_node)
add_subdirectory(protofiles)
add_subdirectory(sailbot_db)

Expand Down
15 changes: 15 additions & 0 deletions src/network_systems/lib/net_node/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
set(module net_node)

set(link_libs
)

set(inc_dirs
)

set(compile_defs
)

set(srcs
${CMAKE_CURRENT_LIST_DIR}/src/net_node.cpp
)
make_lib(${module} "${srcs}" "${link_libs}" "${inc_dirs}" "${compile_defs}")
53 changes: 53 additions & 0 deletions src/network_systems/lib/net_node/inc/net_node.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
#pragma once
#include <rclcpp/rclcpp.hpp>

/**
* Network Systems custom ROS Node.
* Redirects std::cout and std::cerr streams to ROS logging macros.
* @note An extra newline character is added to ROS logs from redirected streams. Not the prettiest, but it's harmless.
* Errors are extra ugly, with multiple empty newlines. It does make them extra obvious though.
*/
class NetNode : public rclcpp::Node
{
public:
/**
* @brief Initialize a NetNode's buffers and stream redirections
*
* @param node_name Name of the node to pass to the base rclcpp::Node
*/
explicit NetNode(const std::string & node_name);
~NetNode();

private:
/**
* @brief Custom string buffer that flushes its contents to ROS logging macros.
* https://stackoverflow.com/a/14232652
*/
class LogBuf : public std::stringbuf
{
public:
/**
* @brief Initialize a LogBuf for the NetNode
*
* @param fd File descriptor. Must be either STDOUT_FILENO or STDERR_FILENO
* @param logger Logger object of from the encompassing NetNode
*/
LogBuf(int fd, rclcpp::Logger logger);

/**
* @brief Called when the buffer is flushed. Invokes ROS logging macros and clears buffer.
*
* @return 0
*/
virtual int sync();

private:
const int fd_; // File descriptor to redirect (either STDOUT_FILENO or STDERR_FILENO)
const rclcpp::Logger logger_; // Logger instance from the encompassing NetNode
};

std::streambuf * og_stdout_buf_; // Original buffer for stdout
std::streambuf * og_stderr_buf_; // Original buffer for stderr
LogBuf new_stdout_buf_; // LogBuf to redirect stdout to
LogBuf new_stderr_buf_; // LogBuf to redirect stderr to
};
42 changes: 42 additions & 0 deletions src/network_systems/lib/net_node/src/net_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
#include "net_node.h"

#include <rclcpp/rclcpp.hpp>

NetNode::NetNode(const std::string & node_name)
: rclcpp::Node(node_name),
// When constructing the new buffers, create a new rclcpp::Logger with ":net_node" appended to the name so that
// we can identify that redirected messages are output from this file, rather than the _ros_intf.cpp file.
// Hopefully this will help reduce confusion with respect to the printed line numbers.
new_stdout_buf_(STDOUT_FILENO, rclcpp::get_logger(std::string(this->get_logger().get_name()) + ":net_node")),
new_stderr_buf_(STDERR_FILENO, rclcpp::get_logger(std::string(this->get_logger().get_name()) + ":net_node"))
{
og_stdout_buf_ = std::cout.rdbuf();
og_stderr_buf_ = std::cerr.rdbuf();
std::cout.rdbuf(&new_stdout_buf_);
std::cerr.rdbuf(&new_stderr_buf_);
}

NetNode::~NetNode()
{
std::cout.rdbuf(og_stdout_buf_);
std::cerr.rdbuf(og_stderr_buf_);
}

NetNode::LogBuf::LogBuf(int fd, rclcpp::Logger logger) : fd_(fd), logger_(logger) {}

int NetNode::LogBuf::sync()
{
switch (fd_) {
case STDOUT_FILENO:
RCLCPP_INFO(logger_, "%s", this->str().c_str());
break;
case STDERR_FILENO:
RCLCPP_ERROR(logger_, "%s", this->str().c_str());
break;
default:
// unreachable
throw std::runtime_error("Invalid file descriptor! " + std::to_string(fd_));
}
this->str("");
return 0;
}
2 changes: 1 addition & 1 deletion src/network_systems/lib/sailbot_db/src/sailbot_db.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ bool SailbotDB::testConnection()
db.run_command(ping_cmd.view());
return true;
} catch (const std::exception & e) {
std::cout << "Exception: " << e.what() << std::endl;
std::cerr << "Exception: " << e.what() << std::endl;
return false;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "can_transceiver.h"
#include "cmn_hdrs/ros_info.h"
#include "cmn_hdrs/shared_constants.h"
#include "net_node.h"

constexpr int QUEUE_SIZE = 10; // Arbitrary number
constexpr auto TIMER_INTERVAL = std::chrono::milliseconds(500);
Expand All @@ -23,10 +24,10 @@ namespace msg = custom_interfaces::msg;
using CAN_FP::CanFrame;
using CAN_FP::CanId;

class CanTransceiverIntf : public rclcpp::Node
class CanTransceiverIntf : public NetNode
{
public:
CanTransceiverIntf() : Node("can_transceiver_node")
CanTransceiverIntf() : NetNode("can_transceiver_node")
{
this->declare_parameter("enabled", true);

Expand Down Expand Up @@ -188,8 +189,20 @@ class CanTransceiverIntf : public rclcpp::Node

int main(int argc, char * argv[])
{
bool err = false;
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<CanTransceiverIntf>());
try {
std::shared_ptr<CanTransceiverIntf> node = std::make_shared<CanTransceiverIntf>();
try {
rclcpp::spin(node);
} catch (std::exception & e) {
RCLCPP_ERROR(node->get_logger(), "%s", e.what());
throw e;
}
} catch (std::exception & e) {
std::cerr << e.what() << std::endl;
err = true;
}
rclcpp::shutdown();
return 0;
return err ? -1 : 0;
}
21 changes: 17 additions & 4 deletions src/network_systems/projects/example/src/cached_fib_ros_intf.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
// Include this module
#include "cached_fib.h"
#include "net_node.h"
// Include ROS headers
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/u_int64.hpp>
Expand All @@ -10,10 +11,10 @@ constexpr int ROS_Q_SIZE = 10;
constexpr int INIT_FIB_SIZE = 5;
} // namespace

class CachedFibNode : public rclcpp::Node
class CachedFibNode : public NetNode
{
public:
explicit CachedFibNode(const std::size_t initSize) : Node("cached_fib_node"), c_fib_(initSize)
explicit CachedFibNode(const std::size_t initSize) : NetNode("cached_fib_node"), c_fib_(initSize)
{
this->declare_parameter("enabled", false);
bool enabled = this->get_parameter("enabled").as_bool();
Expand Down Expand Up @@ -50,8 +51,20 @@ class CachedFibNode : public rclcpp::Node

int main(int argc, char * argv[])
{
bool err = false;
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<CachedFibNode>(INIT_FIB_SIZE));
try {
std::shared_ptr<CachedFibNode> node = std::make_shared<CachedFibNode>(INIT_FIB_SIZE);
try {
rclcpp::spin(node);
} catch (std::exception & e) {
RCLCPP_ERROR(node->get_logger(), "%s", e.what());
throw e;
}
} catch (std::exception & e) {
std::cerr << e.what() << std::endl;
err = true;
}
rclcpp::shutdown();
return 0;
return err ? -1 : 0;
}
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 src/network_systems/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
Loading

0 comments on commit 7d15338

Please sign in to comment.