mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
fix(modules): make daemon command probes responsive
External daemon clients commonly call module status or stop verbs and expect an immediate reply. Teach the example modules to handle those verbs without entering long demo loops, and move px4_mavlink_debug publishing onto a background task so start returns after the task is spawned. Also reject stray positional arguments for shutdown and sd_bench. Without that guard a mistyped client command could accidentally shut down the daemon or run a multi-second benchmark when the caller only meant to query status. Signed-off-by: Nuno Marques <n.marques21@hotmail.com>
This commit is contained in:
@@ -44,9 +44,21 @@ void list_builtins(apps_map_type &apps)
|
||||
|
||||
int shutdown_main(int argc, char *argv[])
|
||||
{
|
||||
// Reject any leftover positional arguments (e.g. "status", "start", "stop").
|
||||
// shutdown takes no flags or subcommands -- it always tears the daemon
|
||||
// down -- so silently ignoring extra args would terminate the daemon when
|
||||
// the user almost certainly meant a different module (e.g.
|
||||
// "<module> status"). Print usage and exit non-zero instead.
|
||||
if (argc > 1) {
|
||||
PX4_ERR("unrecognized argument: %s", argv[1]);
|
||||
printf("Usage:\n shutdown\n");
|
||||
return 1;
|
||||
}
|
||||
|
||||
printf("Exiting NOW.\n");
|
||||
uorb_shutdown();
|
||||
px4_platform_exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int list_tasks_main(int argc, char *argv[])
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2026 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
|
||||
@@ -39,6 +39,10 @@
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <atomic>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
@@ -55,40 +59,58 @@
|
||||
|
||||
extern "C" __EXPORT int px4_mavlink_debug_main(int argc, char *argv[]);
|
||||
|
||||
int px4_mavlink_debug_main(int argc, char *argv[])
|
||||
namespace
|
||||
{
|
||||
printf("Hello Debug!\n");
|
||||
|
||||
// Track liveness of the background publisher so `status`/`stop` can report
|
||||
// the right state without blocking the daemon. The publisher loop runs on a
|
||||
// task spawned by `start`; the daemon's per-client thread returns
|
||||
// immediately so the client connection is not held open for the lifetime of
|
||||
// the loop. Without this split, `start` blocked the IPC socket for the full
|
||||
// 50 s loop, and `status` had to be a bare printf because there was no
|
||||
// long-lived task to query.
|
||||
std::atomic<bool> g_running{false};
|
||||
std::atomic<bool> g_exit_requested{false};
|
||||
|
||||
int publisher_thread_main(int argc, char *argv[])
|
||||
{
|
||||
(void)argc;
|
||||
(void)argv;
|
||||
|
||||
g_running.store(true);
|
||||
|
||||
PX4_INFO("Hello Debug!");
|
||||
|
||||
/* advertise named debug value */
|
||||
struct debug_key_value_s dbg_key;
|
||||
strncpy(dbg_key.key, "velx", 10);
|
||||
struct debug_key_value_s dbg_key {};
|
||||
strncpy(dbg_key.key, "velx", sizeof(dbg_key.key));
|
||||
dbg_key.value = 0.0f;
|
||||
orb_advert_t pub_dbg_key = orb_advertise(ORB_ID(debug_key_value), &dbg_key);
|
||||
|
||||
/* advertise indexed debug value */
|
||||
struct debug_value_s dbg_ind;
|
||||
struct debug_value_s dbg_ind {};
|
||||
dbg_ind.ind = 42;
|
||||
dbg_ind.value = 0.5f;
|
||||
orb_advert_t pub_dbg_ind = orb_advertise(ORB_ID(debug_value), &dbg_ind);
|
||||
|
||||
/* advertise debug vect */
|
||||
struct debug_vect_s dbg_vect;
|
||||
strncpy(dbg_vect.name, "vel3D", 10);
|
||||
struct debug_vect_s dbg_vect {};
|
||||
strncpy(dbg_vect.name, "vel3D", sizeof(dbg_vect.name));
|
||||
dbg_vect.x = 1.0f;
|
||||
dbg_vect.y = 2.0f;
|
||||
dbg_vect.z = 3.0f;
|
||||
orb_advert_t pub_dbg_vect = orb_advertise(ORB_ID(debug_vect), &dbg_vect);
|
||||
|
||||
/* advertise debug array */
|
||||
struct debug_array_s dbg_array;
|
||||
struct debug_array_s dbg_array {};
|
||||
dbg_array.id = 1;
|
||||
strncpy(dbg_array.name, "dbg_array", 10);
|
||||
strncpy(dbg_array.name, "dbg_array", sizeof(dbg_array.name));
|
||||
orb_advert_t pub_dbg_array = orb_advertise(ORB_ID(debug_array), &dbg_array);
|
||||
|
||||
int value_counter = 0;
|
||||
|
||||
while (value_counter < 100) {
|
||||
uint64_t timestamp_us = hrt_absolute_time();
|
||||
while (!g_exit_requested.load() && value_counter < 100) {
|
||||
const uint64_t timestamp_us = hrt_absolute_time();
|
||||
|
||||
/* send one named value */
|
||||
dbg_key.value = value_counter;
|
||||
@@ -115,11 +137,88 @@ int px4_mavlink_debug_main(int argc, char *argv[])
|
||||
dbg_array.timestamp = timestamp_us;
|
||||
orb_publish(ORB_ID(debug_array), pub_dbg_array, &dbg_array);
|
||||
|
||||
warnx("sent one more value..");
|
||||
PX4_DEBUG("sent one more value..");
|
||||
|
||||
value_counter++;
|
||||
px4_usleep(500000);
|
||||
}
|
||||
|
||||
g_running.store(false);
|
||||
g_exit_requested.store(false);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void usage(const char *reason)
|
||||
{
|
||||
if (reason != nullptr) {
|
||||
printf("%s\n", reason);
|
||||
}
|
||||
|
||||
printf("usage: px4_mavlink_debug {start|stop|status}\n");
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
int px4_mavlink_debug_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2) {
|
||||
usage("missing command");
|
||||
return 1;
|
||||
}
|
||||
|
||||
const char *verb = argv[1];
|
||||
|
||||
if (strcmp(verb, "start") == 0) {
|
||||
if (g_running.load()) {
|
||||
PX4_INFO("already running");
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Clear any prior exit request so a re-`start` after a `stop`
|
||||
// runs to completion.
|
||||
g_exit_requested.store(false);
|
||||
|
||||
// Spawn the publisher loop on its own task so the daemon's
|
||||
// per-client thread can return immediately. Otherwise the IPC
|
||||
// socket would stay open for the full ~50 s loop and the
|
||||
// invoking client (`pxh`, `px4-px4_mavlink_debug.exe`, etc.)
|
||||
// would appear to hang.
|
||||
const px4_task_t task = px4_task_spawn_cmd("px4_mavlink_debug",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2000,
|
||||
publisher_thread_main,
|
||||
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
|
||||
|
||||
if (task < 0) {
|
||||
PX4_ERR("task spawn failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (strcmp(verb, "stop") == 0) {
|
||||
if (!g_running.load()) {
|
||||
PX4_INFO("not running");
|
||||
return 0;
|
||||
}
|
||||
|
||||
g_exit_requested.store(true);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (strcmp(verb, "status") == 0) {
|
||||
if (g_running.load()) {
|
||||
PX4_INFO("running: publishing 100 sample debug values at 2 Hz");
|
||||
|
||||
} else {
|
||||
PX4_INFO("not running");
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
return 1;
|
||||
}
|
||||
|
||||
@@ -56,6 +56,30 @@ __EXPORT int px4_simple_app_main(int argc, char *argv[]);
|
||||
|
||||
int px4_simple_app_main(int argc, char *argv[])
|
||||
{
|
||||
/* Handle simple command verbs without entering the polling loop. The
|
||||
* loop below blocks for ~5 s waiting for sensor updates, which would
|
||||
* otherwise make `px4-px4_simple_app status` (and similar one-shot
|
||||
* invocations from the pxh shell or external clients) appear to hang
|
||||
* for the full duration of the example. Return immediately for these
|
||||
* commands so callers get a prompt response.
|
||||
*/
|
||||
if (argc > 1) {
|
||||
if (strcmp(argv[1], "status") == 0) {
|
||||
PX4_INFO("not running (this example is a one-shot demo; "
|
||||
"invoke without arguments to run the polling loop)");
|
||||
return 0;
|
||||
|
||||
} else if (strcmp(argv[1], "stop") == 0) {
|
||||
/* Nothing to stop — the example is not a long-running task. */
|
||||
return 0;
|
||||
|
||||
} else if (strcmp(argv[1], "help") == 0 || strcmp(argv[1], "-h") == 0) {
|
||||
PX4_INFO("usage: px4_simple_app [status|stop|help]");
|
||||
PX4_INFO(" no args: run a short demo loop (5 iterations, ~5 s)");
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
PX4_INFO("Hello Sky!");
|
||||
|
||||
/* subscribe to vehicle_acceleration topic */
|
||||
|
||||
@@ -146,6 +146,17 @@ extern "C" __EXPORT int sd_bench_main(int argc, char *argv[])
|
||||
}
|
||||
}
|
||||
|
||||
// Reject any leftover positional arguments (e.g. "status", "start", "stop").
|
||||
// sd_bench has no subcommands -- it only accepts the flags handled above --
|
||||
// so silently ignoring extra args would run a multi-second benchmark when
|
||||
// the user almost certainly meant a different module. Print usage and exit
|
||||
// non-zero instead.
|
||||
if (myoptind < argc) {
|
||||
PX4_ERR("unrecognized argument: %s", argv[myoptind]);
|
||||
usage();
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (block_size <= 0 || cfg.num_runs <= 0) {
|
||||
PX4_ERR("invalid argument");
|
||||
return -1;
|
||||
|
||||
Reference in New Issue
Block a user