aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/px4_defines.h
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-03 14:43:03 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-03 14:43:03 +0100
commit1c79f0cef1f21cff7935ddd7caf048fd96991eea (patch)
tree21eb9fddf2ac136e8168b4e03a076c3e1e2ebb2a /src/platforms/px4_defines.h
parent6a99b04fb74f6da3faea54c93d234a9b57d7bd0e (diff)
downloadpx4-firmware-1c79f0cef1f21cff7935ddd7caf048fd96991eea.tar.gz
px4-firmware-1c79f0cef1f21cff7935ddd7caf048fd96991eea.tar.bz2
px4-firmware-1c79f0cef1f21cff7935ddd7caf048fd96991eea.zip
improve param wrapper for ros, prepare for px4
Diffstat (limited to 'src/platforms/px4_defines.h')
-rw-r--r--src/platforms/px4_defines.h17
1 files changed, 15 insertions, 2 deletions
diff --git a/src/platforms/px4_defines.h b/src/platforms/px4_defines.h
index 2d9051aae..a10df858a 100644
--- a/src/platforms/px4_defines.h
+++ b/src/platforms/px4_defines.h
@@ -51,8 +51,18 @@
#define PX4_TOPIC_T(_name) _name
#define PX4_SUBSCRIBE_CBMETH(_nodehandle, _name, _cbf, _obj, _interval) _nodehandle.subscribe(PX4_TOPIC(_name), &_cbf, &_obj);
#define PX4_SUBSCRIBE_CBFUNC(_nodehandle, _name, _cbf, _interval) _nodehandle.subscribe(PX4_TOPIC(_name), _cbf);
-#define PX4_PARAM_INIT(_name, _default) ros::param::set(_name, _default);
-#define PX4_PARAM_GET(_name, _destpt) ros::param::get(_name, *_destpt)
+typedef const std::string px4_param_t;
+static inline px4_param_t ROS_PARAM_SET(const std::string &name, int32_t value) {
+ ros::param::set(name, value);
+ return (px4_param_t)name;
+};
+static inline px4_param_t ROS_PARAM_SET(const std::string &name, float value) {
+ ros::param::set(name, value);
+ return (px4_param_t)name;
+};
+#define PX4_PARAM_INIT(_name, _default) ROS_PARAM_SET(_name, _default)
+// #define PX4_PARAM_INIT(_name, _default) ros::param::set(_name, _default)
+#define PX4_PARAM_GET(_handle, _destpt) ros::param::get(_handle, *_destpt)
#else
/*
* Building for NuttX
@@ -65,6 +75,9 @@
#define PX4_TOPIC_T(_name) _name##_s
#define PX4_SUBSCRIBE_CBMETH(_nodehandle, _name, _cbf, _obj, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), std::bind(&_cbf, _obj, std::placeholders::_1), _interval)
#define PX4_SUBSCRIBE_CBFUNC(_nodehandle, _name, _cbf, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), std::bind(&_cbf, std::placeholders::_1), _interval)
+typedef param_t px4_param_t
+#define PX4_PARAM_INIT(_name, _default) param_find(_name)
+#define PX4_PARAM_GET(_handle, _destpt) param_get(_handle, _destpt)
#endif
/* Overload the PX4_SUBSCRIBE macro to suppport methods and pure functions as callback */