forked from Archive/PX4-Autopilot
fix ros compile errors
This commit is contained in:
parent
0474908e1c
commit
818a49b5a8
|
@ -32,9 +32,9 @@ using namespace px4;
|
|||
/**
|
||||
* This tutorial demonstrates simple receipt of messages over the PX4 middleware system.
|
||||
*/
|
||||
void rc_channels_callback(const PX4_TOPIC_T(rc_channels) *msg)
|
||||
void rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg)
|
||||
{
|
||||
PX4_INFO("I heard: [%lu]", msg->timestamp_last_valid);
|
||||
PX4_INFO("I heard: [%lu]", msg.timestamp_last_valid);
|
||||
}
|
||||
namespace px4
|
||||
{
|
||||
|
|
|
@ -69,24 +69,24 @@ public:
|
|||
};
|
||||
|
||||
template<typename M>
|
||||
Subscriber subscribe(const char *topic, void(*fp)(M)) {
|
||||
Subscriber * subscribe(const char *topic, void(*fp)(M)) {
|
||||
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, fp);
|
||||
Subscriber sub(ros_sub);
|
||||
Subscriber * sub = new Subscriber(ros_sub);
|
||||
_subs.push_back(sub);
|
||||
return sub;
|
||||
}
|
||||
|
||||
template<typename M>
|
||||
Publisher advertise(const char *topic) {
|
||||
Publisher * advertise(const char *topic) {
|
||||
ros::Publisher ros_pub = ros::NodeHandle::advertise<M>(topic, kQueueSizeDefault);
|
||||
Publisher pub(ros_pub);
|
||||
Publisher *pub = new Publisher(ros_pub);
|
||||
_pubs.push_back(pub);
|
||||
return pub;
|
||||
}
|
||||
private:
|
||||
static const uint32_t kQueueSizeDefault = 1000;
|
||||
std::list<Subscriber> _subs;
|
||||
std::list<Publisher> _pubs;
|
||||
std::list<Subscriber*> _subs;
|
||||
std::list<Publisher*> _pubs;
|
||||
};
|
||||
#else
|
||||
class __EXPORT NodeHandle
|
||||
|
|
Loading…
Reference in New Issue