mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 11:59:17 +08:00
add base class and template subscriber class as well to improve interface to get last msg value
This commit is contained in:
@@ -78,5 +78,5 @@ SubscriberExample::SubscriberExample() :
|
|||||||
void SubscriberExample::rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg) {
|
void SubscriberExample::rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg) {
|
||||||
PX4_INFO("Subscriber callback: [%llu], value of _sub_rc_chan: [%llu]",
|
PX4_INFO("Subscriber callback: [%llu], value of _sub_rc_chan: [%llu]",
|
||||||
msg.timestamp_last_valid,
|
msg.timestamp_last_valid,
|
||||||
((PX4_SUBSCRIBER_T(rc_channels) *)_sub_rc_chan)->get_msg().timestamp_last_valid);
|
_sub_rc_chan->get_msg().timestamp_last_valid);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -54,7 +54,7 @@ protected:
|
|||||||
int32_t _interval;
|
int32_t _interval;
|
||||||
px4_param_t _p_test_float;
|
px4_param_t _p_test_float;
|
||||||
float _test_float;
|
float _test_float;
|
||||||
px4::Subscriber * _sub_rc_chan;
|
px4::PX4_SUBSCRIBER(rc_channels) * _sub_rc_chan;
|
||||||
|
|
||||||
void rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg);
|
void rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg);
|
||||||
|
|
||||||
|
|||||||
@@ -93,9 +93,6 @@ static inline px4_param_t PX4_ROS_PARAM_SET(const char *name, float value)
|
|||||||
/* Get value of parameter */
|
/* Get value of parameter */
|
||||||
#define PX4_PARAM_GET(_handle, _destpt) ros::param::get(_handle, *_destpt)
|
#define PX4_PARAM_GET(_handle, _destpt) ros::param::get(_handle, *_destpt)
|
||||||
|
|
||||||
/* Get a subscriber class type based on the topic name */
|
|
||||||
#define PX4_SUBSCRIBER_T(_name) SubscriberROS<PX4_TOPIC_T(_name)>
|
|
||||||
|
|
||||||
#else
|
#else
|
||||||
/*
|
/*
|
||||||
* Building for NuttX
|
* Building for NuttX
|
||||||
@@ -134,9 +131,6 @@ typedef param_t px4_param_t;
|
|||||||
/* Get value of parameter */
|
/* Get value of parameter */
|
||||||
#define PX4_PARAM_GET(_handle, _destpt) param_get(_handle, _destpt)
|
#define PX4_PARAM_GET(_handle, _destpt) param_get(_handle, _destpt)
|
||||||
|
|
||||||
/* Get a subscriber class type based on the topic name */
|
|
||||||
#define PX4_SUBSCRIBER_T(_name) SubscriberUORB<PX4_TOPIC_T(_name)>
|
|
||||||
|
|
||||||
/* XXX this is a hack to resolve conflicts with NuttX headers */
|
/* XXX this is a hack to resolve conflicts with NuttX headers */
|
||||||
#define isspace(c) \
|
#define isspace(c) \
|
||||||
((c) == ' ' || (c) == '\t' || (c) == '\n' || \
|
((c) == ' ' || (c) == '\t' || (c) == '\n' || \
|
||||||
@@ -150,6 +144,9 @@ typedef param_t px4_param_t;
|
|||||||
#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, PX4_SUBSCRIBE_NOCB)(__VA_ARGS__)
|
#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 */
|
/* 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))
|
||||||
|
|
||||||
|
|||||||
@@ -77,13 +77,13 @@ public:
|
|||||||
* @param fb Callback, executed on receiving a new message
|
* @param fb Callback, executed on receiving a new message
|
||||||
*/
|
*/
|
||||||
template<typename M>
|
template<typename M>
|
||||||
Subscriber *subscribe(const char *topic, void(*fp)(const M&))
|
Subscriber<M> *subscribe(const char *topic, void(*fp)(const M&))
|
||||||
{
|
{
|
||||||
Subscriber *sub = new SubscriberROS<M>(std::bind(fp, std::placeholders::_1));
|
SubscriberBase *sub = new SubscriberROS<M>(std::bind(fp, std::placeholders::_1));
|
||||||
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS<M>::callback, (SubscriberROS<M>*)sub);
|
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS<M>::callback, (SubscriberROS<M>*)sub);
|
||||||
((SubscriberROS<M>*)sub)->set_ros_sub(ros_sub);
|
((SubscriberROS<M>*)sub)->set_ros_sub(ros_sub);
|
||||||
_subs.push_back(sub);
|
_subs.push_back(sub);
|
||||||
return sub;
|
return (Subscriber<M> *)sub;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -92,13 +92,13 @@ public:
|
|||||||
* @param fb Callback, executed on receiving a new message
|
* @param fb Callback, executed on receiving a new message
|
||||||
*/
|
*/
|
||||||
template<typename M, typename T>
|
template<typename M, typename T>
|
||||||
Subscriber *subscribe(const char *topic, void(T::*fp)(const M&), T *obj)
|
Subscriber<M> *subscribe(const char *topic, void(T::*fp)(const M&), T *obj)
|
||||||
{
|
{
|
||||||
Subscriber *sub = new SubscriberROS<M>(std::bind(fp, obj, std::placeholders::_1));
|
SubscriberBase *sub = new SubscriberROS<M>(std::bind(fp, obj, std::placeholders::_1));
|
||||||
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS<M>::callback, (SubscriberROS<M>*)sub);
|
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS<M>::callback, (SubscriberROS<M>*)sub);
|
||||||
((SubscriberROS<M>*)sub)->set_ros_sub(ros_sub);
|
((SubscriberROS<M>*)sub)->set_ros_sub(ros_sub);
|
||||||
_subs.push_back(sub);
|
_subs.push_back(sub);
|
||||||
return sub;
|
return (Subscriber<M> *)sub;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -106,13 +106,13 @@ public:
|
|||||||
* @param topic Name of the topic
|
* @param topic Name of the topic
|
||||||
*/
|
*/
|
||||||
template<typename M>
|
template<typename M>
|
||||||
Subscriber *subscribe(const char *topic)
|
Subscriber<M> *subscribe(const char *topic)
|
||||||
{
|
{
|
||||||
Subscriber *sub = new SubscriberROS<M>();
|
SubscriberBase *sub = new SubscriberROS<M>();
|
||||||
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS<M>::callback, (SubscriberROS<M>*)sub);
|
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS<M>::callback, (SubscriberROS<M>*)sub);
|
||||||
((SubscriberROS<M>*)sub)->set_ros_sub(ros_sub);
|
((SubscriberROS<M>*)sub)->set_ros_sub(ros_sub);
|
||||||
_subs.push_back(sub);
|
_subs.push_back(sub);
|
||||||
return sub;
|
return (Subscriber<M> *)sub;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -141,10 +141,10 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
static const uint32_t kQueueSizeDefault = 1000; /**< Size of queue for ROS */
|
static const uint32_t kQueueSizeDefault = 1000; /**< Size of queue for ROS */
|
||||||
std::list<Subscriber *> _subs; /**< Subcriptions of node */
|
std::list<SubscriberBase *> _subs; /**< Subcriptions of node */
|
||||||
std::list<Publisher *> _pubs; /**< Publications of node */
|
std::list<PublisherBase *> _pubs; /**< Publications of node */
|
||||||
};
|
};
|
||||||
#else
|
#else //Building for NuttX
|
||||||
class __EXPORT NodeHandle
|
class __EXPORT NodeHandle
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@@ -164,7 +164,7 @@ public:
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
template<typename M>
|
template<typename M>
|
||||||
Subscriber *subscribe(const struct orb_metadata *meta,
|
Subscriber<M> *subscribe(const struct orb_metadata *meta,
|
||||||
std::function<void(const M &)> callback,
|
std::function<void(const M &)> callback,
|
||||||
unsigned interval)
|
unsigned interval)
|
||||||
{
|
{
|
||||||
@@ -175,7 +175,7 @@ public:
|
|||||||
_sub_min_interval = sub_px4;
|
_sub_min_interval = sub_px4;
|
||||||
}
|
}
|
||||||
|
|
||||||
return (Subscriber *)sub_px4;
|
return (Subscriber<M> *)sub_px4;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|||||||
@@ -48,15 +48,30 @@
|
|||||||
|
|
||||||
namespace px4
|
namespace px4
|
||||||
{
|
{
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Untemplated publisher base class
|
||||||
|
* */
|
||||||
|
class PublisherBase
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
PublisherBase() {};
|
||||||
|
~PublisherBase() {};
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||||
class Publisher
|
class Publisher :
|
||||||
|
public PublisherBase
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
* Construct Publisher by providing a ros::Publisher
|
* Construct Publisher by providing a ros::Publisher
|
||||||
* @param ros_pub the ros publisher which will be used to perform the publications
|
* @param ros_pub the ros publisher which will be used to perform the publications
|
||||||
*/
|
*/
|
||||||
Publisher(ros::Publisher ros_pub) : _ros_pub(ros_pub)
|
Publisher(ros::Publisher ros_pub) :
|
||||||
|
PublisherBase(),
|
||||||
|
_ros_pub(ros_pub)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
~Publisher() {};
|
~Publisher() {};
|
||||||
@@ -71,7 +86,8 @@ private:
|
|||||||
};
|
};
|
||||||
#else
|
#else
|
||||||
class Publisher :
|
class Publisher :
|
||||||
public uORB::PublicationNode
|
public uORB::PublicationNode,
|
||||||
|
public PublisherBase
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
@@ -81,7 +97,8 @@ public:
|
|||||||
*/
|
*/
|
||||||
Publisher(const struct orb_metadata *meta,
|
Publisher(const struct orb_metadata *meta,
|
||||||
List<uORB::PublicationNode *> *list) :
|
List<uORB::PublicationNode *> *list) :
|
||||||
uORB::PublicationNode(meta, list)
|
uORB::PublicationNode(meta, list),
|
||||||
|
PublisherBase()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
~Publisher() {};
|
~Publisher() {};
|
||||||
|
|||||||
@@ -50,14 +50,36 @@
|
|||||||
|
|
||||||
namespace px4
|
namespace px4
|
||||||
{
|
{
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Untemplated subscriber base class
|
||||||
|
* */
|
||||||
|
class SubscriberBase
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
SubscriberBase() {};
|
||||||
|
~SubscriberBase() {};
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Subscriber class which is used by nodehandle
|
* Subscriber class which is used by nodehandle
|
||||||
*/
|
*/
|
||||||
class Subscriber
|
template<typename M>
|
||||||
|
class Subscriber :
|
||||||
|
public SubscriberBase
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
Subscriber() {};
|
Subscriber() :
|
||||||
|
SubscriberBase()
|
||||||
|
{};
|
||||||
~Subscriber() {};
|
~Subscriber() {};
|
||||||
|
|
||||||
|
/* Accessors*/
|
||||||
|
/**
|
||||||
|
* Get the last message value
|
||||||
|
*/
|
||||||
|
virtual const M& get_msg() = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||||
@@ -66,7 +88,7 @@ public:
|
|||||||
*/
|
*/
|
||||||
template<typename M>
|
template<typename M>
|
||||||
class SubscriberROS :
|
class SubscriberROS :
|
||||||
public Subscriber
|
public Subscriber<M>
|
||||||
{
|
{
|
||||||
friend class NodeHandle;
|
friend class NodeHandle;
|
||||||
|
|
||||||
@@ -75,7 +97,7 @@ public:
|
|||||||
* Construct Subscriber by providing a callback function
|
* Construct Subscriber by providing a callback function
|
||||||
*/
|
*/
|
||||||
SubscriberROS(std::function<void(const M &)> cbf) :
|
SubscriberROS(std::function<void(const M &)> cbf) :
|
||||||
Subscriber(),
|
Subscriber<M>(),
|
||||||
_ros_sub(),
|
_ros_sub(),
|
||||||
_cbf(cbf),
|
_cbf(cbf),
|
||||||
_msg_current()
|
_msg_current()
|
||||||
@@ -85,7 +107,7 @@ public:
|
|||||||
* Construct Subscriber without a callback function
|
* Construct Subscriber without a callback function
|
||||||
*/
|
*/
|
||||||
SubscriberROS() :
|
SubscriberROS() :
|
||||||
Subscriber(),
|
Subscriber<M>(),
|
||||||
_ros_sub(),
|
_ros_sub(),
|
||||||
_cbf(NULL),
|
_cbf(NULL),
|
||||||
_msg_current()
|
_msg_current()
|
||||||
@@ -128,14 +150,14 @@ protected:
|
|||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#else
|
#else // Building for NuttX
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Subscriber class that is templated with the uorb subscription message type
|
* Subscriber class that is templated with the uorb subscription message type
|
||||||
*/
|
*/
|
||||||
template<typename M>
|
template<typename M>
|
||||||
class SubscriberUORB :
|
class SubscriberUORB :
|
||||||
public Subscriber,
|
public Subscriber<M>,
|
||||||
public uORB::Subscription<M>
|
public uORB::Subscription<M>
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@@ -150,7 +172,7 @@ public:
|
|||||||
unsigned interval,
|
unsigned interval,
|
||||||
std::function<void(const M &)> callback,
|
std::function<void(const M &)> callback,
|
||||||
List<uORB::SubscriptionNode *> *list) :
|
List<uORB::SubscriptionNode *> *list) :
|
||||||
Subscriber(),
|
Subscriber<M>(),
|
||||||
uORB::Subscription<M>(meta, interval, list),
|
uORB::Subscription<M>(meta, interval, list),
|
||||||
_callback(callback)
|
_callback(callback)
|
||||||
//XXX store callback
|
//XXX store callback
|
||||||
|
|||||||
Reference in New Issue
Block a user