MinSubscriber 优化
- 继承自 MinHandler - 配置参数化 - 尝试使用launnch 文件 Signed-off-by: a1012112796 <1012112796@qq.com>
This commit is contained in:
@@ -150,7 +150,7 @@ include_directories( include ${catkin_INCLUDE_DIRS})
|
||||
add_executable(talker src/minPublisher.cpp src/WzSerialportPlus.cpp)
|
||||
target_link_libraries(talker ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(listener src/minSubscriber.cpp src/WzSerialportPlus.cpp)
|
||||
add_executable(listener src/minSubscriber.cpp src/WzSerialportPlus.cpp src/minHandler.cpp)
|
||||
target_link_libraries(listener ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(time_tacker src/timerPublisher.cpp)
|
||||
|
@@ -3,15 +3,17 @@
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <std_msgs/String.h>
|
||||
#include <queue>
|
||||
#include "test_topic/WzSerialportPlus.h"
|
||||
#include "test_topic/minHandler.h"
|
||||
|
||||
using MsgType = std_msgs::String;
|
||||
class MinSubscriber: ros::NodeHandle {
|
||||
using namespace xyfc_std;
|
||||
|
||||
class MinSubscriber: public MinHandler {
|
||||
public:
|
||||
MinSubscriber();
|
||||
MinSubscriber(int argc, char **argv);
|
||||
~MinSubscriber();
|
||||
void run(const char *device);
|
||||
protected:
|
||||
virtual bool node_init(void);
|
||||
private:
|
||||
ros::Subscriber _sub;
|
||||
WzSerialportPlus _serial;
|
||||
|
6
src/test_topic/launch/test1.launch
Normal file
6
src/test_topic/launch/test1.launch
Normal file
@@ -0,0 +1,6 @@
|
||||
<launch>
|
||||
<arg name="port" default="/dev/ttyUSB0" />
|
||||
<node pkg="test_topic" type="listener" name="serial_listen">
|
||||
<param name="port" value="$(arg port)" />
|
||||
</node>
|
||||
</launch>
|
@@ -1,8 +1,28 @@
|
||||
#include "test_topic/minSubscriber.h"
|
||||
|
||||
MinSubscriber::MinSubscriber()
|
||||
MinSubscriber::MinSubscriber(int argc, char **argv):
|
||||
MinHandler(argc, argv, "serial_sender")
|
||||
{
|
||||
_sub = this->subscribe<MsgType>("test_topic", 200, boost::bind(&MinSubscriber::callback, this, _1));
|
||||
}
|
||||
|
||||
bool MinSubscriber::node_init(void)
|
||||
{
|
||||
std::string port, topic;
|
||||
int baud = 115200;
|
||||
ros::param::param<std::string>("~port", port, "/dev/ttyACM0");
|
||||
ros::param::param<int>("~baud", baud, 57600);
|
||||
ros::param::param<std::string>("~topic", topic, "test_topic");
|
||||
|
||||
ROS_INFO("will listen '%s' tiopic", topic.c_str());
|
||||
_sub = _node->subscribe<MsgType>(topic, 200, boost::bind(&MinSubscriber::callback, this, _1));
|
||||
|
||||
if (!_serial.open(port, baud, 1, 8, 'N'))
|
||||
{
|
||||
ROS_ERROR("open serial '%s' failed!", port.c_str());
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
MinSubscriber::~MinSubscriber()
|
||||
@@ -16,18 +36,11 @@ void MinSubscriber::callback(const boost::shared_ptr<MsgType const> &msg)
|
||||
_serial.send(msg->data.c_str(), strlen(msg->data.c_str()));
|
||||
}
|
||||
|
||||
void MinSubscriber::run(const char *device)
|
||||
{
|
||||
_serial.open(device, 115200, 1, 8, 'N');
|
||||
ros::spin();
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
ros::init(argc, argv, "test_sub_node");
|
||||
MinSubscriber nh;
|
||||
|
||||
nh.run("/dev/ttyUSB1");
|
||||
MinSubscriber *nh = new MinSubscriber(argc, argv);
|
||||
nh->run(4);
|
||||
free(nh);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
Reference in New Issue
Block a user