forked from Archive/PX4-Autopilot
hack to define isspace in px4_defines, add macro for subscription without callback
This commit is contained in:
parent
712e5797eb
commit
9ed57211cc
|
@ -96,6 +96,9 @@ static inline px4_param_t PX4_ROS_PARAM_SET(const char *name, float value)
|
||||||
* Building for NuttX
|
* Building for NuttX
|
||||||
*/
|
*/
|
||||||
#include <platforms/px4_includes.h>
|
#include <platforms/px4_includes.h>
|
||||||
|
#ifdef __cplusplus
|
||||||
|
#include <functional>
|
||||||
|
#endif
|
||||||
/* Main entry point */
|
/* Main entry point */
|
||||||
#define PX4_MAIN_FUNCTION(_prefix) extern "C" __EXPORT int _prefix##_main(int argc, char *argv[])
|
#define PX4_MAIN_FUNCTION(_prefix) extern "C" __EXPORT int _prefix##_main(int argc, char *argv[])
|
||||||
|
|
||||||
|
@ -113,6 +116,7 @@ static inline px4_param_t PX4_ROS_PARAM_SET(const char *name, float value)
|
||||||
#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_CBMETH(_nodehandle, _name, _cbf, _obj, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), std::bind(&_cbf, _obj, std::placeholders::_1), _interval)
|
||||||
/* Subscribe and providing a function as callback (do not use directly, use PX4_SUBSCRIBE instead) */
|
/* 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)
|
#define PX4_SUBSCRIBE_CBFUNC(_nodehandle, _name, _cbf, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), std::bind(&_cbf, std::placeholders::_1), _interval)
|
||||||
|
#define PX4_SUBSCRIBE_NOCB(_nodehandle, _name, _interval) _nodehandle.subscribe<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name), nullptr, _interval)
|
||||||
|
|
||||||
/* Parameter handle datatype */
|
/* Parameter handle datatype */
|
||||||
#include <systemlib/param/param.h>
|
#include <systemlib/param/param.h>
|
||||||
|
@ -126,10 +130,10 @@ typedef param_t px4_param_t;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Shortcut for subscribing to topics
|
/* Shortcut for subscribing to topics
|
||||||
* Overload the PX4_SUBSCRIBE macro to suppport methods and pure functions as callback
|
* 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_GET_SUBSCRIBE(_1, _2, _3, _4, _5, NAME, ...) NAME
|
||||||
#define PX4_SUBSCRIBE(...) PX4_GET_SUBSCRIBE(__VA_ARGS__, PX4_SUBSCRIBE_CBMETH, PX4_SUBSCRIBE_CBFUNC)(__VA_ARGS__)
|
#define PX4_SUBSCRIBE(...) PX4_GET_SUBSCRIBE(__VA_ARGS__, PX4_SUBSCRIBE_CBMETH, PX4_SUBSCRIBE_CBFUNC, PX4_SUBSCRIBE_NOCB)(__VA_ARGS__)
|
||||||
|
|
||||||
/* shortcut for advertising topics */
|
/* shortcut for advertising topics */
|
||||||
#define PX4_ADVERTISE(_nodehandle, _name) _nodehandle.advertise<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name))
|
#define PX4_ADVERTISE(_nodehandle, _name) _nodehandle.advertise<PX4_TOPIC_T(_name)>(PX4_TOPIC(_name))
|
||||||
|
@ -139,3 +143,7 @@ typedef param_t px4_param_t;
|
||||||
|
|
||||||
/* wrapper for rotation matrices stored in arrays */
|
/* wrapper for rotation matrices stored in arrays */
|
||||||
#define PX4_R(_array, _x, _y) PX4_ARRAY2D(_array, 3, _x, _y)
|
#define PX4_R(_array, _x, _y) PX4_ARRAY2D(_array, 3, _x, _y)
|
||||||
|
|
||||||
|
#define isspace(c) \
|
||||||
|
((c) == ' ' || (c) == '\t' || (c) == '\n' || \
|
||||||
|
(c) == '\r' || (c) == '\f' || c== '\v')
|
||||||
|
|
Loading…
Reference in New Issue