mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
create list of subscribers
This commit is contained in:
parent
1826fa5d39
commit
e2f846ee2f
@ -74,7 +74,7 @@ int main(int argc, char **argv)
|
||||
* is the number of messages that will be buffered up before beginning to throw
|
||||
* away the oldest ones.
|
||||
*/
|
||||
px4::Subscriber* sub = n.subscribe("rc_channels", rc_channels_callback);
|
||||
px4::Subscriber sub = n.subscribe("rc_channels", rc_channels_callback);
|
||||
PX4_INFO("subscribed");
|
||||
|
||||
/**
|
||||
|
||||
@ -38,6 +38,7 @@
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
#include <cstddef>
|
||||
|
||||
template<class T>
|
||||
class __EXPORT ListNode
|
||||
|
||||
@ -40,6 +40,7 @@
|
||||
#include <px4_subscriber.h>
|
||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||
#include "ros/ros.h"
|
||||
#include <list>
|
||||
#endif
|
||||
|
||||
namespace px4
|
||||
@ -48,12 +49,21 @@ namespace px4
|
||||
class NodeHandle : private ros::NodeHandle
|
||||
{
|
||||
public:
|
||||
NodeHandle () :
|
||||
ros::NodeHandle(),
|
||||
_subs()
|
||||
{}
|
||||
|
||||
template<class M>
|
||||
Subscriber* subscribe(const char *topic, void(*fp)(M)) {
|
||||
Subscriber subscribe(const char *topic, void(*fp)(M)) {
|
||||
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, 1000, fp);
|
||||
//XXX create list here, for ros and nuttx
|
||||
return new Subscriber(ros_sub);
|
||||
Subscriber sub(ros_sub);
|
||||
_subs.push_back(sub);
|
||||
return sub;
|
||||
}
|
||||
private:
|
||||
std::list<Subscriber> _subs;
|
||||
};
|
||||
#else
|
||||
class NodeHandle
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user