forked from Archive/PX4-Autopilot
WIP, towards more px4 compatibility, first macros
This commit is contained in:
parent
c167df9038
commit
55cf2fc61c
|
@ -57,7 +57,7 @@ int main(int argc, char **argv)
|
||||||
* than we can send them, the number here specifies how many messages to
|
* than we can send them, the number here specifies how many messages to
|
||||||
* buffer up before throwing some away.
|
* buffer up before throwing some away.
|
||||||
*/
|
*/
|
||||||
px4::Publisher rc_channels_pub = n.advertise<px4::rc_channels>("rc_channels");
|
px4::Publisher rc_channels_pub = n.advertise<px4::rc_channels>(PX4_TOPIC(rc_channels));
|
||||||
|
|
||||||
|
|
||||||
px4::Rate loop_rate(10);
|
px4::Rate loop_rate(10);
|
||||||
|
|
|
@ -74,7 +74,7 @@ int main(int argc, char **argv)
|
||||||
* is the number of messages that will be buffered up before beginning to throw
|
* is the number of messages that will be buffered up before beginning to throw
|
||||||
* away the oldest ones.
|
* away the oldest ones.
|
||||||
*/
|
*/
|
||||||
px4::Subscriber sub = n.subscribe("rc_channels", rc_channels_callback);
|
px4::Subscriber sub = n.subscribe(PX4_TOPIC(rc_channels), rc_channels_callback);
|
||||||
PX4_INFO("subscribed");
|
PX4_INFO("subscribed");
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -46,14 +46,19 @@
|
||||||
* Building for running within the ROS environment
|
* Building for running within the ROS environment
|
||||||
*/
|
*/
|
||||||
#include "ros/ros.h"
|
#include "ros/ros.h"
|
||||||
|
|
||||||
#define PX4_WARN ROS_WARN
|
#define PX4_WARN ROS_WARN
|
||||||
#define PX4_INFO ROS_INFO
|
#define PX4_INFO ROS_INFO
|
||||||
|
#define PX4_TOPIC(name) #name
|
||||||
#else
|
#else
|
||||||
/*
|
/*
|
||||||
* Building for NuttX
|
* Building for NuttX
|
||||||
*/
|
*/
|
||||||
|
#include <uORB/uORB.h>
|
||||||
|
|
||||||
#define PX4_WARN warnx
|
#define PX4_WARN warnx
|
||||||
#define PX4_INFO warnx
|
#define PX4_INFO warnx
|
||||||
|
#define PX4_TOPIC(name) ORB_ID(name)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "../platforms/px4_defines.h"
|
#include "../platforms/px4_defines.h"
|
||||||
|
|
|
@ -78,5 +78,6 @@ template class __EXPORT Publication<vehicle_rates_setpoint_s>;
|
||||||
template class __EXPORT Publication<actuator_outputs_s>;
|
template class __EXPORT Publication<actuator_outputs_s>;
|
||||||
template class __EXPORT Publication<encoders_s>;
|
template class __EXPORT Publication<encoders_s>;
|
||||||
template class __EXPORT Publication<tecs_status_s>;
|
template class __EXPORT Publication<tecs_status_s>;
|
||||||
|
template class __EXPORT Publication<rc_channels_s>;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -101,5 +101,6 @@ template class __EXPORT Subscription<vehicle_local_position_setpoint_s>;
|
||||||
template class __EXPORT Subscription<vehicle_local_position_s>;
|
template class __EXPORT Subscription<vehicle_local_position_s>;
|
||||||
template class __EXPORT Subscription<vehicle_attitude_setpoint_s>;
|
template class __EXPORT Subscription<vehicle_attitude_setpoint_s>;
|
||||||
template class __EXPORT Subscription<vehicle_rates_setpoint_s>;
|
template class __EXPORT Subscription<vehicle_rates_setpoint_s>;
|
||||||
|
template class __EXPORT Subscription<rc_channels_s>;
|
||||||
|
|
||||||
} // namespace uORB
|
} // namespace uORB
|
||||||
|
|
|
@ -49,21 +49,26 @@
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#else
|
#else
|
||||||
/* includes when building for NuttX */
|
/* includes when building for NuttX */
|
||||||
|
#include <containers/List.hpp>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
namespace px4
|
namespace px4
|
||||||
{
|
{
|
||||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||||
class NodeHandle : private ros::NodeHandle
|
class NodeHandle :
|
||||||
|
private ros::NodeHandle
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
NodeHandle () :
|
NodeHandle() :
|
||||||
ros::NodeHandle(),
|
ros::NodeHandle(),
|
||||||
_subs(),
|
_subs(),
|
||||||
_pubs()
|
_pubs()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
~NodeHandle() {
|
||||||
|
//XXX empty lists
|
||||||
|
};
|
||||||
|
|
||||||
template<typename M>
|
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);
|
ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, fp);
|
||||||
|
@ -87,6 +92,30 @@ private:
|
||||||
#else
|
#else
|
||||||
class NodeHandle
|
class NodeHandle
|
||||||
{
|
{
|
||||||
|
public:
|
||||||
|
NodeHandle() :
|
||||||
|
_subs(),
|
||||||
|
_pubs()
|
||||||
|
{}
|
||||||
|
|
||||||
|
~NodeHandle() {};
|
||||||
|
|
||||||
|
template<typename M>
|
||||||
|
Subscriber subscribe(const char *topic, void(*fp)(M)) {
|
||||||
|
Subscriber sub(&_subs, , interval);
|
||||||
|
return sub;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename M>
|
||||||
|
Publisher advertise(const char *topic) {
|
||||||
|
Publisher pub(ros_pub);
|
||||||
|
_pubs.push_back(pub);
|
||||||
|
return pub;
|
||||||
|
}
|
||||||
|
private:
|
||||||
|
List<Subscriber> _subs;
|
||||||
|
List<Publisher> _pubs;
|
||||||
|
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -38,7 +38,11 @@
|
||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||||
|
/* includes when building for ros */
|
||||||
#include "ros/ros.h"
|
#include "ros/ros.h"
|
||||||
|
#else
|
||||||
|
/* includes when building for NuttX */
|
||||||
|
#include <uORB/Publication.hpp>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
namespace px4
|
namespace px4
|
||||||
|
@ -56,7 +60,15 @@ private:
|
||||||
ros::Publisher _ros_pub;
|
ros::Publisher _ros_pub;
|
||||||
};
|
};
|
||||||
#else
|
#else
|
||||||
class Publisher
|
template<typename M>
|
||||||
|
class Publisher :
|
||||||
|
public uORB::Publication<M>
|
||||||
|
public:
|
||||||
|
Publisher(List<SubscriptionBase *> * list,
|
||||||
|
const struct orb_metadata *meta, unsigned interval) :
|
||||||
|
uORB::Publication(list, meta)
|
||||||
|
{}
|
||||||
|
~Publisher() {};
|
||||||
{
|
{
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -38,7 +38,11 @@
|
||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
|
||||||
|
/* includes when building for ros */
|
||||||
#include "ros/ros.h"
|
#include "ros/ros.h"
|
||||||
|
#else
|
||||||
|
/* includes when building for NuttX */
|
||||||
|
#include <uORB/Subscription.hpp>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
namespace px4
|
namespace px4
|
||||||
|
@ -48,14 +52,23 @@ namespace px4
|
||||||
class Subscriber
|
class Subscriber
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
Subscriber(ros::Subscriber ros_sub) : _ros_sub(ros_sub)
|
Subscriber(ros::Subscriber ros_sub) :
|
||||||
|
_ros_sub(ros_sub)
|
||||||
{}
|
{}
|
||||||
~Subscriber() {};
|
~Subscriber() {};
|
||||||
private:
|
private:
|
||||||
ros::Subscriber _ros_sub;
|
ros::Subscriber _ros_sub;
|
||||||
};
|
};
|
||||||
#else
|
#else
|
||||||
class Subscriber
|
template<typename M>
|
||||||
|
class Subscriber :
|
||||||
|
public uORB::Subscription<M>
|
||||||
|
public:
|
||||||
|
Subscriber(List<SubscriptionBase *> * list,
|
||||||
|
const struct orb_metadata *meta, unsigned interval) :
|
||||||
|
uORB::Subsciption(list, meta, interval)
|
||||||
|
{}
|
||||||
|
~Subscriber() {};
|
||||||
{
|
{
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue