From 63b2befeed7d87a6a35313a7089e13a80bcbe69f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 20 Nov 2019 09:19:26 +0100 Subject: [PATCH] refactor uorb: rename published to advertised No semantic change (yet) --- src/drivers/drv_orb_dev.h | 4 ++-- src/drivers/heater/heater.cpp | 2 +- .../airspeed_selector/airspeed_selector_main.cpp | 2 +- src/modules/mavlink/mavlink_orb_subscription.cpp | 2 +- src/modules/uORB/Subscription.cpp | 2 +- src/modules/uORB/Subscription.hpp | 10 +++++----- src/modules/uORB/SubscriptionInterval.hpp | 4 ++-- src/modules/uORB/uORBDeviceMaster.cpp | 2 +- src/modules/uORB/uORBDeviceNode.cpp | 8 ++++---- src/modules/uORB/uORBDeviceNode.hpp | 6 +++--- src/modules/uORB/uORBManager.cpp | 8 ++++---- 11 files changed, 25 insertions(+), 25 deletions(-) diff --git a/src/drivers/drv_orb_dev.h b/src/drivers/drv_orb_dev.h index 163ef421ab..4388a46314 100644 --- a/src/drivers/drv_orb_dev.h +++ b/src/drivers/drv_orb_dev.h @@ -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 */ diff --git a/src/drivers/heater/heater.cpp b/src/drivers/heater/heater.cpp index 139b93c62c..e7a545c3f4 100644 --- a/src/drivers/heater/heater.cpp +++ b/src/drivers/heater/heater.cpp @@ -136,7 +136,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; } diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index 24f3fcd3b9..85f7efae18 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -248,7 +248,7 @@ AirspeedModule::check_for_connected_airspeed_sensors() if (_param_airspeed_primary_index.get() > 0) { for (int i = 0; i < MAX_NUM_AIRSPEED_SENSORS; i++) { - if (!_airspeed_sub[i].published()) { + if (!_airspeed_sub[i].advertised()) { break; } diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp index 3173accaa3..afe2358bcc 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.cpp +++ b/src/modules/mavlink/mavlink_orb_subscription.cpp @@ -42,7 +42,7 @@ bool MavlinkOrbSubscription::is_published() { - const bool published = _sub.published(); + const bool published = _sub.advertised(); if (published) { return true; diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp index f996d73cb7..ddbdb56ef3 100644 --- a/src/modules/uORB/Subscription.cpp +++ b/src/modules/uORB/Subscription.cpp @@ -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); diff --git a/src/modules/uORB/Subscription.hpp b/src/modules/uORB/Subscription.hpp index c23aa960ae..edd09de543 100644 --- a/src/modules/uORB/Subscription.hpp +++ b/src/modules/uORB/Subscription.hpp @@ -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; } diff --git a/src/modules/uORB/SubscriptionInterval.hpp b/src/modules/uORB/SubscriptionInterval.hpp index 901648eb87..771dfe1b2a 100644 --- a/src/modules/uORB/SubscriptionInterval.hpp +++ b/src/modules/uORB/SubscriptionInterval.hpp @@ -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(); } diff --git a/src/modules/uORB/uORBDeviceMaster.cpp b/src/modules/uORB/uORBDeviceMaster.cpp index 16644df6ad..f704f2df6c 100644 --- a/src/modules/uORB/uORBDeviceMaster.cpp +++ b/src/modules/uORB/uORBDeviceMaster.cpp @@ -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; diff --git a/src/modules/uORB/uORBDeviceNode.cpp b/src/modules/uORB/uORBDeviceNode.cpp index f4e979af63..e435c9ab4a 100644 --- a/src/modules/uORB/uORBDeviceNode.cpp +++ b/src/modules/uORB/uORBDeviceNode.cpp @@ -306,7 +306,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) { @@ -394,8 +394,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; @@ -473,7 +473,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; } diff --git a/src/modules/uORB/uORBDeviceNode.hpp b/src/modules/uORB/uORBDeviceNode.hpp index b60163eacf..60eb5ff13b 100644 --- a/src/modules/uORB/uORBDeviceNode.hpp +++ b/src/modules/uORB/uORBDeviceNode.hpp @@ -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 _generation{0}; /**< object generation count */ List _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}; diff --git a/src/modules/uORB/uORBManager.cpp b/src/modules/uORB/uORBManager.cpp index edc625fa1e..a0f2a678ab 100644 --- a/src/modules/uORB/uORBManager.cpp +++ b/src/modules/uORB/uORBManager.cpp @@ -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; } }