mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
uORB cleanup Subscription/Publication c++
This commit is contained in:
parent
7223780563
commit
e63da5860e
@ -911,8 +911,7 @@ void Logger::run()
|
||||
|
||||
/* Check if parameters have changed */
|
||||
// this needs to change to a timestamped record to record a history of parameter changes
|
||||
if (parameter_update_sub.check_updated()) {
|
||||
parameter_update_sub.update();
|
||||
if (parameter_update_sub.update()) {
|
||||
write_changed_parameters();
|
||||
}
|
||||
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -42,54 +42,57 @@
|
||||
namespace uORB
|
||||
{
|
||||
|
||||
PublicationBase::PublicationBase(const struct orb_metadata *meta,
|
||||
int priority) :
|
||||
PublicationBase::PublicationBase(const struct orb_metadata *meta, int priority) :
|
||||
_meta(meta),
|
||||
_priority(priority),
|
||||
_instance(),
|
||||
_handle(nullptr)
|
||||
_priority(priority)
|
||||
{
|
||||
}
|
||||
|
||||
void PublicationBase::update(void *data)
|
||||
{
|
||||
if (_handle != nullptr) {
|
||||
int ret = orb_publish(getMeta(), getHandle(), data);
|
||||
|
||||
if (ret != PX4_OK) { warnx("publish fail"); }
|
||||
|
||||
} else {
|
||||
orb_advert_t handle;
|
||||
|
||||
if (_priority > 0) {
|
||||
handle = orb_advertise_multi(
|
||||
getMeta(), data,
|
||||
&_instance, _priority);
|
||||
|
||||
} else {
|
||||
handle = orb_advertise(getMeta(), data);
|
||||
}
|
||||
|
||||
if (int64_t(handle) != PX4_ERROR) {
|
||||
setHandle(handle);
|
||||
|
||||
} else {
|
||||
warnx("advert fail");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
PublicationBase::~PublicationBase()
|
||||
{
|
||||
orb_unadvertise(getHandle());
|
||||
orb_unadvertise(_handle);
|
||||
}
|
||||
|
||||
PublicationNode::PublicationNode(const struct orb_metadata *meta,
|
||||
int priority,
|
||||
List<PublicationNode *> *list) :
|
||||
bool PublicationBase::update(void *data)
|
||||
{
|
||||
bool updated = false;
|
||||
|
||||
if (_handle != nullptr) {
|
||||
if (orb_publish(_meta, _handle, data) != PX4_OK) {
|
||||
PX4_ERR("%s publish fail", _meta->o_name);
|
||||
|
||||
} else {
|
||||
updated = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
orb_advert_t handle = nullptr;
|
||||
|
||||
if (_priority > 0) {
|
||||
handle = orb_advertise_multi(_meta, data, &_instance, _priority);
|
||||
|
||||
} else {
|
||||
handle = orb_advertise(_meta, data);
|
||||
}
|
||||
|
||||
if (handle != nullptr) {
|
||||
_handle = handle;
|
||||
updated = true;
|
||||
|
||||
} else {
|
||||
PX4_ERR("%s advert fail", _meta->o_name);
|
||||
}
|
||||
}
|
||||
|
||||
return updated;
|
||||
}
|
||||
|
||||
PublicationNode::PublicationNode(const struct orb_metadata *meta, int priority, List<PublicationNode *> *list) :
|
||||
PublicationBase(meta, priority)
|
||||
{
|
||||
if (list != nullptr) { list->add(this); }
|
||||
if (list != nullptr) {
|
||||
list->add(this);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
} // namespace uORB
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -32,14 +32,12 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file Publication.h
|
||||
* @file Publication.hpp
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <assert.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <containers/List.hpp>
|
||||
#include <systemlib/err.h>
|
||||
@ -63,35 +61,28 @@ public:
|
||||
* @param priority The priority for multi pub/sub, 0-based, -1 means
|
||||
* don't publish as multi
|
||||
*/
|
||||
PublicationBase(const struct orb_metadata *meta,
|
||||
int priority = -1);
|
||||
PublicationBase(const struct orb_metadata *meta, int priority = -1);
|
||||
|
||||
virtual ~PublicationBase();
|
||||
|
||||
// no copy, assignment, move, move assignment
|
||||
PublicationBase(const PublicationBase &) = delete;
|
||||
PublicationBase &operator=(const PublicationBase &) = delete;
|
||||
PublicationBase(PublicationBase &&) = delete;
|
||||
PublicationBase &operator=(PublicationBase &&) = delete;
|
||||
|
||||
/**
|
||||
* Update the struct
|
||||
* @param data The uORB message struct we are updating.
|
||||
*/
|
||||
void update(void *data);
|
||||
bool update(void *data);
|
||||
|
||||
/**
|
||||
* Deconstructor
|
||||
*/
|
||||
virtual ~PublicationBase();
|
||||
|
||||
// accessors
|
||||
const struct orb_metadata *getMeta() { return _meta; }
|
||||
orb_advert_t getHandle() { return _handle; }
|
||||
protected:
|
||||
// disallow copy
|
||||
PublicationBase(const PublicationBase &other);
|
||||
// disallow assignment
|
||||
PublicationBase &operator=(const PublicationBase &other);
|
||||
// accessors
|
||||
void setHandle(orb_advert_t handle) { _handle = handle; }
|
||||
// attributes
|
||||
const struct orb_metadata *_meta;
|
||||
int _priority;
|
||||
int _instance;
|
||||
orb_advert_t _handle;
|
||||
const int _priority;
|
||||
|
||||
int _instance{0};
|
||||
orb_advert_t _handle{nullptr};
|
||||
};
|
||||
|
||||
/**
|
||||
@ -103,9 +94,7 @@ typedef PublicationBase PublicationTiny;
|
||||
/**
|
||||
* The publication base class as a list node.
|
||||
*/
|
||||
class __EXPORT PublicationNode :
|
||||
public PublicationBase,
|
||||
public ListNode<PublicationNode *>
|
||||
class __EXPORT PublicationNode : public PublicationBase, public ListNode<PublicationNode *>
|
||||
{
|
||||
public:
|
||||
/**
|
||||
@ -118,20 +107,20 @@ public:
|
||||
* list during construction
|
||||
*/
|
||||
PublicationNode(const struct orb_metadata *meta, int priority = -1, List<PublicationNode *> *list = nullptr);
|
||||
virtual ~PublicationNode() override = default;
|
||||
|
||||
/**
|
||||
* This function is the callback for list traversal
|
||||
* updates, a child class must implement it.
|
||||
*/
|
||||
virtual void update() = 0;
|
||||
virtual bool update() = 0;
|
||||
};
|
||||
|
||||
/**
|
||||
* Publication wrapper class
|
||||
*/
|
||||
template<class T>
|
||||
class __EXPORT Publication :
|
||||
public PublicationNode
|
||||
class __EXPORT Publication final : public PublicationNode
|
||||
{
|
||||
public:
|
||||
/**
|
||||
@ -149,10 +138,13 @@ public:
|
||||
{
|
||||
}
|
||||
|
||||
/**
|
||||
* Deconstructor
|
||||
**/
|
||||
virtual ~Publication() {};
|
||||
~Publication() override = default;
|
||||
|
||||
// no copy, assignment, move, move assignment
|
||||
Publication(const Publication &) = delete;
|
||||
Publication &operator=(const Publication &) = delete;
|
||||
Publication(Publication &&) = delete;
|
||||
Publication &operator=(Publication &&) = delete;
|
||||
|
||||
/*
|
||||
* This function gets the T struct
|
||||
@ -162,10 +154,11 @@ public:
|
||||
/**
|
||||
* Create an update function that uses the embedded struct.
|
||||
*/
|
||||
void update()
|
||||
bool update() override
|
||||
{
|
||||
PublicationBase::update((void *)(&_data));
|
||||
return PublicationBase::update((void *)(&_data));
|
||||
}
|
||||
|
||||
private:
|
||||
T _data;
|
||||
};
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -42,51 +42,67 @@
|
||||
namespace uORB
|
||||
{
|
||||
|
||||
SubscriptionBase::SubscriptionBase(const struct orb_metadata *meta,
|
||||
unsigned interval, unsigned instance) :
|
||||
SubscriptionBase::SubscriptionBase(const struct orb_metadata *meta, unsigned interval, unsigned instance) :
|
||||
_meta(meta),
|
||||
_instance(instance),
|
||||
_handle()
|
||||
_instance(instance)
|
||||
{
|
||||
if (_instance > 0) {
|
||||
_handle = orb_subscribe_multi(
|
||||
getMeta(), instance);
|
||||
if (instance > 0) {
|
||||
_handle = orb_subscribe_multi(_meta, instance);
|
||||
|
||||
} else {
|
||||
_handle = orb_subscribe(getMeta());
|
||||
_handle = orb_subscribe(_meta);
|
||||
}
|
||||
|
||||
if (_handle < 0) { PX4_ERR("sub failed"); }
|
||||
if (_handle < 0) {
|
||||
PX4_ERR("%s sub failed", _meta->o_name);
|
||||
}
|
||||
|
||||
if (interval > 0) {
|
||||
orb_set_interval(getHandle(), interval);
|
||||
orb_set_interval(_handle, interval);
|
||||
}
|
||||
}
|
||||
|
||||
bool SubscriptionBase::updated()
|
||||
{
|
||||
bool isUpdated = false;
|
||||
int ret = orb_check(_handle, &isUpdated);
|
||||
|
||||
if (ret != PX4_OK) { PX4_ERR("orb check failed"); }
|
||||
if (orb_check(_handle, &isUpdated) != PX4_OK) {
|
||||
PX4_ERR("%s check failed", _meta->o_name);
|
||||
}
|
||||
|
||||
return isUpdated;
|
||||
}
|
||||
|
||||
void SubscriptionBase::update(void *data)
|
||||
bool SubscriptionBase::update(void *data)
|
||||
{
|
||||
if (updated()) {
|
||||
int ret = orb_copy(_meta, _handle, data);
|
||||
bool orb_updated = false;
|
||||
|
||||
if (ret != PX4_OK) { PX4_ERR("orb copy failed"); }
|
||||
if (updated()) {
|
||||
if (orb_copy(_meta, _handle, data) != PX4_OK) {
|
||||
PX4_ERR("%s copy failed", _meta->o_name);
|
||||
|
||||
} else {
|
||||
orb_updated = true;
|
||||
}
|
||||
}
|
||||
|
||||
return orb_updated;
|
||||
}
|
||||
|
||||
SubscriptionBase::~SubscriptionBase()
|
||||
{
|
||||
int ret = orb_unsubscribe(_handle);
|
||||
if (orb_unsubscribe(_handle) != PX4_OK) {
|
||||
PX4_ERR("%s unsubscribe failed", _meta->o_name);
|
||||
}
|
||||
}
|
||||
|
||||
if (ret != PX4_OK) { PX4_ERR("orb unsubscribe failed"); }
|
||||
SubscriptionNode::SubscriptionNode(const struct orb_metadata *meta, unsigned interval, unsigned instance,
|
||||
List<SubscriptionNode *> *list)
|
||||
: SubscriptionBase(meta, interval, instance)
|
||||
{
|
||||
if (list != nullptr) {
|
||||
list->add(this);
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace uORB
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -32,14 +32,12 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file Subscription.h
|
||||
* @file Subscription.hpp
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <assert.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <containers/List.hpp>
|
||||
#include <systemlib/err.h>
|
||||
@ -48,14 +46,12 @@ namespace uORB
|
||||
{
|
||||
|
||||
/**
|
||||
* Base subscription warapper class, used in list traversal
|
||||
* Base subscription wrapper class, used in list traversal
|
||||
* of various subscriptions.
|
||||
*/
|
||||
class __EXPORT SubscriptionBase
|
||||
{
|
||||
public:
|
||||
// methods
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
@ -65,8 +61,14 @@ public:
|
||||
* between updates
|
||||
* @param instance The instance for multi sub.
|
||||
*/
|
||||
SubscriptionBase(const struct orb_metadata *meta,
|
||||
unsigned interval = 0, unsigned instance = 0);
|
||||
SubscriptionBase(const struct orb_metadata *meta, unsigned interval = 0, unsigned instance = 0);
|
||||
virtual ~SubscriptionBase();
|
||||
|
||||
// no copy, assignment, move, move assignment
|
||||
SubscriptionBase(const SubscriptionBase &) = delete;
|
||||
SubscriptionBase &operator=(const SubscriptionBase &) = delete;
|
||||
SubscriptionBase(SubscriptionBase &&) = delete;
|
||||
SubscriptionBase &operator=(SubscriptionBase &&) = delete;
|
||||
|
||||
/**
|
||||
* Check if there is a new update.
|
||||
@ -77,35 +79,14 @@ public:
|
||||
* Update the struct
|
||||
* @param data The uORB message struct we are updating.
|
||||
*/
|
||||
void update(void *data);
|
||||
bool update(void *data);
|
||||
|
||||
/**
|
||||
* Deconstructor
|
||||
*/
|
||||
virtual ~SubscriptionBase();
|
||||
|
||||
// accessors
|
||||
const struct orb_metadata *getMeta() { return _meta; }
|
||||
int getHandle() const { return _handle; }
|
||||
|
||||
unsigned getInterval() const
|
||||
{
|
||||
unsigned int interval;
|
||||
orb_get_interval(getHandle(), &interval);
|
||||
return interval;
|
||||
}
|
||||
protected:
|
||||
// accessors
|
||||
void setHandle(int handle) { _handle = handle; }
|
||||
// attributes
|
||||
const struct orb_metadata *_meta;
|
||||
int _instance;
|
||||
unsigned _instance;
|
||||
int _handle;
|
||||
private:
|
||||
// disallow copy
|
||||
SubscriptionBase(const SubscriptionBase &other);
|
||||
// disallow assignment
|
||||
SubscriptionBase &operator=(const SubscriptionBase &other);
|
||||
};
|
||||
|
||||
/**
|
||||
@ -116,10 +97,7 @@ typedef SubscriptionBase SubscriptionTiny;
|
||||
/**
|
||||
* The subscription base class as a list node.
|
||||
*/
|
||||
class __EXPORT SubscriptionNode :
|
||||
|
||||
public SubscriptionBase,
|
||||
public ListNode<SubscriptionNode *>
|
||||
class __EXPORT SubscriptionNode : public SubscriptionBase, public ListNode<SubscriptionNode *>
|
||||
{
|
||||
public:
|
||||
/**
|
||||
@ -133,20 +111,16 @@ public:
|
||||
* @param list A pointer to a list of subscriptions
|
||||
* that this should be appended to.
|
||||
*/
|
||||
SubscriptionNode(const struct orb_metadata *meta,
|
||||
unsigned interval = 0,
|
||||
int instance = 0,
|
||||
List<SubscriptionNode *> *list = nullptr) :
|
||||
SubscriptionBase(meta, interval, instance)
|
||||
{
|
||||
if (list != nullptr) { list->add(this); }
|
||||
}
|
||||
SubscriptionNode(const struct orb_metadata *meta, unsigned interval = 0, unsigned instance = 0,
|
||||
List<SubscriptionNode *> *list = nullptr);
|
||||
|
||||
virtual ~SubscriptionNode() override = default;
|
||||
|
||||
/**
|
||||
* This function is the callback for list traversal
|
||||
* updates, a child class must implement it.
|
||||
*/
|
||||
virtual void update() = 0;
|
||||
virtual bool update() = 0;
|
||||
|
||||
};
|
||||
|
||||
@ -154,8 +128,7 @@ public:
|
||||
* Subscription wrapper class
|
||||
*/
|
||||
template<class T>
|
||||
class __EXPORT Subscription :
|
||||
public SubscriptionNode
|
||||
class __EXPORT Subscription final : public SubscriptionNode
|
||||
{
|
||||
public:
|
||||
/**
|
||||
@ -168,43 +141,26 @@ public:
|
||||
* @param list A list interface for adding to
|
||||
* list during construction
|
||||
*/
|
||||
Subscription(const struct orb_metadata *meta,
|
||||
unsigned interval = 0,
|
||||
int instance = 0,
|
||||
Subscription(const struct orb_metadata *meta, unsigned interval = 0, unsigned instance = 0,
|
||||
List<SubscriptionNode *> *list = nullptr):
|
||||
SubscriptionNode(meta, interval, instance, list),
|
||||
_data() // initialize data structure to zero
|
||||
{}
|
||||
|
||||
~Subscription() override final = default;
|
||||
|
||||
Subscription(const Subscription &other):
|
||||
SubscriptionNode(other._meta, other.getInterval(), other._instance, nullptr),
|
||||
_data() // initialize data structure to zero
|
||||
{}
|
||||
|
||||
|
||||
/**
|
||||
* Deconstructor
|
||||
*/
|
||||
virtual ~Subscription()
|
||||
{}
|
||||
|
||||
// no copy, assignment, move, move assignment
|
||||
Subscription(const Subscription &) = delete;
|
||||
Subscription &operator=(const Subscription &) = delete;
|
||||
Subscription(Subscription &&) = delete;
|
||||
Subscription &operator=(Subscription &&) = delete;
|
||||
|
||||
/**
|
||||
* Create an update function that uses the embedded struct.
|
||||
*/
|
||||
void update()
|
||||
bool update() override final
|
||||
{
|
||||
SubscriptionBase::update((void *)(&_data));
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Create an update function that uses the embedded struct.
|
||||
*/
|
||||
bool check_updated()
|
||||
{
|
||||
return SubscriptionBase::updated();
|
||||
return SubscriptionBase::update((void *)(&_data));
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
@ -197,7 +197,7 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta,
|
||||
px4_close(fd);
|
||||
|
||||
if (result == ERROR) {
|
||||
PX4_WARN("px4_ioctl ORBIOCGADVERTISER failed. fd = %d", fd);
|
||||
PX4_WARN("px4_ioctl ORBIOCGADVERTISER failed. fd = %d", fd);
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user