Browse Source

AP_Periph: node stats

- Added new config parameter object - STAT
 - init and update statistics
apm_2208
Pradeep 3 years ago committed by Andrew Tridgell
parent
commit
80e2533cf0
  1. 8
      Tools/AP_Periph/AP_Periph.cpp
  2. 5
      Tools/AP_Periph/AP_Periph.h
  3. 6
      Tools/AP_Periph/Parameters.cpp
  4. 1
      Tools/AP_Periph/Parameters.h

8
Tools/AP_Periph/AP_Periph.cpp

@ -142,6 +142,10 @@ void AP_Periph_FW::init() @@ -142,6 +142,10 @@ void AP_Periph_FW::init()
printf("Reboot after watchdog reset\n");
}
#if AP_STATS_ENABLED
node_stats.init();
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) {
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD);
@ -331,6 +335,10 @@ void AP_Periph_FW::show_stack_free() @@ -331,6 +335,10 @@ void AP_Periph_FW::show_stack_free()
void AP_Periph_FW::update()
{
#if AP_STATS_ENABLED
node_stats.update();
#endif
static uint32_t last_led_ms;
uint32_t now = AP_HAL::native_millis();
if (now - last_led_ms > 1000) {

5
Tools/AP_Periph/AP_Periph.h

@ -18,6 +18,7 @@ @@ -18,6 +18,7 @@
#include <AP_CANManager/AP_CANManager.h>
#include <AP_Scripting/AP_Scripting.h>
#include <AP_HAL/CANIface.h>
#include <AP_Stats/AP_Stats.h>
#if HAL_GCS_ENABLED
#include "GCS_MAVLink.h"
@ -103,6 +104,10 @@ public: @@ -103,6 +104,10 @@ public:
AP_SerialManager serial_manager;
#if AP_STATS_ENABLED
AP_Stats node_stats;
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
AP_GPS gps;
#if HAL_NUM_CAN_IFACES >= 2

6
Tools/AP_Periph/Parameters.cpp

@ -403,6 +403,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { @@ -403,6 +403,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(scripting, "SCR_", AP_Scripting),
#endif
#if AP_STATS_ENABLED
// @Group: Node
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
GOBJECT(node_stats, "STAT", AP_Stats),
#endif
AP_VAREND
};

1
Tools/AP_Periph/Parameters.h

@ -54,6 +54,7 @@ public: @@ -54,6 +54,7 @@ public:
k_param_can_fdmode,
k_param_can_fdbaudrate0,
k_param_can_fdbaudrate1,
k_param_node_stats,
};
AP_Int16 format_version;

Loading…
Cancel
Save