Moved UOrbPubliction/Subscription to uORB::Publication/Subscription

This commit is contained in:
James Goppert 2014-03-16 16:14:56 -04:00
parent 2c32cdf16b
commit fd6590cfa7
14 changed files with 81 additions and 83 deletions

View File

@ -52,7 +52,7 @@
#include <arch/board/board.h>
#include <mavlink/mavlink_log.h>
#include <controllib/uorb/UOrbPublication.hpp>
#include </uORB/Publication.hpp>
#include <uORB/topics/debug_key_value.h>
#include <drivers/drv_hrt.h>
@ -587,7 +587,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitu
float prev_revolution = md25.getRevolutions1();
// debug publication
control::UOrbPublication<debug_key_value_s> debug_msg(NULL,
uORB::Publication<debug_key_value_s> debug_msg(NULL,
ORB_ID(debug_key_value));
// sine wave for motor 1

View File

@ -46,7 +46,7 @@
#include <poll.h>
#include <stdio.h>
#include <controllib/uorb/UOrbSubscription.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <drivers/device/i2c.h>
@ -270,7 +270,7 @@ private:
struct pollfd _controlPoll;
/** actuator controls subscription */
control::UOrbSubscription<actuator_controls_s> _actuators;
uORB::Subscription<actuator_controls_s> _actuators;
// local copy of data from i2c device
uint8_t _version;

View File

@ -53,7 +53,7 @@
#include <arch/board/board.h>
#include <mavlink/mavlink_log.h>
#include <controllib/uorb/UOrbPublication.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/debug_key_value.h>
#include <drivers/drv_hrt.h>

View File

@ -45,7 +45,7 @@
#include <poll.h>
#include <stdio.h>
#include <controllib/uorb/UOrbSubscription.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <drivers/device/i2c.h>
@ -169,7 +169,7 @@ private:
struct pollfd _controlPoll;
/** actuator controls subscription */
control::UOrbSubscription<actuator_controls_s> _actuators;
uORB::Subscription<actuator_controls_s> _actuators;
// private data
float _motor1Position;

View File

@ -47,8 +47,8 @@
#include <mathlib/mathlib.h>
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
#include <controllib/uorb/UOrbSubscription.hpp>
#include <controllib/uorb/UOrbPublication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_global_position.h>
@ -138,13 +138,13 @@ protected:
math::Matrix<3,3> C_nb; /**< direction cosine matrix from body to nav frame */
math::Quaternion q; /**< quaternion from body to nav frame */
// subscriptions
control::UOrbSubscription<sensor_combined_s> _sensors; /**< sensors sub. */
control::UOrbSubscription<vehicle_gps_position_s> _gps; /**< gps sub. */
control::UOrbSubscription<parameter_update_s> _param_update; /**< parameter update sub. */
uORB::Subscription<sensor_combined_s> _sensors; /**< sensors sub. */
uORB::Subscription<vehicle_gps_position_s> _gps; /**< gps sub. */
uORB::Subscription<parameter_update_s> _param_update; /**< parameter update sub. */
// publications
control::UOrbPublication<vehicle_global_position_s> _pos; /**< position pub. */
control::UOrbPublication<vehicle_local_position_s> _localPos; /**< local position pub. */
control::UOrbPublication<vehicle_attitude_s> _att; /**< attitude pub. */
uORB::Publication<vehicle_global_position_s> _pos; /**< position pub. */
uORB::Publication<vehicle_local_position_s> _localPos; /**< local position pub. */
uORB::Publication<vehicle_attitude_s> _att; /**< attitude pub. */
// time stamps
uint64_t _pubTimeStamp; /**< output data publication time stamp */
uint64_t _predictTimeStamp; /**< prediction time stamp */

View File

@ -43,8 +43,8 @@
#include "Block.hpp"
#include "BlockParam.hpp"
#include "../uorb/UOrbSubscription.hpp"
#include "../uorb/UOrbPublication.hpp"
#include "uORB/Subscription.hpp"
#include "uORB/Publication.hpp"
namespace control
{
@ -100,7 +100,7 @@ void Block::updateParams()
void Block::updateSubscriptions()
{
UOrbSubscriptionBase *sub = getSubscriptions().getHead();
uORB::SubscriptionBase *sub = getSubscriptions().getHead();
int count = 0;
while (sub != NULL) {
@ -118,7 +118,7 @@ void Block::updateSubscriptions()
void Block::updatePublications()
{
UOrbPublicationBase *pub = getPublications().getHead();
uORB::PublicationBase *pub = getPublications().getHead();
int count = 0;
while (pub != NULL) {

View File

@ -44,6 +44,12 @@
#include "List.hpp"
// forward declaration
namespace uORB {
class SubscriptionBase;
class PublicationBase;
}
namespace control
{
@ -55,8 +61,6 @@ static const uint8_t blockNameLengthMax = 80;
// forward declaration
class BlockParamBase;
class UOrbSubscriptionBase;
class UOrbPublicationBase;
class SuperBlock;
/**
@ -79,15 +83,15 @@ public:
protected:
// accessors
SuperBlock *getParent() { return _parent; }
List<UOrbSubscriptionBase *> & getSubscriptions() { return _subscriptions; }
List<UOrbPublicationBase *> & getPublications() { return _publications; }
List<uORB::SubscriptionBase *> & getSubscriptions() { return _subscriptions; }
List<uORB::PublicationBase *> & getPublications() { return _publications; }
List<BlockParamBase *> & getParams() { return _params; }
// attributes
const char *_name;
SuperBlock *_parent;
float _dt;
List<UOrbSubscriptionBase *> _subscriptions;
List<UOrbPublicationBase *> _publications;
List<uORB::SubscriptionBase *> _subscriptions;
List<uORB::PublicationBase *> _publications;
List<BlockParamBase *> _params;
};

View File

@ -37,7 +37,5 @@
SRCS = test_params.c \
block/Block.cpp \
block/BlockParam.cpp \
uorb/UOrbPublication.cpp \
uorb/UOrbSubscription.cpp \
uorb/blocks.cpp \
blocks.cpp

View File

@ -62,8 +62,8 @@ extern "C" {
}
#include "../blocks.hpp"
#include "UOrbSubscription.hpp"
#include "UOrbPublication.hpp"
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
namespace control
{
@ -94,16 +94,16 @@ class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
{
protected:
// subscriptions
UOrbSubscription<vehicle_attitude_s> _att;
UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
UOrbSubscription<vehicle_global_position_s> _pos;
UOrbSubscription<position_setpoint_triplet_s> _missionCmd;
UOrbSubscription<manual_control_setpoint_s> _manual;
UOrbSubscription<vehicle_status_s> _status;
UOrbSubscription<parameter_update_s> _param_update;
uORB::Subscription<vehicle_attitude_s> _att;
uORB::Subscription<vehicle_attitude_setpoint_s> _attCmd;
uORB::Subscription<vehicle_rates_setpoint_s> _ratesCmd;
uORB::Subscription<vehicle_global_position_s> _pos;
uORB::Subscription<position_setpoint_triplet_s> _missionCmd;
uORB::Subscription<manual_control_setpoint_s> _manual;
uORB::Subscription<vehicle_status_s> _status;
uORB::Subscription<parameter_update_s> _param_update;
// publications
UOrbPublication<actuator_controls_s> _actuators;
uORB::Publication<actuator_controls_s> _actuators;
public:
BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
virtual ~BlockUorbEnabledAutopilot();

View File

@ -32,8 +32,8 @@
****************************************************************************/
/**
* @file UOrbPublication.cpp
* @file Publication.cpp
*
*/
#include "UOrbPublication.hpp"
#include "Publication.hpp"

View File

@ -32,32 +32,29 @@
****************************************************************************/
/**
* @file UOrbPublication.h
* @file Publication.h
*
*/
#pragma once
#include <uORB/uORB.h>
#include "../block/Block.hpp"
#include "../block/List.hpp"
#include <controllib/block/List.hpp>
namespace control
namespace uORB
{
class Block;
/**
* Base publication warapper class, used in list traversal
* of various publications.
*/
class __EXPORT UOrbPublicationBase : public ListNode<control::UOrbPublicationBase *>
class __EXPORT PublicationBase : public ListNode<uORB::PublicationBase *>
{
public:
UOrbPublicationBase(
List<UOrbPublicationBase *> * list,
PublicationBase(
List<PublicationBase *> * list,
const struct orb_metadata *meta) :
_meta(meta),
_handle(-1) {
@ -71,7 +68,7 @@ public:
}
}
virtual void *getDataVoidPtr() = 0;
virtual ~UOrbPublicationBase() {
virtual ~PublicationBase() {
orb_unsubscribe(getHandle());
}
const struct orb_metadata *getMeta() { return _meta; }
@ -83,12 +80,12 @@ protected:
};
/**
* UOrb Publication wrapper class
* Publication wrapper class
*/
template<class T>
class UOrbPublication :
class Publication :
public T, // this must be first!
public UOrbPublicationBase
public PublicationBase
{
public:
/**
@ -98,13 +95,13 @@ public:
* @param meta The uORB metadata (usually from the ORB_ID() macro)
* for the topic.
*/
UOrbPublication(
List<UOrbPublicationBase *> * list,
Publication(
List<PublicationBase *> * list,
const struct orb_metadata *meta) :
T(), // initialize data structure to zero
UOrbPublicationBase(list, meta) {
PublicationBase(list, meta) {
}
virtual ~UOrbPublication() {}
virtual ~Publication() {}
/*
* XXX
* This function gets the T struct, assuming
@ -115,4 +112,4 @@ public:
void *getDataVoidPtr() { return (void *)(T *)(this); }
};
} // namespace control
} // namespace uORB

View File

@ -32,20 +32,20 @@
****************************************************************************/
/**
* @file UOrbSubscription.cpp
* @file Subscription.cpp
*
*/
#include "UOrbSubscription.hpp"
#include "Subscription.hpp"
namespace control
namespace uORB
{
bool __EXPORT UOrbSubscriptionBase::updated()
bool __EXPORT SubscriptionBase::updated()
{
bool isUpdated = false;
orb_check(_handle, &isUpdated);
return isUpdated;
}
} // namespace control
} // namespace uORB

View File

@ -32,28 +32,25 @@
****************************************************************************/
/**
* @file UOrbSubscription.h
* @file Subscription.h
*
*/
#pragma once
#include <uORB/uORB.h>
#include "../block/Block.hpp"
#include "../block/List.hpp"
#include <controllib/block/List.hpp>
namespace control
namespace uORB
{
class Block;
/**
* Base subscription warapper class, used in list traversal
* of various subscriptions.
*/
class __EXPORT UOrbSubscriptionBase :
public ListNode<control::UOrbSubscriptionBase *>
class __EXPORT SubscriptionBase :
public ListNode<SubscriptionBase *>
{
public:
// methods
@ -64,8 +61,8 @@ public:
* @param meta The uORB metadata (usually from the ORB_ID() macro)
* for the topic.
*/
UOrbSubscriptionBase(
List<UOrbSubscriptionBase *> * list,
SubscriptionBase(
List<SubscriptionBase *> * list,
const struct orb_metadata *meta) :
_meta(meta),
_handle() {
@ -78,7 +75,7 @@ public:
}
}
virtual void *getDataVoidPtr() = 0;
virtual ~UOrbSubscriptionBase() {
virtual ~SubscriptionBase() {
orb_unsubscribe(_handle);
}
// accessors
@ -93,12 +90,12 @@ protected:
};
/**
* UOrb Subscription wrapper class
* Subscription wrapper class
*/
template<class T>
class __EXPORT UOrbSubscription :
class __EXPORT Subscription :
public T, // this must be first!
public UOrbSubscriptionBase
public SubscriptionBase
{
public:
/**
@ -109,11 +106,11 @@ public:
* for the topic.
* @param interval The minimum interval in milliseconds between updates
*/
UOrbSubscription(
List<UOrbSubscriptionBase *> * list,
Subscription(
List<SubscriptionBase *> * list,
const struct orb_metadata *meta, unsigned interval) :
T(), // initialize data structure to zero
UOrbSubscriptionBase(list, meta) {
SubscriptionBase(list, meta) {
setHandle(orb_subscribe(getMeta()));
orb_set_interval(getHandle(), interval);
}
@ -121,7 +118,7 @@ public:
/**
* Deconstructor
*/
virtual ~UOrbSubscription() {}
virtual ~Subscription() {}
/*
* XXX
@ -134,4 +131,4 @@ public:
T getData() { return T(*this); }
};
} // namespace control
} // namespace uORB

View File

@ -41,4 +41,6 @@ MODULE_COMMAND = uorb
MODULE_STACKSIZE = 4096
SRCS = uORB.cpp \
objects_common.cpp
objects_common.cpp \
Publication.cpp \
Subscription.cpp