aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/px4_nodehandle.h
diff options
context:
space:
mode:
Diffstat (limited to 'src/platforms/px4_nodehandle.h')
-rw-r--r--src/platforms/px4_nodehandle.h18
1 files changed, 17 insertions, 1 deletions
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h
index d278828b7..df198615c 100644
--- a/src/platforms/px4_nodehandle.h
+++ b/src/platforms/px4_nodehandle.h
@@ -36,11 +36,27 @@
*
* PX4 Middleware Wrapper Node Handle
*/
+#pragma once
+#include <px4_subscriber.h>
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
+#include "ros/ros.h"
+#endif
namespace px4
{
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
+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();
+ }
+};
+#else
class NodeHandle
{
-
};
+#endif
}