2016-02-26 18:03:18 -08:00
|
|
|
/****************************************************************************
|
|
|
|
|
*
|
|
|
|
|
* Copyright (c) 2012-2016 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.
|
|
|
|
|
*
|
|
|
|
|
****************************************************************************/
|
|
|
|
|
|
|
|
|
|
/**
|
2016-04-29 09:57:59 +02:00
|
|
|
* @file load_mon.cpp
|
2016-02-26 18:03:18 -08:00
|
|
|
*
|
|
|
|
|
* @author Jonathan Challinger <jonathan@3drobotics.com>
|
2016-04-29 14:29:31 +02:00
|
|
|
* @author Julian Oes <julian@oes.ch
|
2016-11-21 14:30:51 +01:00
|
|
|
* @author Andreas Antener <andreas@uaventure.com>
|
2016-02-26 18:03:18 -08:00
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
#include <stdio.h>
|
|
|
|
|
#include <stdlib.h>
|
|
|
|
|
#include <string.h>
|
|
|
|
|
#include <unistd.h>
|
|
|
|
|
|
|
|
|
|
#include <px4_config.h>
|
2016-04-29 14:29:31 +02:00
|
|
|
#include <px4_workqueue.h>
|
2016-05-11 16:51:55 +02:00
|
|
|
#include <px4_defines.h>
|
2016-02-26 18:03:18 -08:00
|
|
|
|
|
|
|
|
#include <drivers/drv_hrt.h>
|
|
|
|
|
|
|
|
|
|
#include <systemlib/systemlib.h>
|
|
|
|
|
#include <systemlib/err.h>
|
|
|
|
|
#include <systemlib/cpuload.h>
|
2016-12-04 18:27:44 +01:00
|
|
|
#include <systemlib/perf_counter.h>
|
2016-02-26 18:03:18 -08:00
|
|
|
|
|
|
|
|
#include <uORB/uORB.h>
|
|
|
|
|
#include <uORB/topics/cpuload.h>
|
2016-11-21 14:30:51 +01:00
|
|
|
#include <uORB/topics/low_stack.h>
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
extern struct system_load_s system_load;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
namespace load_mon
|
|
|
|
|
{
|
2016-02-26 18:03:18 -08:00
|
|
|
|
|
|
|
|
extern "C" __EXPORT int load_mon_main(int argc, char *argv[]);
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
// Run it at 1 Hz.
|
|
|
|
|
const unsigned LOAD_MON_INTERVAL_US = 1000000;
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
class LoadMon
|
|
|
|
|
{
|
|
|
|
|
public:
|
|
|
|
|
LoadMon();
|
|
|
|
|
~LoadMon();
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
/* Start the load monitoring
|
|
|
|
|
*
|
|
|
|
|
* @return 0 if successfull, -1 on error. */
|
|
|
|
|
int start();
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
/* Stop the load monitoring */
|
|
|
|
|
void stop();
|
|
|
|
|
|
|
|
|
|
/* Trampoline for the work queue. */
|
|
|
|
|
static void cycle_trampoline(void *arg);
|
|
|
|
|
|
|
|
|
|
bool isRunning() { return _taskIsRunning; }
|
|
|
|
|
|
2016-12-04 18:27:44 +01:00
|
|
|
void printStatus();
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
private:
|
|
|
|
|
/* Do a compute and schedule the next cycle. */
|
|
|
|
|
void _cycle();
|
|
|
|
|
|
|
|
|
|
/* Do a calculation of the CPU load and publish it. */
|
|
|
|
|
void _compute();
|
|
|
|
|
|
2016-08-15 14:53:48 +02:00
|
|
|
/* Calculate the memory usage */
|
|
|
|
|
float _ram_used();
|
|
|
|
|
|
2016-11-21 14:30:51 +01:00
|
|
|
#ifdef __PX4_NUTTX
|
|
|
|
|
/* Calculate stack usage */
|
|
|
|
|
void _stack_usage();
|
|
|
|
|
|
|
|
|
|
struct low_stack_s _low_stack;
|
|
|
|
|
int _stack_task_index;
|
|
|
|
|
orb_advert_t _low_stack_pub;
|
|
|
|
|
#endif
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
bool _taskShouldExit;
|
|
|
|
|
bool _taskIsRunning;
|
|
|
|
|
struct work_s _work;
|
|
|
|
|
|
|
|
|
|
struct cpuload_s _cpuload;
|
|
|
|
|
orb_advert_t _cpuload_pub;
|
|
|
|
|
hrt_abstime _last_idle_time;
|
2016-12-04 18:27:44 +01:00
|
|
|
perf_counter_t _stack_perf;
|
2016-12-04 19:05:57 +01:00
|
|
|
bool _stack_check_enabled;
|
2016-04-29 14:29:31 +02:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
LoadMon::LoadMon() :
|
2016-11-21 14:30:51 +01:00
|
|
|
#ifdef __PX4_NUTTX
|
|
|
|
|
_low_stack {},
|
|
|
|
|
_stack_task_index(0),
|
|
|
|
|
_low_stack_pub(nullptr),
|
|
|
|
|
#endif
|
2016-04-29 14:29:31 +02:00
|
|
|
_taskShouldExit(false),
|
|
|
|
|
_taskIsRunning(false),
|
|
|
|
|
_work{},
|
|
|
|
|
_cpuload{},
|
|
|
|
|
_cpuload_pub(nullptr),
|
2016-12-04 18:27:44 +01:00
|
|
|
_last_idle_time(0),
|
2016-12-04 19:05:57 +01:00
|
|
|
_stack_perf(perf_alloc(PC_ELAPSED, "stack_check")),
|
|
|
|
|
_stack_check_enabled(false)
|
|
|
|
|
{
|
2016-12-12 09:49:36 +01:00
|
|
|
// Enable stack checking by param
|
|
|
|
|
param_t param_stack_check = param_find("SYS_STCK_EN");
|
|
|
|
|
|
|
|
|
|
if (param_stack_check != PARAM_INVALID) {
|
|
|
|
|
int ret_val = 0;
|
|
|
|
|
param_get(param_stack_check, &ret_val);
|
|
|
|
|
_stack_check_enabled = ret_val > 0;
|
|
|
|
|
|
|
|
|
|
// Only be verbose if enabled
|
|
|
|
|
if (_stack_check_enabled) {
|
|
|
|
|
PX4_INFO("stack check enabled");
|
|
|
|
|
}
|
|
|
|
|
}
|
2016-12-04 19:05:57 +01:00
|
|
|
}
|
2016-04-29 14:29:31 +02:00
|
|
|
|
|
|
|
|
LoadMon::~LoadMon()
|
2016-02-26 18:03:18 -08:00
|
|
|
{
|
2016-11-21 14:30:51 +01:00
|
|
|
work_cancel(LPWORK, &_work);
|
2016-12-04 18:56:28 +01:00
|
|
|
perf_free(_stack_perf);
|
2016-04-29 14:29:31 +02:00
|
|
|
_taskIsRunning = false;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
int LoadMon::start()
|
|
|
|
|
{
|
|
|
|
|
/* Schedule a cycle to start things. */
|
2016-11-21 14:30:51 +01:00
|
|
|
return work_queue(LPWORK, &_work, (worker_t)&LoadMon::cycle_trampoline, this, 0);
|
2016-04-29 14:29:31 +02:00
|
|
|
}
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
void LoadMon::stop()
|
|
|
|
|
{
|
|
|
|
|
_taskShouldExit = true;
|
|
|
|
|
}
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
void
|
|
|
|
|
LoadMon::cycle_trampoline(void *arg)
|
|
|
|
|
{
|
|
|
|
|
LoadMon *dev = reinterpret_cast<LoadMon *>(arg);
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
dev->_cycle();
|
|
|
|
|
}
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
void LoadMon::_cycle()
|
|
|
|
|
{
|
|
|
|
|
_taskIsRunning = true;
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
_compute();
|
|
|
|
|
|
|
|
|
|
if (!_taskShouldExit) {
|
2016-11-21 14:30:51 +01:00
|
|
|
work_queue(LPWORK, &_work, (worker_t)&LoadMon::cycle_trampoline, this,
|
2016-04-29 14:29:31 +02:00
|
|
|
USEC2TICK(LOAD_MON_INTERVAL_US));
|
2016-02-26 18:03:18 -08:00
|
|
|
}
|
2016-04-29 14:29:31 +02:00
|
|
|
}
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
void LoadMon::_compute()
|
|
|
|
|
{
|
|
|
|
|
if (_last_idle_time == 0) {
|
|
|
|
|
/* Just get the time in the first iteration */
|
|
|
|
|
_last_idle_time = system_load.tasks[0].total_runtime;
|
|
|
|
|
return;
|
|
|
|
|
}
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
/* compute system load */
|
|
|
|
|
const hrt_abstime interval_idletime = system_load.tasks[0].total_runtime - _last_idle_time;
|
|
|
|
|
_last_idle_time = system_load.tasks[0].total_runtime;
|
2016-02-26 18:03:18 -08:00
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
_cpuload.timestamp = hrt_absolute_time();
|
|
|
|
|
_cpuload.load = 1.0f - (float)interval_idletime / (float)LOAD_MON_INTERVAL_US;
|
2016-08-15 14:53:48 +02:00
|
|
|
_cpuload.ram_usage = _ram_used();
|
2016-04-29 14:29:31 +02:00
|
|
|
|
2016-11-21 14:30:51 +01:00
|
|
|
#ifdef __PX4_NUTTX
|
2016-12-04 19:05:57 +01:00
|
|
|
|
|
|
|
|
if (_stack_check_enabled) {
|
|
|
|
|
_stack_usage();
|
|
|
|
|
}
|
|
|
|
|
|
2016-11-21 14:30:51 +01:00
|
|
|
#endif
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
if (_cpuload_pub == nullptr) {
|
|
|
|
|
_cpuload_pub = orb_advertise(ORB_ID(cpuload), &_cpuload);
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
orb_publish(ORB_ID(cpuload), _cpuload_pub, &_cpuload);
|
|
|
|
|
}
|
2016-02-26 18:03:18 -08:00
|
|
|
}
|
|
|
|
|
|
2016-08-15 14:53:48 +02:00
|
|
|
float LoadMon::_ram_used()
|
|
|
|
|
{
|
2016-08-15 14:54:27 +02:00
|
|
|
#ifdef __PX4_NUTTX
|
2016-08-15 14:53:48 +02:00
|
|
|
struct mallinfo mem;
|
|
|
|
|
|
|
|
|
|
#ifdef CONFIG_CAN_PASS_STRUCTS
|
|
|
|
|
mem = mallinfo();
|
|
|
|
|
#else
|
|
|
|
|
(void)mallinfo(&mem);
|
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
// mem.arena: total ram (bytes)
|
|
|
|
|
// mem.uordblks: used (bytes)
|
|
|
|
|
// mem.fordblks: free (bytes)
|
|
|
|
|
// mem.mxordblk: largest remaining block (bytes)
|
2016-04-29 14:29:31 +02:00
|
|
|
|
2016-08-15 14:53:48 +02:00
|
|
|
float load = (float)mem.uordblks / mem.arena;
|
|
|
|
|
|
|
|
|
|
// Check for corruption of the allocation counters
|
2016-12-12 15:04:44 -10:00
|
|
|
if ((mem.arena > CONFIG_RAM_SIZE) || (mem.fordblks > CONFIG_RAM_SIZE)) {
|
2016-08-15 14:54:27 +02:00
|
|
|
load = 1.0f;
|
2016-08-15 14:53:48 +02:00
|
|
|
}
|
2016-08-15 14:54:27 +02:00
|
|
|
|
|
|
|
|
return load;
|
2016-08-15 14:53:48 +02:00
|
|
|
#else
|
|
|
|
|
return 0.0f;
|
|
|
|
|
#endif
|
|
|
|
|
}
|
2016-04-29 14:29:31 +02:00
|
|
|
|
2016-11-21 14:30:51 +01:00
|
|
|
#ifdef __PX4_NUTTX
|
|
|
|
|
void LoadMon::_stack_usage()
|
|
|
|
|
{
|
2016-12-04 18:04:35 +01:00
|
|
|
int task_index = 0;
|
|
|
|
|
|
|
|
|
|
/* Scan maximum 3 tasks per cycle to reduce load. */
|
|
|
|
|
for (int i = _stack_task_index; i < _stack_task_index + 3; i++) {
|
|
|
|
|
task_index = i % CONFIG_MAX_TASKS;
|
2016-12-07 19:58:13 +01:00
|
|
|
unsigned stack_free = 0;
|
|
|
|
|
bool checked_task = false;
|
|
|
|
|
|
|
|
|
|
perf_begin(_stack_perf);
|
|
|
|
|
sched_lock();
|
2016-12-04 18:04:35 +01:00
|
|
|
|
|
|
|
|
if (system_load.tasks[task_index].valid && system_load.tasks[task_index].tcb->pid > 0) {
|
|
|
|
|
unsigned stack_size = (uintptr_t)system_load.tasks[task_index].tcb->adj_stack_ptr -
|
|
|
|
|
(uintptr_t)system_load.tasks[task_index].tcb->stack_alloc_ptr;
|
2016-12-07 19:58:13 +01:00
|
|
|
|
2016-12-04 18:04:35 +01:00
|
|
|
uint8_t *stack_sweeper = (uint8_t *)system_load.tasks[task_index].tcb->stack_alloc_ptr;
|
2016-11-21 14:30:51 +01:00
|
|
|
|
|
|
|
|
while (stack_free < stack_size) {
|
|
|
|
|
if (*stack_sweeper++ != 0xff) {
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
stack_free++;
|
|
|
|
|
}
|
|
|
|
|
|
2016-12-07 19:58:13 +01:00
|
|
|
checked_task = true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
sched_unlock();
|
|
|
|
|
perf_end(_stack_perf);
|
|
|
|
|
|
|
|
|
|
if (checked_task) {
|
2016-11-21 14:30:51 +01:00
|
|
|
/*
|
|
|
|
|
* Found task low on stack, report and exit. Continue here in next cycle.
|
|
|
|
|
*/
|
|
|
|
|
if (stack_free < 300) {
|
2016-12-04 18:04:35 +01:00
|
|
|
strncpy((char *)_low_stack.task_name, system_load.tasks[task_index].tcb->name, low_stack_s::MAX_REPORT_TASK_NAME_LEN);
|
2016-11-21 14:30:51 +01:00
|
|
|
_low_stack.stack_free = stack_free;
|
|
|
|
|
|
|
|
|
|
if (_low_stack_pub == nullptr) {
|
|
|
|
|
_low_stack_pub = orb_advertise(ORB_ID(low_stack), &_low_stack);
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
orb_publish(ORB_ID(low_stack), _low_stack_pub, &_low_stack);
|
|
|
|
|
}
|
|
|
|
|
|
2016-12-04 18:04:35 +01:00
|
|
|
break;
|
2016-11-21 14:30:51 +01:00
|
|
|
}
|
2016-12-04 18:04:35 +01:00
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
/* No task here, check one more task in same cycle. */
|
|
|
|
|
_stack_task_index++;
|
2016-11-21 14:30:51 +01:00
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2016-12-04 18:04:35 +01:00
|
|
|
/* Continue after last checked task next cycle. */
|
|
|
|
|
_stack_task_index = task_index + 1;
|
2016-11-21 14:30:51 +01:00
|
|
|
}
|
|
|
|
|
#endif
|
|
|
|
|
|
2016-12-04 18:27:44 +01:00
|
|
|
void LoadMon::printStatus()
|
|
|
|
|
{
|
|
|
|
|
perf_print_counter(_stack_perf);
|
|
|
|
|
}
|
|
|
|
|
|
2016-02-26 18:03:18 -08:00
|
|
|
/**
|
|
|
|
|
* Print the correct usage.
|
|
|
|
|
*/
|
|
|
|
|
static void usage(const char *reason);
|
|
|
|
|
|
|
|
|
|
static void
|
|
|
|
|
usage(const char *reason)
|
|
|
|
|
{
|
|
|
|
|
if (reason) {
|
2016-04-29 14:29:31 +02:00
|
|
|
PX4_ERR("%s", reason);
|
2016-02-26 18:03:18 -08:00
|
|
|
}
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
PX4_INFO("usage: load_mon {start|stop|status}");
|
2016-02-26 18:03:18 -08:00
|
|
|
}
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
|
|
|
|
|
static LoadMon *load_mon = nullptr;
|
|
|
|
|
|
2016-02-26 18:03:18 -08:00
|
|
|
/**
|
|
|
|
|
* The daemon app only briefly exists to start
|
|
|
|
|
* the background job. The stack size assigned in the
|
|
|
|
|
* Makefile does only apply to this management task.
|
|
|
|
|
*
|
|
|
|
|
* The actual stack size should be set in the call
|
|
|
|
|
* to task_create().
|
|
|
|
|
*/
|
|
|
|
|
int load_mon_main(int argc, char *argv[])
|
|
|
|
|
{
|
|
|
|
|
if (argc < 2) {
|
|
|
|
|
usage("missing command");
|
|
|
|
|
return 1;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (!strcmp(argv[1], "start")) {
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
if (load_mon != nullptr && load_mon->isRunning()) {
|
|
|
|
|
PX4_WARN("already running");
|
2016-02-26 18:03:18 -08:00
|
|
|
/* this is not an error */
|
|
|
|
|
return 0;
|
|
|
|
|
}
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
load_mon = new LoadMon();
|
|
|
|
|
|
|
|
|
|
// Check if alloc worked.
|
|
|
|
|
if (load_mon == nullptr) {
|
|
|
|
|
PX4_ERR("alloc failed");
|
|
|
|
|
return -1;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
int ret = load_mon->start();
|
|
|
|
|
|
|
|
|
|
if (ret != 0) {
|
|
|
|
|
PX4_ERR("start failed");
|
|
|
|
|
}
|
|
|
|
|
|
2016-02-26 18:03:18 -08:00
|
|
|
return 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (!strcmp(argv[1], "stop")) {
|
2016-04-29 14:29:31 +02:00
|
|
|
|
|
|
|
|
if (load_mon == nullptr || load_mon->isRunning()) {
|
|
|
|
|
PX4_WARN("not running");
|
|
|
|
|
/* this is not an error */
|
|
|
|
|
return 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
load_mon->stop();
|
|
|
|
|
|
|
|
|
|
// Wait for task to die
|
|
|
|
|
int i = 0;
|
|
|
|
|
|
|
|
|
|
do {
|
|
|
|
|
/* wait up to 3s */
|
|
|
|
|
usleep(100000);
|
|
|
|
|
|
|
|
|
|
} while (load_mon->isRunning() && ++i < 30);
|
|
|
|
|
|
|
|
|
|
delete load_mon;
|
|
|
|
|
load_mon = nullptr;
|
|
|
|
|
|
2016-02-26 18:03:18 -08:00
|
|
|
return 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (!strcmp(argv[1], "status")) {
|
2016-04-29 14:29:31 +02:00
|
|
|
if (load_mon != nullptr && load_mon->isRunning()) {
|
|
|
|
|
PX4_INFO("running");
|
2016-12-04 18:27:44 +01:00
|
|
|
load_mon->printStatus();
|
2016-04-29 14:29:31 +02:00
|
|
|
|
2016-02-26 18:03:18 -08:00
|
|
|
} else {
|
2016-04-29 14:29:31 +02:00
|
|
|
PX4_INFO("not running\n");
|
2016-02-26 18:03:18 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
usage("unrecognized command");
|
|
|
|
|
return 1;
|
|
|
|
|
}
|
|
|
|
|
|
2016-04-29 14:29:31 +02:00
|
|
|
} // namespace load_mon
|