Browse Source

wip, working on the nuttx wrapper

sbg
Thomas Gubler 10 years ago
parent
commit
e7c1e5b1ff
  1. 13
      src/examples/publisher/publisher.cpp
  2. 11
      src/examples/subscriber/subscriber.cpp
  3. 10
      src/include/px4.h
  4. 1
      src/modules/uORB/Publication.cpp
  5. 10
      src/modules/uORB/Publication.hpp
  6. 1
      src/modules/uORB/Subscription.cpp
  7. 3
      src/platforms/nuttx/module.mk
  8. 2
      src/platforms/nuttx/px4_nodehandle.cpp
  9. 8
      src/platforms/nuttx/px4_nuttx_impl.cpp
  10. 1
      src/platforms/nuttx/px4_publisher.cpp
  11. 2
      src/platforms/nuttx/px4_subscriber.cpp
  12. 23
      src/platforms/px4_defines.h
  13. 11
      src/platforms/px4_middleware.h
  14. 23
      src/platforms/px4_nodehandle.h
  15. 21
      src/platforms/px4_publisher.h
  16. 20
      src/platforms/px4_subscriber.h

13
src/examples/publisher/publisher.cpp

@ -26,14 +26,15 @@ @@ -26,14 +26,15 @@
*/
#include <px4.h>
#include <px4/rc_channels.h>
#include <sstream>
using namespace px4;
/**
* This tutorial demonstrates simple sending of messages over the PX4 middleware system.
*/
int main(int argc, char **argv)
// __EXPORT bool task_should_exit;
PX4_MAIN_FUNCTION(publisher)
{
px4::init(argc, argv, "px4_publisher");
@ -57,7 +58,7 @@ int main(int argc, char **argv) @@ -57,7 +58,7 @@ int main(int argc, char **argv)
* than we can send them, the number here specifies how many messages to
* buffer up before throwing some away.
*/
px4::Publisher rc_channels_pub = n.advertise<px4::rc_channels>(PX4_TOPIC(rc_channels));
px4::Publisher * rc_channels_pub = n.advertise<PX4_TOPIC_T(rc_channels)>(PX4_TOPIC(rc_channels));
px4::Rate loop_rate(10);
@ -72,7 +73,7 @@ int main(int argc, char **argv) @@ -72,7 +73,7 @@ int main(int argc, char **argv)
/**
* This is a message object. You stuff it with data, and then publish it.
*/
px4::rc_channels msg;
PX4_TOPIC_T(rc_channels) msg;
msg.timestamp_last_valid = px4::get_time_micros();
PX4_INFO("%lu", msg.timestamp_last_valid);
@ -83,7 +84,7 @@ int main(int argc, char **argv) @@ -83,7 +84,7 @@ int main(int argc, char **argv)
* given as a template parameter to the advertise<>() call, as was done
* in the constructor above.
*/
rc_channels_pub.publish(msg);
rc_channels_pub->publish(msg);
px4::spin_once();

11
src/examples/subscriber/subscriber.cpp

@ -26,19 +26,20 @@ @@ -26,19 +26,20 @@
*/
#include <px4.h>
#include "px4/rc_channels.h"
using namespace px4;
/**
* This tutorial demonstrates simple receipt of messages over the PX4 middleware system.
*/
void rc_channels_callback(const px4::rc_channels::ConstPtr &msg)
void rc_channels_callback(const PX4_TOPIC_T(rc_channels) *msg)
{
PX4_INFO("I heard: [%lu]", msg->timestamp_last_valid);
}
PX4_MAIN_FUNCTION(subscriber)
// __EXPORT bool task_should_exit;
int main(int argc, char **argv)
PX4_MAIN_FUNCTION(subscriber)
{
/**
* The ros::init() function needs to see argc and argv so that it can perform
@ -74,7 +75,7 @@ int main(int argc, char **argv) @@ -74,7 +75,7 @@ int main(int argc, char **argv)
* is the number of messages that will be buffered up before beginning to throw
* away the oldest ones.
*/
px4::Subscriber sub = n.subscribe(PX4_TOPIC(rc_channels), rc_channels_callback);
n.subscribe(PX4_TOPIC(rc_channels), rc_channels_callback);
PX4_INFO("subscribed");
/**

10
src/include/px4.h

@ -46,19 +46,17 @@ @@ -46,19 +46,17 @@
* Building for running within the ROS environment
*/
#include "ros/ros.h"
#include "px4/rc_channels.h"
#define PX4_WARN ROS_WARN
#define PX4_INFO ROS_INFO
#define PX4_TOPIC(name) #name
#else
/*
* Building for NuttX
*/
#include <nuttx/config.h>
#include <uORB/uORB.h>
#include <uORB/topics/rc_channels.h>
#include <systemlib/err.h>
#define PX4_WARN warnx
#define PX4_INFO warnx
#define PX4_TOPIC(name) ORB_ID(name)
#endif
#include "../platforms/px4_defines.h"

1
src/modules/uORB/Publication.cpp

@ -48,6 +48,7 @@ @@ -48,6 +48,7 @@
#include "topics/actuator_outputs.h"
#include "topics/encoders.h"
#include "topics/tecs_status.h"
#include "topics/rc_channels.h"
namespace uORB {

10
src/modules/uORB/Publication.hpp

@ -59,7 +59,7 @@ public: @@ -59,7 +59,7 @@ public:
* Constructor
*
*
* @param meta The uORB metadata (usually from the ORB_ID()
* @param meta The uORB metadata (usually from the ORB_ID()
* macro) for the topic.
*/
PublicationBase(const struct orb_metadata *meta) :
@ -96,7 +96,7 @@ protected: @@ -96,7 +96,7 @@ protected:
orb_advert_t _handle;
};
/**
/**
* alias class name so it is clear that the base class
* can be used by itself if desired
*/
@ -114,9 +114,9 @@ public: @@ -114,9 +114,9 @@ public:
* Constructor
*
*
* @param meta The uORB metadata (usually from the ORB_ID()
* @param meta The uORB metadata (usually from the ORB_ID()
* macro) for the topic.
* @param list A pointer to a list of subscriptions
* @param list A pointer to a list of subscriptions
* that this should be appended to.
*/
PublicationNode(const struct orb_metadata *meta,
@ -144,7 +144,7 @@ public: @@ -144,7 +144,7 @@ public:
/**
* Constructor
*
* @param meta The uORB metadata (usually from
* @param meta The uORB metadata (usually from
* the ORB_ID() macro) for the topic.
* @param list A list interface for adding to
* list during construction

1
src/modules/uORB/Subscription.cpp

@ -52,6 +52,7 @@ @@ -52,6 +52,7 @@
#include "topics/vehicle_local_position.h"
#include "topics/vehicle_attitude_setpoint.h"
#include "topics/vehicle_rates_setpoint.h"
#include "topics/rc_channels.h"
namespace uORB
{

3
src/platforms/nuttx/module.mk

@ -37,6 +37,7 @@ @@ -37,6 +37,7 @@
SRCS = px4_nuttx_impl.cpp \
px4_publisher.cpp \
px4_subscriber.cpp
px4_subscriber.cpp \
px4_nodehandle.cpp
MAXOPTIMIZATION = -Os

2
src/platforms/nuttx/px4_nodehandle.cpp

@ -36,4 +36,4 @@ @@ -36,4 +36,4 @@
*
* PX4 Middleware Wrapper Nodehandle
*/
#include <px4_nodehandle.h>
#include <platforms/px4_nodehandle.h>

8
src/platforms/nuttx/px4_nuttx_impl.cpp

@ -38,6 +38,7 @@ @@ -38,6 +38,7 @@
*/
#include <px4.h>
#include <drivers/drv_hrt.h>
extern bool task_should_exit;
@ -46,8 +47,7 @@ namespace px4 @@ -46,8 +47,7 @@ namespace px4
void init(int argc, char *argv[], const char *process_name)
{
px4_warn("process: %s", process_name);
return 0;
PX4_WARN("process: %s", process_name);
}
uint64_t get_time_micros()
@ -57,7 +57,9 @@ uint64_t get_time_micros() @@ -57,7 +57,9 @@ uint64_t get_time_micros()
bool ok()
{
return !task_should_exit;
// return !task_should_exit;
//XXX
return true;
}
void spin_once()

1
src/platforms/nuttx/px4_publisher.cpp

@ -36,5 +36,6 @@ @@ -36,5 +36,6 @@
*
* PX4 Middleware Wrapper for Publisher
*/
#include <platforms/px4_publisher.h>

2
src/platforms/nuttx/px4_subscriber.cpp

@ -36,5 +36,5 @@ @@ -36,5 +36,5 @@
*
* PX4 Middleware Wrapper Subscriber
*/
#include <platforms/px4_subscriber.h>

23
src/platforms/px4_defines.h

@ -44,8 +44,25 @@ @@ -44,8 +44,25 @@
* Building for running within the ROS environment
*/
#define __EXPORT
#define PX4_MAIN_FUNCTION(_prefix)
// #define PX4_MAIN_FUNCTION(_prefix)
#define PX4_MAIN_FUNCTION(_prefix) int main(int argc, char **argv)
#define PX4_WARN ROS_WARN
#define PX4_INFO ROS_INFO
#define PX4_TOPIC(name) #name
#define PX4_TOPIC_T(name) name
#else
#include <nuttx/config.h>
#define PX4_MAIN_FUNCTION(_prefix) __EXPORT int _prefix##main(int argc, char **argv)() { return main(argc, argv); }
/*
* Building for NuttX
*/
// #define PX4_MAIN_FUNCTION(_prefix) __EXPORT int _prefix##_main(int argc, char **argv)() { return main(argc, argv); }
// #define PX4_MAIN_FUNCTION(_prefix) extern "C" __EXPORT int _prefix##_main(int argc, char *argv[]) { return main(argc, argv); }
#define PX4_MAIN_FUNCTION(_prefix) extern "C" __EXPORT int _prefix##_main(int argc, char *argv[])
#define PX4_WARN warnx
#define PX4_WARN warnx
#define PX4_INFO warnx
#define PX4_TOPIC(name) ORB_ID(name)
#define PX4_TOPIC_T(name) name##_s
#endif

11
src/platforms/px4_middleware.h

@ -40,19 +40,20 @@ @@ -40,19 +40,20 @@
#pragma once
#include <stdint.h>
#include <unistd.h>
namespace px4
{
void init(int argc, char *argv[], const char *process_name);
__EXPORT void init(int argc, char *argv[], const char *process_name);
uint64_t get_time_micros();
__EXPORT uint64_t get_time_micros();
bool ok();
__EXPORT bool ok();
void spin_once();
__EXPORT void spin_once();
void spin();
__EXPORT void spin();
class Rate
{

23
src/platforms/px4_nodehandle.h

@ -39,8 +39,8 @@ @@ -39,8 +39,8 @@
#pragma once
/* includes for all platforms */
#include <px4_subscriber.h>
#include <px4_publisher.h>
#include "px4_subscriber.h"
#include "px4_publisher.h"
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
/* includes when building for ros */
@ -49,7 +49,6 @@ @@ -49,7 +49,6 @@
#include <inttypes.h>
#else
/* includes when building for NuttX */
#include <containers/List.hpp>
#endif
namespace px4
@ -90,7 +89,7 @@ private: @@ -90,7 +89,7 @@ private:
std::list<Publisher> _pubs;
};
#else
class NodeHandle
class __EXPORT NodeHandle
{
public:
NodeHandle() :
@ -101,20 +100,22 @@ public: @@ -101,20 +100,22 @@ public:
~NodeHandle() {};
template<typename M>
Subscriber subscribe(const char *topic, void(*fp)(M)) {
Subscriber sub(&_subs, , interval);
Subscriber * subscribe(const struct orb_metadata *meta, void(*fp)(M)) {
unsigned interval = 0;//XXX decide how to wrap this, ros equivalent?
//XXX
Subscriber *sub = new Subscriber(meta, interval, fp, &_subs);
return sub;
}
template<typename M>
Publisher advertise(const char *topic) {
Publisher pub(ros_pub);
_pubs.push_back(pub);
Publisher * advertise(const struct orb_metadata *meta) {
//XXX
Publisher * pub = new Publisher(meta, &_pubs);
return pub;
}
private:
List<Subscriber> _subs;
List<Publisher> _pubs;
List<uORB::SubscriptionNode*> _subs;
List<uORB::PublicationNode*> _pubs;
};
#endif

21
src/platforms/px4_publisher.h

@ -43,6 +43,7 @@ @@ -43,6 +43,7 @@
#else
/* includes when building for NuttX */
#include <uORB/Publication.hpp>
#include <containers/List.hpp>
#endif
namespace px4
@ -60,16 +61,24 @@ private: @@ -60,16 +61,24 @@ private:
ros::Publisher _ros_pub;
};
#else
template<typename M>
class Publisher :
public uORB::Publication<M>
public uORB::PublicationNode
{
public:
Publisher(List<SubscriptionBase *> * list,
const struct orb_metadata *meta, unsigned interval) :
uORB::Publication(list, meta)
Publisher(const struct orb_metadata *meta,
List<uORB::PublicationNode *> * list) :
uORB::PublicationNode(meta, list)
{}
~Publisher() {};
{
template<typename M>
int publish(const M &msg) {
uORB::PublicationBase::update((void*)&msg);
return 0;
}
void update() {
//XXX list traversal callback, needed?
} ;
};
#endif
}

20
src/platforms/px4_subscriber.h

@ -43,6 +43,7 @@ @@ -43,6 +43,7 @@
#else
/* includes when building for NuttX */
#include <uORB/Subscription.hpp>
#include <containers/List.hpp>
#endif
namespace px4
@ -60,16 +61,23 @@ private: @@ -60,16 +61,23 @@ private:
ros::Subscriber _ros_sub;
};
#else
template<typename M>
class Subscriber :
public uORB::Subscription<M>
public uORB::SubscriptionNode
{
public:
Subscriber(List<SubscriptionBase *> * list,
const struct orb_metadata *meta, unsigned interval) :
uORB::Subsciption(list, meta, interval)
template<typename M>
Subscriber(const struct orb_metadata *meta,
unsigned interval,
void(*fp)(M),
List<uORB::SubscriptionNode *> * list) :
uORB::SubscriptionNode(meta, interval, list)
//XXX store callback
{}
~Subscriber() {};
{
void update() {
//XXX list traversal callback, needed?
} ;
};
#endif

Loading…
Cancel
Save