在minPublisher中使用自定义数据类型

Signed-off-by: a1012112796 <1012112796@qq.com>
This commit is contained in:
2021-09-15 15:28:14 +08:00
parent 5149c7c7d7
commit 6b98790c1b
4 changed files with 57 additions and 22 deletions

View File

@@ -148,7 +148,7 @@ include_directories( include ${catkin_INCLUDE_DIRS})
# ${catkin_LIBRARIES} # ${catkin_LIBRARIES}
# ) # )
add_executable(talker src/minPublisher.cpp src/WzSerialportPlus.cpp) add_executable(talker src/minPublisher.cpp src/WzSerialportPlus.cpp src/minHandler.cpp)
target_link_libraries(talker ${catkin_LIBRARIES}) target_link_libraries(talker ${catkin_LIBRARIES})
add_executable(listener src/minSubscriber.cpp src/WzSerialportPlus.cpp src/minHandler.cpp) add_executable(listener src/minSubscriber.cpp src/WzSerialportPlus.cpp src/minHandler.cpp)

View File

@@ -4,16 +4,19 @@
#include <ros/ros.h> #include <ros/ros.h>
#include <std_msgs/String.h> #include <std_msgs/String.h>
#include "test_topic/WzSerialportPlus.h" #include "test_topic/WzSerialportPlus.h"
#include "test_topic/minHandler.h"
using MsgType = std_msgs::String; using namespace xyfc_std;
class MinPublisher: ros::NodeHandle { class MinPublisher: public MinHandler {
public: public:
MinPublisher(); MinPublisher(int argc, char **argv);
~MinPublisher(); ~MinPublisher();
void run(const char *device); protected:
virtual bool node_init(void);
private: private:
ros::Publisher _sender; ros::Publisher _sender;
WzSerialportPlus _serial; WzSerialportPlus _serial;
void handle(void);
}; };
#endif #endif

View File

@@ -1,6 +1,10 @@
<launch> <launch>
<arg name="port" default="/dev/ttyUSB0" /> <arg name="port_in" default="/dev/ttyUSB0" />
<node pkg="test_topic" type="listener" name="serial_listen"> <arg name="port_out" default="/dev/ttyUSB1" />
<param name="port" value="$(arg port)" /> <node pkg="test_topic" type="talker" name="serial_talker">
<param name="port" value="$(arg port_in)" />
</node>
<node pkg="test_topic" type="listener" name="serial_listen" output="screen">
<param name="port" value="$(arg port_out)" />
</node> </node>
</launch> </launch>

View File

@@ -1,23 +1,44 @@
#include "test_topic/minPublisher.h" #include "test_topic/minPublisher.h"
MinPublisher::MinPublisher() MinPublisher::MinPublisher(int argc, char **argv):
MinHandler(argc, argv, "test_pub")
{ {
_sender = this->advertise<MsgType>("test_topic", 200); }
bool MinPublisher::node_init(void)
{
std::string port, topic;
int baud = 115200;
ros::param::param<std::string>("~port", port, "/dev/ttyUSB0");
ros::param::param<int>("~baud", baud, 115200);
ros::param::param<std::string>("~topic", topic, "test_topic");
ROS_INFO("will send '%s' tiopic", topic.c_str());
_sender = _node->advertise<MsgType>("test_topic", 200);
if (!_serial.open(port, baud, 1, 8, 'N'))
{
ROS_ERROR("open serial '%s' failed!", port.c_str());
return false;
}
ThreadFuncType thd = boost::bind(&MinPublisher::handle, this);
add_thread(thd);
return true;
} }
MinPublisher::~MinPublisher() MinPublisher::~MinPublisher()
{ {
_serial.close();
} }
void MinPublisher::run(const char *device) void MinPublisher::handle()
{ {
_serial.open(device, 115200, 1, 8, 'N');
char *read_buf = new char[500]; char *read_buf = new char[500];
while (ros::ok()) while (ok())
{ {
std_msgs::String msg; MsgType msg;
std::stringstream ss; std::stringstream ss;
memset(read_buf, 0, 500); memset(read_buf, 0, 500);
@@ -27,20 +48,27 @@ void MinPublisher::run(const char *device)
{ {
continue; continue;
} }
ss << read_buf;
msg.data = ss.str();
ROS_INFO("send: '%s'", msg.data.c_str()); for (int i =0; i < len; i++)
{
msg.data.push_back(read_buf[i]);
}
msg.length = len;
msg.tick = ros::Time::now();
ROS_INFO("send: '%s'", &msg.data[0]);
_sender.publish(msg); _sender.publish(msg);
} }
printf("MinPublisher: exit handle thread\n");
_serial.close();
} }
int main(int argc, char *argv[]) int main(int argc, char *argv[])
{ {
ros::init(argc, argv, "test_pub_node"); MinPublisher *nh = new MinPublisher(argc, argv);
MinPublisher nh; nh->run(4);
free(nh);
nh.run("/dev/ttyUSB0");
return 0; return 0;
} }