@@ -51,6 +51,8 @@ public:
|
||||
int send(const char* data,int length);
|
||||
|
||||
void setReceiveCalback(ReceiveCallback receiveCallback);
|
||||
int read_data(char* receive_buf, size_t receive_buf_size);
|
||||
void sync_read(void);
|
||||
|
||||
protected:
|
||||
virtual void onReceive(char* data,int length);
|
||||
|
@@ -3,7 +3,6 @@
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <std_msgs/String.h>
|
||||
#include <queue>
|
||||
#include "test_topic/WzSerialportPlus.h"
|
||||
|
||||
using MsgType = std_msgs::String;
|
||||
@@ -14,7 +13,6 @@ public:
|
||||
void run(const char *device);
|
||||
private:
|
||||
ros::Publisher _sender;
|
||||
std::queue<MsgType> _queue;
|
||||
WzSerialportPlus _serial;
|
||||
};
|
||||
|
||||
|
@@ -195,10 +195,25 @@ bool WzSerialportPlus::open()
|
||||
|
||||
receivable = true;
|
||||
|
||||
printf("[WzSerialportPlus::open()]: open success.\n");
|
||||
return true;
|
||||
}
|
||||
|
||||
int WzSerialportPlus::read_data(char* receive_buf, size_t receive_buf_size)
|
||||
{
|
||||
if (!receivable)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return read(serialportFd, receive_buf, receive_buf_size);
|
||||
}
|
||||
|
||||
void WzSerialportPlus::sync_read(void)
|
||||
{
|
||||
std::thread([&]{
|
||||
char* receiveData = new char[receiveMaxlength];
|
||||
int receivedLength = 0;
|
||||
int selectResult = -1;
|
||||
|
||||
while (receivable)
|
||||
{
|
||||
@@ -218,9 +233,6 @@ bool WzSerialportPlus::open()
|
||||
delete[] receiveData;
|
||||
receiveData = nullptr;
|
||||
}).detach();
|
||||
|
||||
printf("[WzSerialportPlus::open()]: open success.\n");
|
||||
return true;
|
||||
}
|
||||
|
||||
bool WzSerialportPlus::open(const std::string& name,
|
||||
|
@@ -12,29 +12,26 @@ MinPublisher::~MinPublisher()
|
||||
|
||||
void MinPublisher::run(const char *device)
|
||||
{
|
||||
_serial.setReceiveCalback([this](char* str,int length){
|
||||
MsgType msg;
|
||||
std::stringstream ss;
|
||||
ss << str;
|
||||
|
||||
msg.data = ss.str();
|
||||
|
||||
this->_queue.push(msg);
|
||||
});
|
||||
|
||||
_serial.open(device, 115200, 1, 8, 'N');
|
||||
char *read_buf = new char[500];
|
||||
|
||||
while (ros::ok())
|
||||
{
|
||||
while(_queue.size() > 0)
|
||||
std_msgs::String msg;
|
||||
std::stringstream ss;
|
||||
|
||||
memset(read_buf, 0, 500);
|
||||
|
||||
int len = _serial.read_data(read_buf, 500);
|
||||
if (len <= 0)
|
||||
{
|
||||
MsgType msg = _queue.front();
|
||||
continue;
|
||||
}
|
||||
ss << read_buf;
|
||||
msg.data = ss.str();
|
||||
|
||||
ROS_INFO("send: '%s'", msg.data.c_str());
|
||||
_sender.publish(msg);
|
||||
_queue.pop();
|
||||
}
|
||||
|
||||
usleep(50);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -43,7 +40,7 @@ int main(int argc, char *argv[])
|
||||
ros::init(argc, argv, "test_pub_node");
|
||||
MinPublisher nh;
|
||||
|
||||
nh.run("/dev/ttyUSB1");
|
||||
nh.run("/dev/ttyUSB0");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@@ -2,7 +2,7 @@
|
||||
|
||||
MinSubscriber::MinSubscriber()
|
||||
{
|
||||
_sub = this->subscribe<MsgType>("test_topic_2", 200, boost::bind(&MinSubscriber::callback, this, _1));
|
||||
_sub = this->subscribe<MsgType>("test_topic", 200, boost::bind(&MinSubscriber::callback, this, _1));
|
||||
}
|
||||
|
||||
MinSubscriber::~MinSubscriber()
|
||||
@@ -27,7 +27,7 @@ int main(int argc, char *argv[])
|
||||
ros::init(argc, argv, "test_sub_node");
|
||||
MinSubscriber nh;
|
||||
|
||||
nh.run("/dev/ttyUSB0");
|
||||
nh.run("/dev/ttyUSB1");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
Reference in New Issue
Block a user