- 继承自 MinHandler - 配置参数化 - 尝试使用launnch 文件 Signed-off-by: a1012112796 <1012112796@qq.com>
47 lines
1.1 KiB
C++
47 lines
1.1 KiB
C++
#include "test_topic/minSubscriber.h"
|
|
|
|
MinSubscriber::MinSubscriber(int argc, char **argv):
|
|
MinHandler(argc, argv, "serial_sender")
|
|
{
|
|
}
|
|
|
|
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()
|
|
{
|
|
_serial.close();
|
|
}
|
|
|
|
void MinSubscriber::callback(const boost::shared_ptr<MsgType const> &msg)
|
|
{
|
|
ROS_INFO("I heard: [%s]", msg->data.c_str());
|
|
_serial.send(msg->data.c_str(), strlen(msg->data.c_str()));
|
|
}
|
|
|
|
int main(int argc, char *argv[])
|
|
{
|
|
MinSubscriber *nh = new MinSubscriber(argc, argv);
|
|
nh->run(4);
|
|
free(nh);
|
|
|
|
return 0;
|
|
}
|