get rid of lots of multiplatform macros, oh yeah

This commit is contained in:
Thomas Gubler 2015-02-08 17:52:18 +01:00
parent d1e14741cd
commit 347047bafc
1 changed files with 2 additions and 72 deletions

View File

@ -54,6 +54,7 @@
#ifdef __cplusplus
#include "ros/ros.h"
#endif
/* Main entry point */
#define PX4_MAIN_FUNCTION(_prefix) int main(int argc, char **argv)
@ -61,48 +62,8 @@
#define PX4_WARN ROS_WARN
#define PX4_INFO ROS_INFO
/* Topic Handle */
#define PX4_TOPIC(_name) #_name
/* Topic type */
#define PX4_TOPIC_T(_name) px4::_name
/* Subscribe and providing a class method as callback (do not use directly, use PX4_SUBSCRIBE instead) */
#define PX4_SUBSCRIBE_CBMETH(_nodehandle, _name, _cbf, _objptr, _interval) _nodehandle.subscribe(PX4_TOPIC(_name), &_cbf, _objptr);
/* Subscribe and providing a function as callback (do not use directly, use PX4_SUBSCRIBE instead) */
#define PX4_SUBSCRIBE_CBFUNC(_nodehandle, _name, _cbf, _interval) _nodehandle.subscribe(PX4_TOPIC(_name), _cbf);
/* Subscribe without a callback (do not use directly, use PX4_SUBSCRIBE instead) */
#define PX4_SUBSCRIBE_NOCB(_nodehandle, _name, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name));
/* Parameter handle datatype */
typedef const char *px4_param_t;
/* Helper functions to set ROS params, only int and float supported */
static inline px4_param_t PX4_ROS_PARAM_SET(const char *name, int value)
{
if (!ros::param::has(name)) {
ros::param::set(name, value);
}
return (px4_param_t)name;
};
static inline px4_param_t PX4_ROS_PARAM_SET(const char *name, float value)
{
if (!ros::param::has(name)) {
ros::param::set(name, value);
}
return (px4_param_t)name;
};
/* Initialize a param, in case of ROS the parameter is sent to the parameter server here */
#define PX4_PARAM_INIT(_name) PX4_ROS_PARAM_SET(#_name, PX4_PARAM_DEFAULT_VALUE_NAME(_name))
/* Get value of parameter by handle */
#define PX4_PARAM_GET(_handle, _destpt) ros::param::get(_handle, *_destpt)
/* Get value of parameter by name, which is equal to the handle for ros */
#define PX4_PARAM_GET_BYNAME(_name, _destpt) PX4_PARAM_GET(_name, _destpt)
#define PX4_PARAM_GET_BYNAME(_name, _destpt) ros::param::get(_name, *_destpt)
#define OK 0
#define ERROR -1
@ -150,29 +111,10 @@ static inline px4_param_t PX4_ROS_PARAM_SET(const char *name, float value)
#define PX4_WARN warnx
#define PX4_INFO warnx
/* Topic Handle */
#define PX4_TOPIC(_name) ORB_ID(_name)
/* Topic type */
#define PX4_TOPIC_T(_name) _name##_s
/* Subscribe and providing a class method as callback (do not use directly, use PX4_SUBSCRIBE instead) */
#define PX4_SUBSCRIBE_CBMETH(_nodehandle, _name, _cbf, _objptr, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), std::bind(&_cbf, _objptr, std::placeholders::_1), _interval)
/* Subscribe and providing a function as callback (do not use directly, use PX4_SUBSCRIBE instead) */
#define PX4_SUBSCRIBE_CBFUNC(_nodehandle, _name, _cbf, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), std::bind(&_cbf, std::placeholders::_1), _interval)
/* Subscribe without a callback (do not use directly, use PX4_SUBSCRIBE instead) */
#define PX4_SUBSCRIBE_NOCB(_nodehandle, _name, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), _interval)
/* Parameter handle datatype */
#include <systemlib/param/param.h>
typedef param_t px4_param_t;
/* Initialize a param, get param handle */
#define PX4_PARAM_INIT(_name) param_find(#_name)
/* Get value of parameter by handle */
#define PX4_PARAM_GET(_handle, _destpt) param_get(_handle, _destpt)
/* Get value of parameter by name */
#define PX4_PARAM_GET_BYNAME(_name, _destpt) param_get(param_find(_name), _destpt)
@ -187,18 +129,6 @@ typedef param_t px4_param_t;
/* Defines for all platforms */
/* Shortcut for subscribing to topics
* Overload the PX4_SUBSCRIBE macro to suppport methods, pure functions as callback and no callback at all
*/
#define PX4_GET_SUBSCRIBE(_1, _2, _3, _4, _5, NAME, ...) NAME
#define PX4_SUBSCRIBE(...) PX4_GET_SUBSCRIBE(__VA_ARGS__, PX4_SUBSCRIBE_CBMETH, PX4_SUBSCRIBE_CBFUNC, PX4_SUBSCRIBE_NOCB)(__VA_ARGS__)
/* Get a subscriber class type based on the topic name */
#define PX4_SUBSCRIBER(_name) Subscriber<PX4_TOPIC_T(_name)>
/* shortcut for advertising topics */
#define PX4_ADVERTISE(_nodehandle, _name) _nodehandle.advertise<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name))
/* wrapper for 2d matrices */
#define PX4_ARRAY2D(_array, _ncols, _x, _y) (_array[_x * _ncols + _y])