multiplatform: better publisher base class

This commit is contained in:
Thomas Gubler 2015-01-22 09:30:43 +01:00
parent 2af44f5995
commit 8c4fce3654
4 changed files with 59 additions and 42 deletions

View File

@ -125,26 +125,26 @@ ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics
# Generic warnings
#
ARCHWARNINGS = -Wall \
-Wextra \
-Werror \
-Wdouble-promotion \
-Wshadow \
-Wfloat-equal \
-Wframe-larger-than=1024 \
-Wpointer-arith \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
-Wno-unused-parameter \
-Werror=format-security \
-Werror=array-bounds \
-Wfatal-errors \
-Wformat=1 \
-Werror=unused-but-set-variable \
-Werror=unused-variable \
-Werror=double-promotion \
-Werror=reorder
# ARCHWARNINGS = -Wall \
# -Wextra \
# -Werror \
# -Wdouble-promotion \
# -Wshadow \
# -Wfloat-equal \
# -Wframe-larger-than=1024 \
# -Wpointer-arith \
# -Wlogical-op \
# -Wmissing-declarations \
# -Wpacked \
# -Wno-unused-parameter \
# -Werror=format-security \
# -Werror=array-bounds \
# -Wfatal-errors \
# -Wformat=1 \
# -Werror=unused-but-set-variable \
# -Werror=unused-variable \
# -Werror=double-promotion \
# -Werror=reorder
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives

View File

@ -37,6 +37,7 @@
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include <px4.h>
class PublisherExample {
@ -48,5 +49,5 @@ public:
int main();
protected:
px4::NodeHandle _n;
px4::Publisher * _rc_channels_pub;
px4::Publisher<px4::px4_rc_channels> * _rc_channels_pub;
};

View File

@ -124,12 +124,12 @@ public:
* Advertise topic
*/
template<typename T>
Publisher* advertise()
Publisher<T>* advertise()
{
ros::Publisher ros_pub = ros::NodeHandle::advertise<typename std::remove_reference<decltype(((T*)nullptr)->data())>::type &>(T::handle(), kQueueSizeDefault);
Publisher *pub = new Publisher(ros_pub);
_pubs.push_back(pub);
return pub;
PublisherROS<T> *pub = new PublisherROS<T>(ros_pub);
_pubs.push_back((PublisherBase*)pub);
return (Publisher<T>*)pub;
}
/**
@ -236,16 +236,16 @@ public:
* Advertise topic
*/
template<typename T>
Publisher *advertise()
Publisher<T> *advertise()
{
//XXX
// uORB::PublicationBase * uorb_pub = new uORB::PublicationBase((new T())->handle());
uORB::PublicationBase * uorb_pub = new uORB::PublicationBase(T::handle());
Publisher *pub = new Publisher(uorb_pub);
PublisherUORB<T> *pub = new PublisherUORB<T>(uorb_pub);
_pubs.add(pub);
return pub;
return (Publisher<T>*)pub;
}
/**

View File

@ -61,29 +61,44 @@ public:
~PublisherBase() {};
};
/**
* Publisher base class, templated with the message type
* */
template <typename T>
class __EXPORT Publisher
{
public:
Publisher() {};
~Publisher() {};
virtual int publish(const T &msg) = 0;
};
#if defined(__PX4_ROS)
class Publisher :
public PublisherBase
template <typename T>
class PublisherROS :
public Publisher<T>
{
public:
/**
* Construct Publisher by providing a ros::Publisher
* @param ros_pub the ros publisher which will be used to perform the publications
*/
Publisher(ros::Publisher ros_pub) :
PublisherBase(),
PublisherROS(ros::Publisher ros_pub) :
Publisher<T>(),
_ros_pub(ros_pub)
{}
~Publisher() {};
~PublisherROS() {};
/** Publishes msg
* @param msg the message which is published to the topic
*/
template <typename T>
int publish(T &msg) {
int publish(const T &msg)
{
_ros_pub.publish(msg.data());
return 0;}
return 0;
}
private:
ros::Publisher _ros_pub; /**< Handle to the ros publisher */
};
@ -104,8 +119,9 @@ public:
virtual void update() = 0;
};
class __EXPORT Publisher :
public PublisherBase,
template <typename T>
class __EXPORT PublisherUORB :
public Publisher<T>,
public PublisherNode
{
@ -113,17 +129,17 @@ public:
/**
* Construct Publisher by providing orb meta data
*/
Publisher(uORB::PublicationBase * uorb_pub) :
PublisherBase(),
PublisherUORB(uORB::PublicationBase * uorb_pub) :
Publisher<T>(),
PublisherNode(),
_uorb_pub(uorb_pub)
{}
~Publisher() {};
~PublisherUORB() {};
/** Publishes msg
* @param msg the message which is published to the topic
*/
template<typename T>
int publish(const T &msg)
{
_uorb_pub->update((void *)&(msg.data()));