如何让回调函数与main函数互相传值

在main函数中访问回调函数中处理的变量

做法是让类的成员函数做回调函数,在回调函数中处理相应变量,在main函数中实例化类,然后通过返回对象的成员进行访问

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
class Listener 
{
public:
double theta1f;
double theta2f;
double theta3f;

void callback(const std_msgs::Float32MultiArray::ConstPtr& msg);
};

void Listener::callback(const std_msgs::Float32MultiArray::ConstPtr& msg)
{
theta1f = msg->data[0];
theta2f = msg->data[1];
theta3f = msg->data[2];
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "node");
ros::NodeHandle nh;
ros::Rate loop_rate(30);
Listener listener;
ros::Subscriber sub = nh.subscribe<std_msgs::float32multiarray>("topic_subscribed", 1, &Listener::callback, &listener);
while (ros::ok())
{
ros::spinOnce();
ROS_INFO("This is theta1f: %.2f", listener.theta1f);
ROS_INFO("This is theta2f: %.2f", listener.theta2f);
ROS_INFO("This is theta2f: %.2f", listener.theta2f);
loop_rate.sleep();
}

return 0;
}



回调函数中访问main函数中的变量赋值

以前我都是用全局变量来实现,但这种方法总感觉不保险,后来发现ROS中有专门的解决方法,NodeHandle::subscribe有一个重载可以处理这种情况,用到了boost::bind,其实用std::bind也能实现。代码如下:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
#include <ros/ros.h>
#include <std_msgs/Int8.h>
//回调函数里访问main中的一个结构体
typedef struct _Struct
{
int m;
double n;
} myStruct;

void callback(const std_msgs::Int8ConstPtr& msg, myStruct p)
{
ROS_INFO("msg: %d", msg->data);
ROS_INFO("m: %d",p.m);
ROS_INFO("n: %f",p.n);
sleep(1);
}


int main(int argc, char** argv)
{
ros::init(argc,argv, "Sub");
ros::NodeHandle nh;

myStruct p;
p.m = 7;
p.n = 1.85;

// "_1" 是占位符,对应 void callback(const std_msgs::Int8ConstPtr& msg, myStruct p)第一个参数
/* subscribe (
* const std::string &base_topic,
* uint32_t queue_size,
* const boost::function< void(const std_msgs::Int8ConstPtr &)> &callback )
*/
ros::Subscriber sub = nh.subscribe<std_msgs::Int8>("topic", 20, boost::bind(&callback, _1, p) );
ros::spin();
return 0;
}

myStruct是我自定义的结构体,在main函数里对其声明的变量赋值,回调的形参里多了它的变量。
其中subscribe函数的原型是这个:

1
2
3
4
5
6
7
template<class M >
Subscriber ros::NodeHandle::subscribe(const std::string& topic,
uint32_t queue_size,
const boost::function< void(const boost::shared_ptr< M const > &)> & callback,
const VoidConstPtr & tracked_object = VoidConstPtr(),
const TransportHints & transport_hints = TransportHints()
)

boost::function对象能接受函数和仿函数, boost::bind创建了仿函数,包含了所有想传给回调函数的参数。

与平时的重载形式不同,这次要用到话题的模板类型,第三个形参不是回调函数的指针,而是boost::bind,其中_1是一个占位符,要传给回调函数参数,在发生函数调用时才接受实参;最后是结构体的变量。

注意:回调函数第一个形参必须是const std_msgs::Int8ConstPtr&形式,其他形式比如const std_msgs::Int8Ptr&会报错,另外看到一篇博客说这里不能用引用,但是我用引用也没报错。对于回调函数callback,一般在bind里不用&,但是用了也可以,因为bind可接受函数或函数指针

参考:
How to make callback function called by several subscriber?
How to pass arguments to/from subscriber callback functions