Skip to content

Commit a63e95b

Browse files
authored
Merge pull request #11 from Meta-Team/wfy
Fix referee serial
2 parents c4e382c + e07b5ae commit a63e95b

2 files changed

Lines changed: 13 additions & 12 deletions

File tree

perception/referee_serial/include/referee_serial/referee_serial.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,9 @@
2020
using spb = asio::serial_port_base;
2121
using drivers::serial_driver::FlowControl;
2222
using drivers::serial_driver::Parity;
23-
using drivers::serial_driver::SerialPort;
2423
using drivers::serial_driver::StopBits;
2524
using drivers::serial_driver::SerialPortConfig;
25+
using drivers::serial_driver::SerialDriver;
2626

2727
/**
2828
* @class RefereeSerial
@@ -91,7 +91,7 @@ class RefereeSerial
9191
// Serial port
9292
std::unique_ptr<IoContext> ctx_;
9393
std::unique_ptr<SerialPortConfig> config_;
94-
std::unique_ptr<SerialPort> port_;
94+
std::unique_ptr<SerialDriver> serial_driver_;
9595
static std::string dev_name; ///< The path to the serial port.
9696
static constexpr const char* dev_null = "/dev/null";
9797
static constexpr uint32_t baud = 115200;

perception/referee_serial/src/referee_serial.cpp

Lines changed: 11 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,8 @@ RefereeSerial::RefereeSerial(const rclcpp::NodeOptions & options)
3030
auto dev_path = "/dev/" + dev_name; // default: /dev/referee_serial
3131
ctx_ = std::make_unique<IoContext>(2);
3232
config_ = std::make_unique<SerialPortConfig>(baud, fc, pt, sb);
33-
port_ = std::make_unique<SerialPort>(*ctx_, dev_name, *config_);
33+
serial_driver_ = std::make_unique<SerialDriver>(*ctx_);
34+
serial_driver_->init_port(dev_path, *config_);
3435
RCLCPP_INFO(node_->get_logger(), "RefereeSerial using serial port: %s", dev_path.c_str());
3536

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

4344
// open serial port
44-
if (!port_->is_open())
45+
if (!serial_driver_->port()->is_open())
4546
{
46-
port_->open();
47+
serial_driver_->port()->open();
4748
receive_thread = std::thread(&RefereeSerial::receive, this);
4849
}
4950

@@ -56,9 +57,9 @@ RefereeSerial::~RefereeSerial()
5657
{
5758
receive_thread.join();
5859
}
59-
if (port_->is_open())
60+
if (serial_driver_->port()->is_open())
6061
{
61-
port_->close();
62+
serial_driver_->port()->close();
6263
}
6364
if (ctx_)
6465
{
@@ -79,7 +80,7 @@ void RefereeSerial::receive()
7980
while (rclcpp::ok())
8081
{
8182
try {
82-
port_->receive(prefix);
83+
serial_driver_->port()->receive(prefix);
8384

8485
if (KeyMouse::is_wanted_pre(prefix)) // key mouse
8586
{
@@ -129,7 +130,7 @@ void RefereeSerial::handle_frame(const std::vector<uint8_t>& prefix,
129130
{
130131
std::vector<uint8_t> frame;
131132
frame.resize(sizeof(typename PARSE::FrameType) - prefix.size());
132-
port_->receive(frame);
133+
serial_driver_->port()->receive(frame);
133134
frame.insert(frame.begin(), prefix.begin(), prefix.end());
134135

135136
PARSE info(frame); // parse the frame
@@ -152,11 +153,11 @@ void RefereeSerial::reopen_port()
152153
{
153154
RCLCPP_WARN(node_->get_logger(), "Reopening serial port");
154155
try {
155-
if (port_->is_open())
156+
if (serial_driver_->port()->is_open())
156157
{
157-
port_->close();
158+
serial_driver_->port()->close();
158159
}
159-
port_->open();
160+
serial_driver_->port()->open();
160161
RCLCPP_INFO(node_->get_logger(), "Serial port reopened");
161162
}
162163
catch (const std::exception & e)

0 commit comments

Comments
 (0)