forked from Archive/PX4-Autopilot
improve subsciber api
This commit is contained in:
parent
3f36d30a34
commit
1826fa5d39
|
@ -75,6 +75,7 @@ int main(int argc, char **argv)
|
|||
* away the oldest ones.
|
||||
*/
|
||||
px4::Subscriber* sub = n.subscribe("rc_channels", rc_channels_callback);
|
||||
PX4_INFO("subscribed");
|
||||
|
||||
/**
|
||||
* px4::spin() will enter a loop, pumping callbacks. With this version, all
|
||||
|
|
|
@ -50,8 +50,9 @@ class NodeHandle : private ros::NodeHandle
|
|||
public:
|
||||
template<class M>
|
||||
Subscriber* subscribe(const char *topic, void(*fp)(M)) {
|
||||
ros::NodeHandle::subscribe("rc_channels", 1000, fp);
|
||||
return new Subscriber();
|
||||
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, 1000, fp);
|
||||
//XXX create list here, for ros and nuttx
|
||||
return new Subscriber(ros_sub);
|
||||
}
|
||||
};
|
||||
#else
|
||||
|
|
|
@ -47,8 +47,11 @@ namespace px4
|
|||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||
class Subscriber
|
||||
{
|
||||
private:
|
||||
ros::Subscriber _ros_sub;
|
||||
public:
|
||||
Subscriber() {};
|
||||
Subscriber(ros::Subscriber ros_sub) : _ros_sub(ros_sub)
|
||||
{}
|
||||
~Subscriber() {};
|
||||
};
|
||||
#else
|
||||
|
|
Loading…
Reference in New Issue