mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
SubscriptionMultiArray: use Subscription instead of SubscriptionInterval
Saves ~3KB RAM on fmu-v5.
This commit is contained in:
parent
9b0b0d1168
commit
04f7df3848
@ -76,7 +76,7 @@ public:
|
||||
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
|
||||
* @param instance The instance for multi sub.
|
||||
*/
|
||||
Subscription(const orb_metadata *meta, uint8_t instance = 0) :
|
||||
Subscription(const orb_metadata *meta = nullptr, uint8_t instance = 0) :
|
||||
_orb_id((meta == nullptr) ? ORB_ID::INVALID : static_cast<ORB_ID>(meta->o_id)),
|
||||
_instance(instance)
|
||||
{
|
||||
|
||||
@ -43,7 +43,7 @@
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
|
||||
#include "SubscriptionInterval.hpp"
|
||||
#include "Subscription.hpp"
|
||||
|
||||
namespace uORB
|
||||
{
|
||||
@ -67,21 +67,21 @@ public:
|
||||
explicit SubscriptionMultiArray(ORB_ID id)
|
||||
{
|
||||
for (uint8_t i = 0; i < SIZE; i++) {
|
||||
_subscriptions[i] = SubscriptionInterval{id, 0, i};
|
||||
_subscriptions[i] = Subscription{id, i};
|
||||
_subscriptions[i].subscribe();
|
||||
}
|
||||
}
|
||||
|
||||
~SubscriptionMultiArray() = default;
|
||||
|
||||
SubscriptionInterval &operator [](int i) { return _subscriptions[i]; }
|
||||
const SubscriptionInterval &operator [](int i) const { return _subscriptions[i]; }
|
||||
Subscription &operator [](int i) { return _subscriptions[i]; }
|
||||
const Subscription &operator [](int i) const { return _subscriptions[i]; }
|
||||
|
||||
SubscriptionInterval *begin() { return _subscriptions; }
|
||||
SubscriptionInterval *end() { return _subscriptions + SIZE; }
|
||||
Subscription *begin() { return _subscriptions; }
|
||||
Subscription *end() { return _subscriptions + SIZE; }
|
||||
|
||||
const SubscriptionInterval *begin() const { return _subscriptions; }
|
||||
const SubscriptionInterval *end() const { return _subscriptions + SIZE; }
|
||||
const Subscription *begin() const { return _subscriptions; }
|
||||
const Subscription *end() const { return _subscriptions + SIZE; }
|
||||
|
||||
// true if any instance is advertised
|
||||
bool advertised()
|
||||
@ -122,7 +122,7 @@ public:
|
||||
}
|
||||
|
||||
private:
|
||||
SubscriptionInterval _subscriptions[SIZE];
|
||||
Subscription _subscriptions[SIZE];
|
||||
};
|
||||
|
||||
} // namespace uORB
|
||||
|
||||
@ -46,6 +46,7 @@
|
||||
#include <lib/systemlib/mavlink_log.h>
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionInterval.hpp>
|
||||
#include <uORB/SubscriptionMultiArray.hpp>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
#include <uORB/topics/airspeed_validated.h>
|
||||
|
||||
@ -63,6 +63,7 @@
|
||||
|
||||
// subscriptions
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionInterval.hpp>
|
||||
#include <uORB/SubscriptionMultiArray.hpp>
|
||||
#include <uORB/topics/action_request.h>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user