refactor uorb: rename published to advertised

No semantic change (yet)
This commit is contained in:
Beat Küng 2019-11-25 10:02:11 +01:00
parent 0e9fde2055
commit 8e8d6deea5
10 changed files with 24 additions and 24 deletions

View File

@ -73,7 +73,7 @@
/** Get the minimum interval at which the topic can be seen to be updated for this subscription */
#define ORBIOCGETINTERVAL _ORBIOC(16)
/** Check whether the topic is published, sets *(unsigned long *)arg to 1 if published, 0 otherwise */
#define ORBIOCISPUBLISHED _ORBIOC(17)
/** Check whether the topic is advertised, sets *(unsigned long *)arg to 1 if advertised, 0 otherwise */
#define ORBIOCISADVERTISED _ORBIOC(17)
#endif /* _DRV_UORB_H */

View File

@ -188,7 +188,7 @@ void Heater::initialize_topics()
for (uint8_t x = 0; x < number_of_imus; x++) {
_sensor_accel_sub = uORB::Subscription{ORB_ID(sensor_accel), x};
if (!_sensor_accel_sub.published()) {
if (!_sensor_accel_sub.advertised()) {
continue;
}

View File

@ -42,7 +42,7 @@
bool
MavlinkOrbSubscription::is_published()
{
const bool published = _sub.published();
const bool published = _sub.advertised();
if (published) {
return true;

View File

@ -116,7 +116,7 @@ Subscription::init()
bool
Subscription::update(uint64_t *time, void *dst)
{
if ((time != nullptr) && (dst != nullptr) && published()) {
if ((time != nullptr) && (dst != nullptr) && advertised()) {
// always copy data to dst regardless of update
const uint64_t t = _node->copy_and_get_timestamp(dst, _last_generation);

View File

@ -75,17 +75,17 @@ public:
void unsubscribe();
bool valid() const { return _node != nullptr; }
bool published()
bool advertised()
{
if (valid()) {
return _node->is_published();
return _node->is_advertised();
}
// try to initialize
if (init()) {
// check again if valid
if (valid()) {
return _node->is_published();
return _node->is_advertised();
}
}
@ -95,7 +95,7 @@ public:
/**
* Check if there is a new update.
* */
bool updated() { return published() ? (_node->published_message_count() != _last_generation) : false; }
bool updated() { return advertised() ? (_node->published_message_count() != _last_generation) : false; }
/**
* Update the struct
@ -118,7 +118,7 @@ public:
* Copy the struct
* @param data The uORB message struct we are updating.
*/
bool copy(void *dst) { return published() ? _node->copy(dst, _last_generation) : false; }
bool copy(void *dst) { return advertised() ? _node->copy(dst, _last_generation) : false; }
uint8_t get_instance() const { return _instance; }
orb_id_t get_topic() const { return _meta; }

View File

@ -73,14 +73,14 @@ public:
bool subscribe() { return _subscription.subscribe(); }
bool published() { return _subscription.published(); }
bool advertised() { return _subscription.advertised(); }
/**
* Check if there is a new update.
* */
bool updated()
{
if (published() && (hrt_elapsed_time(&_last_update) >= _interval_us)) {
if (advertised() && (hrt_elapsed_time(&_last_update) >= _interval_us)) {
return _subscription.updated();
}

View File

@ -123,7 +123,7 @@ uORB::DeviceMaster::advertise(const struct orb_metadata *meta, int *instance, in
* something has been published yet. */
uORB::DeviceNode *existing_node = getDeviceNodeLocked(meta, group_tries);
if ((existing_node != nullptr) && !(existing_node->is_published())) {
if (existing_node != nullptr && !existing_node->is_advertised()) {
/* nothing has been published yet, lets claim it */
existing_node->set_priority(priority);
ret = PX4_OK;

View File

@ -308,7 +308,7 @@ uORB::DeviceNode::write(cdev::file_t *filp, const char *buffer, size_t buflen)
/* update the timestamp and generation count */
_last_update = hrt_absolute_time();
_published = true;
_advertised = true;
// callbacks
for (auto item : _callbacks) {
@ -396,8 +396,8 @@ uORB::DeviceNode::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
return OK;
case ORBIOCISPUBLISHED:
*(unsigned long *)arg = _published;
case ORBIOCISADVERTISED:
*(unsigned long *)arg = _advertised;
return OK;
@ -475,7 +475,7 @@ int uORB::DeviceNode::unadvertise(orb_advert_t handle)
* of subscribers and publishers. But we also do not have a leak since future
* publishers reuse the same DeviceNode object.
*/
devnode->_published = false;
devnode->_advertised = false;
return PX4_OK;
}

View File

@ -158,11 +158,11 @@ public:
void remove_internal_subscriber();
/**
* Return true if this topic has been published.
* Return true if this topic has been advertised.
*
* This is used in the case of multi_pub/sub to check if it's valid to advertise
* and publish to this node or if another node should be tried. */
bool is_published() const { return _published; }
bool is_advertised() const { return _advertised; }
/**
* Try to change the size of the queue. This can only be done as long as nobody published yet.
@ -271,7 +271,7 @@ private:
px4::atomic<unsigned> _generation{0}; /**< object generation count */
List<uORB::SubscriptionCallback *> _callbacks;
uint8_t _priority; /**< priority of the topic */
bool _published{false}; /**< has ever data been published */
bool _advertised{false}; /**< has ever been advertised (not necessarily published data yet) */
uint8_t _queue_size; /**< maximum number of elements in the queue */
int8_t _subscriber_count{0};

View File

@ -116,7 +116,7 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
uORB::DeviceNode *node = _device_master->getDeviceNode(meta, instance);
if (node != nullptr) {
if (node->is_published()) {
if (node->is_advertised()) {
return PX4_OK;
}
}
@ -150,10 +150,10 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
int fd = px4_open(path, 0);
if (fd >= 0) {
unsigned long is_published;
unsigned long is_advertised;
if (px4_ioctl(fd, ORBIOCISPUBLISHED, (unsigned long)&is_published) == 0) {
if (!is_published) {
if (px4_ioctl(fd, ORBIOCISADVERTISED, (unsigned long)&is_advertised) == 0) {
if (!is_advertised) {
ret = PX4_ERROR;
}
}