mirror of
https://github.com/westonrobot/ugv_sdk
synced 2023-04-08 06:32:14 +08:00
async_port: updated latest async_port impl from wrp_sdk
This commit is contained in:
@@ -20,9 +20,11 @@
|
||||
|
||||
namespace westonrobot {
|
||||
AsyncCAN::AsyncCAN(std::string can_port)
|
||||
: AsyncPortBase(can_port), socketcan_stream_(io_context_) {}
|
||||
: port_(can_port), socketcan_stream_(io_context_) {}
|
||||
|
||||
bool AsyncCAN::SetupPort() {
|
||||
AsyncCAN::~AsyncCAN() { Close(); }
|
||||
|
||||
bool AsyncCAN::Open() {
|
||||
try {
|
||||
const size_t iface_name_size = strlen(port_.c_str()) + 1;
|
||||
if (iface_name_size > IFNAMSIZ) return false;
|
||||
@@ -36,7 +38,7 @@ bool AsyncCAN::SetupPort() {
|
||||
|
||||
const int ioctl_result = ioctl(can_fd_, SIOCGIFINDEX, &ifr);
|
||||
if (ioctl_result < 0) {
|
||||
StopService();
|
||||
Close();
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -48,13 +50,14 @@ bool AsyncCAN::SetupPort() {
|
||||
const int bind_result =
|
||||
bind(can_fd_, (struct sockaddr *)&addr, sizeof(addr));
|
||||
if (bind_result < 0) {
|
||||
StopService();
|
||||
Close();
|
||||
return false;
|
||||
}
|
||||
|
||||
port_opened_ = true;
|
||||
std::cout << "Start listening to port: " << port_ << std::endl;
|
||||
} catch (std::system_error &e) {
|
||||
port_opened_ = false;
|
||||
std::cout << e.what() << std::endl;
|
||||
return false;
|
||||
}
|
||||
@@ -72,15 +75,17 @@ bool AsyncCAN::SetupPort() {
|
||||
std::ref(socketcan_stream_)));
|
||||
#endif
|
||||
|
||||
// start io thread
|
||||
io_thread_ = std::thread([this]() { io_context_.run(); });
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void AsyncCAN::StopService() {
|
||||
// stop io thread
|
||||
void AsyncCAN::Close() {
|
||||
io_context_.stop();
|
||||
if (io_thread_.joinable()) io_thread_.join();
|
||||
io_context_.reset();
|
||||
|
||||
|
||||
// release port fd
|
||||
const int close_result = ::close(can_fd_);
|
||||
can_fd_ = -1;
|
||||
@@ -88,6 +93,8 @@ void AsyncCAN::StopService() {
|
||||
port_opened_ = false;
|
||||
}
|
||||
|
||||
bool AsyncCAN::IsOpened() const { return port_opened_; }
|
||||
|
||||
void AsyncCAN::DefaultReceiveCallback(can_frame *rx_frame) {
|
||||
std::cout << std::hex << rx_frame->can_id << " ";
|
||||
for (int i = 0; i < rx_frame->can_dlc; i++)
|
||||
@@ -102,7 +109,7 @@ void AsyncCAN::ReadFromPort(struct can_frame &rec_frame,
|
||||
asio::buffer(&rec_frame, sizeof(rec_frame)),
|
||||
[sthis](asio::error_code error, size_t bytes_transferred) {
|
||||
if (error) {
|
||||
sthis->StopService();
|
||||
sthis->Close();
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
@@ -19,15 +19,17 @@
|
||||
namespace westonrobot {
|
||||
|
||||
AsyncSerial::AsyncSerial(std::string port_name, uint32_t baud_rate)
|
||||
: AsyncPortBase(port_name),
|
||||
baud_rate_(baud_rate),
|
||||
serial_port_(io_context_) {}
|
||||
: port_(port_name), baud_rate_(baud_rate), serial_port_(io_context_) {}
|
||||
|
||||
AsyncSerial::~AsyncSerial() { Close(); }
|
||||
|
||||
void AsyncSerial::SetBaudRate(unsigned baudrate) {
|
||||
serial_port_.set_option(asio::serial_port_base::baud_rate(baudrate));
|
||||
}
|
||||
|
||||
bool AsyncSerial::SetupPort() {
|
||||
void AsyncSerial::SetHardwareFlowControl(bool enabled) { hwflow_ = enabled; }
|
||||
|
||||
bool AsyncSerial::Open() {
|
||||
using SPB = asio::serial_port_base;
|
||||
|
||||
try {
|
||||
@@ -67,15 +69,17 @@ bool AsyncSerial::SetupPort() {
|
||||
asio::post(io_context_, std::bind(&AsyncSerial::ReadFromPort, this));
|
||||
#endif
|
||||
|
||||
// start io thread
|
||||
io_thread_ = std::thread([this]() { io_context_.run(); });
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void AsyncSerial::StopService() {
|
||||
// stop io thread
|
||||
void AsyncSerial::Close() {
|
||||
io_context_.stop();
|
||||
if (io_thread_.joinable()) io_thread_.join();
|
||||
io_context_.reset();
|
||||
|
||||
|
||||
if (IsOpened()) {
|
||||
serial_port_.cancel();
|
||||
serial_port_.close();
|
||||
@@ -84,6 +88,8 @@ void AsyncSerial::StopService() {
|
||||
port_opened_ = false;
|
||||
}
|
||||
|
||||
bool AsyncSerial::IsOpened() const { return serial_port_.is_open(); }
|
||||
|
||||
void AsyncSerial::DefaultReceiveCallback(uint8_t *data, const size_t bufsize,
|
||||
size_t len) {}
|
||||
|
||||
@@ -93,7 +99,7 @@ void AsyncSerial::ReadFromPort() {
|
||||
asio::buffer(rx_buf_),
|
||||
[sthis](asio::error_code error, size_t bytes_transferred) {
|
||||
if (error) {
|
||||
sthis->StopService();
|
||||
sthis->Close();
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -122,7 +128,7 @@ void AsyncSerial::WriteToPort(bool check_if_busy) {
|
||||
asio::buffer(tx_buf_, len),
|
||||
[sthis](asio::error_code error, size_t bytes_transferred) {
|
||||
if (error) {
|
||||
sthis->StopService();
|
||||
sthis->Close();
|
||||
return;
|
||||
}
|
||||
std::lock_guard<std::recursive_mutex> lock(sthis->tx_mutex_);
|
||||
|
||||
@@ -15,7 +15,7 @@ bool ProtocolDectctor::Connect(std::string can_name) {
|
||||
can_ = std::make_shared<AsyncCAN>(can_name);
|
||||
can_->SetReceiveCallback(
|
||||
std::bind(&ProtocolDectctor::ParseCANFrame, this, std::placeholders::_1));
|
||||
return can_->StartListening();
|
||||
return can_->Open();
|
||||
}
|
||||
|
||||
ProtocolVersion ProtocolDectctor::DetectProtocolVersion(uint32_t timeout_sec) {
|
||||
|
||||
Reference in New Issue
Block a user