Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,9 @@
using spb = asio::serial_port_base;
using drivers::serial_driver::FlowControl;
using drivers::serial_driver::Parity;
using drivers::serial_driver::SerialPort;
using drivers::serial_driver::StopBits;
using drivers::serial_driver::SerialPortConfig;
using drivers::serial_driver::SerialDriver;

/**
* @class RefereeSerial
Expand Down Expand Up @@ -91,7 +91,7 @@ class RefereeSerial
// Serial port
std::unique_ptr<IoContext> ctx_;
std::unique_ptr<SerialPortConfig> config_;
std::unique_ptr<SerialPort> port_;
std::unique_ptr<SerialDriver> serial_driver_;
static std::string dev_name; ///< The path to the serial port.
static constexpr const char* dev_null = "/dev/null";
static constexpr uint32_t baud = 115200;
Expand Down
21 changes: 11 additions & 10 deletions perception/referee_serial/src/referee_serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@ RefereeSerial::RefereeSerial(const rclcpp::NodeOptions & options)
auto dev_path = "/dev/" + dev_name; // default: /dev/referee_serial
ctx_ = std::make_unique<IoContext>(2);
config_ = std::make_unique<SerialPortConfig>(baud, fc, pt, sb);
port_ = std::make_unique<SerialPort>(*ctx_, dev_name, *config_);
serial_driver_ = std::make_unique<SerialDriver>(*ctx_);
serial_driver_->init_port(dev_path, *config_);
RCLCPP_INFO(node_->get_logger(), "RefereeSerial using serial port: %s", dev_path.c_str());

// create publishers
Expand All @@ -41,9 +42,9 @@ RefereeSerial::RefereeSerial(const rclcpp::NodeOptions & options)
robot_state_pub_ = node_->create_publisher<operation_interface::msg::RobotState>("robot_state", 10);

// open serial port
if (!port_->is_open())
if (!serial_driver_->port()->is_open())
{
port_->open();
serial_driver_->port()->open();
receive_thread = std::thread(&RefereeSerial::receive, this);
}

Expand All @@ -56,9 +57,9 @@ RefereeSerial::~RefereeSerial()
{
receive_thread.join();
}
if (port_->is_open())
if (serial_driver_->port()->is_open())
{
port_->close();
serial_driver_->port()->close();
}
if (ctx_)
{
Expand All @@ -79,7 +80,7 @@ void RefereeSerial::receive()
while (rclcpp::ok())
{
try {
port_->receive(prefix);
serial_driver_->port()->receive(prefix);

if (KeyMouse::is_wanted_pre(prefix)) // key mouse
{
Expand Down Expand Up @@ -129,7 +130,7 @@ void RefereeSerial::handle_frame(const std::vector<uint8_t>& prefix,
{
std::vector<uint8_t> frame;
frame.resize(sizeof(typename PARSE::FrameType) - prefix.size());
port_->receive(frame);
serial_driver_->port()->receive(frame);
frame.insert(frame.begin(), prefix.begin(), prefix.end());

PARSE info(frame); // parse the frame
Expand All @@ -152,11 +153,11 @@ void RefereeSerial::reopen_port()
{
RCLCPP_WARN(node_->get_logger(), "Reopening serial port");
try {
if (port_->is_open())
if (serial_driver_->port()->is_open())
{
port_->close();
serial_driver_->port()->close();
}
port_->open();
serial_driver_->port()->open();
RCLCPP_INFO(node_->get_logger(), "Serial port reopened");
}
catch (const std::exception & e)
Expand Down