mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-12 23:42:23 +08:00
logger move to uORB::SubscriptionInterval (#12123)
This commit is contained in:
+119
-197
File diff suppressed because it is too large
Load Diff
+16
-31
@@ -83,27 +83,17 @@ inline bool operator&(SDLogProfileMask a, SDLogProfileMask b)
|
||||
return static_cast<int32_t>(a) & static_cast<int32_t>(b);
|
||||
}
|
||||
|
||||
struct LoggerSubscription {
|
||||
int fd[ORB_MULTI_MAX_INSTANCES]; ///< uorb subscription. The first fd is also used to store the interval if
|
||||
/// not subscribed yet (-interval - 1)
|
||||
const orb_metadata *metadata = nullptr;
|
||||
uint8_t msg_ids[ORB_MULTI_MAX_INSTANCES];
|
||||
static constexpr uint8_t MSG_ID_INVALID = UINT8_MAX;
|
||||
|
||||
LoggerSubscription() {}
|
||||
struct LoggerSubscription : public uORB::SubscriptionInterval {
|
||||
|
||||
LoggerSubscription(int fd_, const orb_metadata *metadata_) :
|
||||
metadata(metadata_)
|
||||
{
|
||||
fd[0] = fd_;
|
||||
uint8_t msg_id{MSG_ID_INVALID};
|
||||
|
||||
for (int i = 1; i < ORB_MULTI_MAX_INSTANCES; i++) {
|
||||
fd[i] = -1;
|
||||
}
|
||||
LoggerSubscription() = default;
|
||||
|
||||
for (int i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) {
|
||||
msg_ids[i] = (uint8_t) - 1;
|
||||
}
|
||||
}
|
||||
LoggerSubscription(const orb_metadata *meta, uint32_t interval_ms = 0, uint8_t instance = 0) :
|
||||
uORB::SubscriptionInterval(meta, interval_ms * 1000, instance)
|
||||
{}
|
||||
};
|
||||
|
||||
class Logger : public ModuleBase<Logger>
|
||||
@@ -150,18 +140,19 @@ public:
|
||||
* Add a topic to be logged. This must be called before start_log()
|
||||
* (because it does not write an ADD_LOGGED_MSG message).
|
||||
* @param name topic name
|
||||
* @param interval limit rate if >0, otherwise log as fast as the topic is updated.
|
||||
* @param interval limit in milliseconds if >0, otherwise log as fast as the topic is updated.
|
||||
* @param instance orb topic instance
|
||||
* @return true on success
|
||||
*/
|
||||
bool add_topic(const char *name, unsigned interval = 0);
|
||||
bool add_topic(const char *name, uint32_t interval_ms = 0, uint8_t instance = 0);
|
||||
bool add_topic_multi(const char *name, uint32_t interval_ms = 0);
|
||||
|
||||
/**
|
||||
* add a logged topic (called by add_topic() above).
|
||||
* In addition, it subscribes to the first instance of the topic, if it's advertised,
|
||||
* and sets the file descriptor of LoggerSubscription accordingly
|
||||
* @return the newly added subscription on success, nullptr otherwise
|
||||
*/
|
||||
LoggerSubscription *add_topic(const orb_metadata *topic);
|
||||
LoggerSubscription *add_topic(const orb_metadata *topic, uint32_t interval_ms = 0, uint8_t instance = 0);
|
||||
|
||||
/**
|
||||
* request the logger thread to stop (this method does not block).
|
||||
@@ -181,7 +172,7 @@ private:
|
||||
Watchdog
|
||||
};
|
||||
|
||||
static constexpr size_t MAX_TOPICS_NUM = 64; /**< Maximum number of logged topics */
|
||||
static constexpr size_t MAX_TOPICS_NUM = 90; /**< Maximum number of logged topics */
|
||||
static constexpr int MAX_MISSION_TOPICS_NUM = 5; /**< Maximum number of mission topics */
|
||||
static constexpr unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
|
||||
static constexpr const char *LOG_ROOT[(int)LogType::Count] = {
|
||||
@@ -218,7 +209,7 @@ private:
|
||||
* Write an ADD_LOGGED_MSG to the log for a given subscription and instance.
|
||||
* _writer.lock() must be held when calling this.
|
||||
*/
|
||||
void write_add_logged_msg(LogType type, LoggerSubscription &subscription, int instance);
|
||||
void write_add_logged_msg(LogType type, LoggerSubscription &subscription);
|
||||
|
||||
/**
|
||||
* Create logging directory
|
||||
@@ -301,13 +292,7 @@ private:
|
||||
|
||||
void write_changed_parameters(LogType type);
|
||||
|
||||
inline bool copy_if_updated_multi(int sub_idx, int multi_instance, void *buffer, bool try_to_subscribe);
|
||||
|
||||
/**
|
||||
* Check if a topic instance exists and subscribe to it
|
||||
* @return true when topic exists and subscription successful
|
||||
*/
|
||||
bool try_to_subscribe_topic(LoggerSubscription &sub, int multi_instance);
|
||||
inline bool copy_if_updated(int sub_idx, void *buffer, bool try_to_subscribe);
|
||||
|
||||
/**
|
||||
* Write exactly one ulog message to the logger and handle dropouts.
|
||||
@@ -335,7 +320,7 @@ private:
|
||||
* @param name topic name
|
||||
* @param interval limit rate if >0 [ms], otherwise log as fast as the topic is updated.
|
||||
*/
|
||||
void add_mission_topic(const char *name, unsigned interval = 0);
|
||||
void add_mission_topic(const char *name, uint32_t interval_ms = 0);
|
||||
|
||||
/**
|
||||
* Add topic subscriptions based on the _sdlog_profile_handle parameter
|
||||
|
||||
Reference in New Issue
Block a user