Browse Source

PreFlightCheck: add checks for CPU and RAM load

sbg
Matthias Grob 5 years ago committed by Julian Oes
parent
commit
8b76c0c023
  1. 1
      ROMFS/px4fmu_common/init.d-posix/rcS
  2. 1
      src/modules/commander/Arming/PreFlightCheck/CMakeLists.txt
  3. 1
      src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.cpp
  4. 1
      src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.hpp
  5. 76
      src/modules/commander/Arming/PreFlightCheck/checks/cpuResourceCheck.cpp
  6. 13
      src/modules/commander/commander_params.c

1
ROMFS/px4fmu_common/init.d-posix/rcS

@ -186,6 +186,7 @@ then @@ -186,6 +186,7 @@ then
param set TRIG_INTERFACE 3
param set COM_CPU_MAX -1
fi
# Adapt timeout parameters if simulation runs faster or slower than realtime.

1
src/modules/commander/Arming/PreFlightCheck/CMakeLists.txt

@ -47,6 +47,7 @@ px4_add_library(PreFlightCheck @@ -47,6 +47,7 @@ px4_add_library(PreFlightCheck
checks/ekf2Check.cpp
checks/failureDetectorCheck.cpp
checks/manualControlCheck.cpp
checks/cpuResourceCheck.cpp
)
target_include_directories(PreFlightCheck PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_link_libraries(PreFlightCheck PUBLIC ArmAuthorization HealthFlags)

1
src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.cpp

@ -298,6 +298,7 @@ bool PreFlightCheck::preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_statu @@ -298,6 +298,7 @@ bool PreFlightCheck::preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_statu
}
failed = failed || !manualControlCheck(mavlink_log_pub, reportFailures);
failed = failed || !cpuResourceCheck(mavlink_log_pub, reportFailures);
/* Report status */
return !failed;

1
src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.hpp

@ -115,4 +115,5 @@ private: @@ -115,4 +115,5 @@ private:
static bool check_calibration(const char *param_template, const int32_t device_id);
static bool manualControlCheck(orb_advert_t *mavlink_log_pub, const bool report_fail);
static bool airframeCheck(orb_advert_t *mavlink_log_pub, const vehicle_status_s &status);
static bool cpuResourceCheck(orb_advert_t *mavlink_log_pub, const bool report_fail);
};

76
src/modules/commander/Arming/PreFlightCheck/checks/cpuResourceCheck.cpp

@ -0,0 +1,76 @@ @@ -0,0 +1,76 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "../PreFlightCheck.hpp"
#include <drivers/drv_hrt.h>
#include <systemlib/mavlink_log.h>
#include <lib/parameters/param.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/cpuload.h>
using namespace time_literals;
bool PreFlightCheck::cpuResourceCheck(orb_advert_t *mavlink_log_pub, const bool report_fail)
{
bool success = true;
uORB::SubscriptionData<cpuload_s> cpuload_sub{ORB_ID(cpuload)};
cpuload_sub.update();
float cpuload_percent_max;
param_get(param_find("COM_CPU_MAX"), &cpuload_percent_max);
if (cpuload_percent_max > 0.f) {
if (hrt_elapsed_time(&cpuload_sub.get().timestamp) > 2_s) {
success = false;
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "Fail: No CPU load information");
}
}
const float cpuload_percent = cpuload_sub.get().load * 100.f;
if (cpuload_percent > cpuload_percent_max) {
success = false;
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "Fail: CPU load too high: %3.1f%%", (double)cpuload_percent);
}
}
}
return success;
}

13
src/modules/commander/commander_params.c

@ -899,3 +899,16 @@ PARAM_DEFINE_INT32(COM_MOT_TEST_EN, 1); @@ -899,3 +899,16 @@ PARAM_DEFINE_INT32(COM_MOT_TEST_EN, 1);
* @increment 0.1
*/
PARAM_DEFINE_FLOAT(COM_KILL_DISARM, 5.0f);
/**
* Maximum allowed CPU load to still allow arming
*
* A negative value disables the check.
*
* @group Commander
* @unit %
* @min -1
* @max 100
* @increment 1
*/
PARAM_DEFINE_FLOAT(COM_CPU_MAX, 90.0f);

Loading…
Cancel
Save