|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <SubscriptionInterval.hpp>
Public Member Functions | |
| SubscriptionInterval (const orb_metadata *meta, uint32_t interval_us=0, uint8_t instance=0) | |
| Constructor. More... | |
| SubscriptionInterval () | |
| ~SubscriptionInterval ()=default | |
| bool | subscribe () |
| bool | advertised () |
| bool | updated () |
| Check if there is a new update. More... | |
| bool | update (void *dst) |
| Copy the struct if updated. More... | |
| bool | copy (void *dst) |
| Copy the struct. More... | |
| bool | valid () const |
| uint8_t | get_instance () const |
| orb_id_t | get_topic () const |
| void | set_interval_us (uint32_t interval) |
| Set the interval in microseconds. More... | |
| void | set_interval_ms (uint32_t interval) |
| Set the interval in milliseconds. More... | |
Protected Attributes | |
| Subscription | _subscription |
| uint64_t | _last_update {0} |
| uint32_t | _interval_us {0} |
Definition at line 54 of file SubscriptionInterval.hpp.
|
inline |
Constructor.
| meta | The uORB metadata (usually from the ORB_ID() macro) for the topic. |
| interval | The requested maximum update interval in microseconds. |
| instance | The instance for multi sub. |
Definition at line 65 of file SubscriptionInterval.hpp.
References _interval_us, and ll40ls::instance.
|
inline |
Definition at line 70 of file SubscriptionInterval.hpp.
References ~SubscriptionInterval().
|
default |
|
inline |
Definition at line 76 of file SubscriptionInterval.hpp.
References _subscription, and uORB::Subscription::advertised().
Referenced by updated().
|
inline |
Copy the struct.
| dst | The destination pointer where the struct will be copied. |
Definition at line 109 of file SubscriptionInterval.hpp.
References _last_update, _subscription, uORB::Subscription::copy(), and hrt_absolute_time().
Referenced by px4::logger::Logger::copy_if_updated(), VehicleAcceleration::Run(), VehicleAngularVelocity::Run(), VehicleAngularVelocity::SensorCorrectionsUpdate(), and update().
|
inline |
Definition at line 121 of file SubscriptionInterval.hpp.
References _subscription, and uORB::Subscription::get_instance().
Referenced by px4::logger::Logger::write_add_logged_msg().
|
inline |
Definition at line 122 of file SubscriptionInterval.hpp.
References _subscription, and uORB::Subscription::get_topic().
Referenced by px4::logger::Logger::write_add_logged_msg(), and px4::logger::Logger::write_formats().
|
inline |
Set the interval in milliseconds.
| interval | The interval in milliseconds. |
Definition at line 134 of file SubscriptionInterval.hpp.
References _interval_us.
Referenced by BlockLocalPositionEstimator::BlockLocalPositionEstimator(), and FixedwingPositionControl::FixedwingPositionControl().
|
inline |
Set the interval in microseconds.
| interval | The interval in microseconds. |
Definition at line 128 of file SubscriptionInterval.hpp.
References _interval_us.
Referenced by MulticopterPositionControl::init(), and MixingOutput::setMaxTopicUpdateRate().
|
inline |
Definition at line 74 of file SubscriptionInterval.hpp.
References _subscription, and uORB::Subscription::subscribe().
Referenced by px4::logger::Logger::copy_if_updated().
|
inline |
Copy the struct if updated.
| dst | The destination pointer where the struct will be copied. |
Definition at line 95 of file SubscriptionInterval.hpp.
References copy(), and updated().
Referenced by px4::logger::Logger::copy_if_updated(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), AttitudeEstimatorQ::Run(), FixedwingAttitudeControl::Run(), MulticopterPositionControl::Run(), VtolAttitudeControl::Run(), Ekf2::Run(), px4::logger::Logger::run(), FixedwingPositionControl::Run(), and BlockLocalPositionEstimator::Run().
|
inline |
Check if there is a new update.
Definition at line 81 of file SubscriptionInterval.hpp.
References _interval_us, _last_update, _subscription, advertised(), hrt_elapsed_time(), and uORB::Subscription::updated().
Referenced by VehicleAngularVelocity::SensorCorrectionsUpdate(), and update().
|
inline |
Definition at line 119 of file SubscriptionInterval.hpp.
References _subscription, and uORB::Subscription::valid().
Referenced by px4::logger::Logger::copy_if_updated(), and px4::logger::Logger::write_all_add_logged_msg().
|
protected |
Definition at line 140 of file SubscriptionInterval.hpp.
Referenced by uORB::SubscriptionCallbackWorkItem::call(), set_interval_ms(), set_interval_us(), SubscriptionInterval(), and updated().
|
protected |
Definition at line 139 of file SubscriptionInterval.hpp.
Referenced by uORB::SubscriptionCallbackWorkItem::call(), copy(), and updated().
|
protected |
Definition at line 138 of file SubscriptionInterval.hpp.
Referenced by advertised(), copy(), get_instance(), get_topic(), uORB::SubscriptionCallback::registerCallback(), subscribe(), uORB::SubscriptionCallback::unregisterCallback(), updated(), and valid().