|
|
|
@ -50,90 +50,101 @@
@@ -50,90 +50,101 @@
|
|
|
|
|
#include <cstring> |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* This mutex protects against race conditions during startup & shutdown of modules. |
|
|
|
|
* There could be one mutex per module instantiation, but to reduce the memory footprint |
|
|
|
|
* there is only a single global mutex. This sounds bad, but we actually don't expect |
|
|
|
|
* contention here, as module startup is sequential. |
|
|
|
|
* @brief This mutex protects against race conditions during startup & shutdown of modules. |
|
|
|
|
* There could be one mutex per module instantiation, but to reduce the memory footprint |
|
|
|
|
* there is only a single global mutex. This sounds bad, but we actually don't expect |
|
|
|
|
* contention here, as module startup is sequential. |
|
|
|
|
*/ |
|
|
|
|
extern pthread_mutex_t px4_modules_mutex; |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
** class ModuleBase |
|
|
|
|
* @class ModuleBase |
|
|
|
|
* Base class for modules, implementing common functionality, |
|
|
|
|
* such as 'start', 'stop' and 'status' commands. |
|
|
|
|
* Currently does not support modules which allow multiple instances, |
|
|
|
|
* such as mavlink. |
|
|
|
|
* |
|
|
|
|
* Base class for modules, implementing common functionality, such as 'start', |
|
|
|
|
* 'stop' and 'status' commands. |
|
|
|
|
* Currently does not support modules which allow multiple instances, such as |
|
|
|
|
* mavlink. |
|
|
|
|
* The class is implemented as curiously recurring template pattern (CRTP). |
|
|
|
|
* It allows to have a static object in the base class that is different for |
|
|
|
|
* each module type, and call static methods from the base class. |
|
|
|
|
* |
|
|
|
|
* The class is implemented as curiously recurring template pattern (CRTP). It |
|
|
|
|
* allows to have a static object in the base class that is different for |
|
|
|
|
* each module type, and call static methods from the base class. |
|
|
|
|
* @note Required methods for a derived class: |
|
|
|
|
* When running in its own thread: |
|
|
|
|
* static int task_spawn(int argc, char *argv[]) |
|
|
|
|
* { |
|
|
|
|
* // call px4_task_spawn_cmd() with &run_trampoline as startup method
|
|
|
|
|
* // optional: wait until _object is not null, which means the task got initialized (use a timeout)
|
|
|
|
|
* // set _task_id and return 0
|
|
|
|
|
* // on error return != 0 (and _task_id must be -1)
|
|
|
|
|
* } |
|
|
|
|
* |
|
|
|
|
* Required methods for a derived class: |
|
|
|
|
* static T *instantiate(int argc, char *argv[]) |
|
|
|
|
* { |
|
|
|
|
* // this is called from within the new thread, from run_trampoline()
|
|
|
|
|
* // parse the arguments
|
|
|
|
|
* // create a new object T & return it
|
|
|
|
|
* // or return nullptr on error
|
|
|
|
|
* } |
|
|
|
|
* |
|
|
|
|
* When running in its own thread: |
|
|
|
|
static int task_spawn(int argc, char *argv[]) { |
|
|
|
|
// call px4_task_spawn_cmd() with &run_trampoline as startup method
|
|
|
|
|
// optional: wait until _object is not null, which means the task got initialized (use a timeout)
|
|
|
|
|
// set _task_id and return 0
|
|
|
|
|
// on error return != 0 (and _task_id must be -1)
|
|
|
|
|
} |
|
|
|
|
static T *instantiate(int argc, char *argv[]) { |
|
|
|
|
// this is called from within the new thread, from run_trampoline()
|
|
|
|
|
// parse the arguments
|
|
|
|
|
// create a new object T & return it
|
|
|
|
|
// or return nullptr on error
|
|
|
|
|
} |
|
|
|
|
static int custom_command(int argc, char *argv[]) { |
|
|
|
|
// support for custom commands
|
|
|
|
|
// it none are supported, just do:
|
|
|
|
|
return print_usage("unrecognized command"); |
|
|
|
|
} |
|
|
|
|
static int print_usage(const char *reason = nullptr) { |
|
|
|
|
// use the PRINT_MODULE_* methods...
|
|
|
|
|
} |
|
|
|
|
* static int custom_command(int argc, char *argv[]) |
|
|
|
|
* { |
|
|
|
|
* // support for custom commands
|
|
|
|
|
* // it none are supported, just do:
|
|
|
|
|
* return print_usage("unrecognized command"); |
|
|
|
|
* } |
|
|
|
|
* |
|
|
|
|
* static int print_usage(const char *reason = nullptr) |
|
|
|
|
* { |
|
|
|
|
* // use the PRINT_MODULE_* methods...
|
|
|
|
|
* } |
|
|
|
|
* |
|
|
|
|
* When running on the work queue: |
|
|
|
|
* - custom_command & print_usage as above |
|
|
|
|
static int task_spawn(int argc, char *argv[]) { |
|
|
|
|
// parse the arguments
|
|
|
|
|
// set _object (here or from the work_queue() callback)
|
|
|
|
|
// call work_queue() (with a custom cycle trampoline)
|
|
|
|
|
// optional: wait until _object is not null, which means the task got initialized (use a timeout)
|
|
|
|
|
// set _task_id to task_id_is_work_queue and return 0
|
|
|
|
|
// on error return != 0 (and _task_id must be -1)
|
|
|
|
|
} |
|
|
|
|
* static int task_spawn(int argc, char *argv[]) { |
|
|
|
|
* // parse the arguments
|
|
|
|
|
* // set _object (here or from the work_queue() callback)
|
|
|
|
|
* // call work_queue() (with a custom cycle trampoline)
|
|
|
|
|
* // optional: wait until _object is not null, which means the task got initialized (use a timeout)
|
|
|
|
|
* // set _task_id to task_id_is_work_queue and return 0
|
|
|
|
|
* // on error return != 0 (and _task_id must be -1)
|
|
|
|
|
* } |
|
|
|
|
*/ |
|
|
|
|
template<class T> |
|
|
|
|
class ModuleBase |
|
|
|
|
{ |
|
|
|
|
public: |
|
|
|
|
ModuleBase() = default; |
|
|
|
|
virtual ~ModuleBase() {} |
|
|
|
|
virtual ~ModuleBase() {}; |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* main entry point. Should be called directly from the module's main method. |
|
|
|
|
* @brief main Main entry point to the module that should be |
|
|
|
|
* called directly from the module's main method. |
|
|
|
|
* @return Returns 0 iff successful, -1 otherwise. |
|
|
|
|
*/ |
|
|
|
|
static int main(int argc, char *argv[]) |
|
|
|
|
{ |
|
|
|
|
if (argc <= 1 || strcmp(argv[1], "help") == 0 || strcmp(argv[1], "-h") == 0) { |
|
|
|
|
if (argc <= 1 || |
|
|
|
|
strcmp(argv[1], "-h") == 0 || |
|
|
|
|
strcmp(argv[1], "help") == 0 || |
|
|
|
|
strcmp(argv[1], "info") == 0 || |
|
|
|
|
strcmp(argv[1], "usage") == 0) { |
|
|
|
|
return T::print_usage(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (strcmp(argv[1], "start") == 0) { |
|
|
|
|
// we pass the 'start' argument too, because later on px4_getopt() will ignore the first argument
|
|
|
|
|
// Pass the 'start' argument too, because later on px4_getopt() will ignore the first argument.
|
|
|
|
|
return start_command_base(argc - 1, argv + 1); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (strcmp(argv[1], "stop") == 0) { |
|
|
|
|
return stop_command(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (strcmp(argv[1], "status") == 0) { |
|
|
|
|
return status_command(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
lock_module(); // we better lock here, as the method could access _object
|
|
|
|
|
if (strcmp(argv[1], "stop") == 0) { |
|
|
|
|
return stop_command(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
lock_module(); // Lock here, as the method could access _object.
|
|
|
|
|
int ret = T::custom_command(argc - 1, argv + 1); |
|
|
|
|
unlock_module(); |
|
|
|
|
|
|
|
|
@ -141,20 +152,21 @@ public:
@@ -141,20 +152,21 @@ public:
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Entry point for px4_task_spawn_cmd() if the module runs in its own thread. |
|
|
|
|
* It does: |
|
|
|
|
* - instantiate the object |
|
|
|
|
* - call run() on it to execute the main loop |
|
|
|
|
* - cleanup: delete the object |
|
|
|
|
* @param argc start argument(s) |
|
|
|
|
* @param argv start argument(s) |
|
|
|
|
* @brief Entry point for px4_task_spawn_cmd() if the module runs in its own thread. |
|
|
|
|
* It does: |
|
|
|
|
* - instantiate the object |
|
|
|
|
* - call run() on it to execute the main loop |
|
|
|
|
* - cleanup: delete the object |
|
|
|
|
* @param argc The start argument count. |
|
|
|
|
* @param argv The start argument vector. |
|
|
|
|
* @return Returns 0 iff successful, -1 otherwise. |
|
|
|
|
*/ |
|
|
|
|
static int run_trampoline(int argc, char *argv[]) |
|
|
|
|
{ |
|
|
|
|
int ret = 0; |
|
|
|
|
|
|
|
|
|
#ifdef __PX4_NUTTX |
|
|
|
|
// on NuttX task_create() adds the task name as first argument
|
|
|
|
|
// On NuttX task_create() adds the task name as first argument.
|
|
|
|
|
argc -= 1; |
|
|
|
|
argv += 1; |
|
|
|
|
#endif |
|
|
|
@ -176,7 +188,9 @@ public:
@@ -176,7 +188,9 @@ public:
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* handle 'command start': check if already running and call T::task_spawn() if it's not |
|
|
|
|
* @brief Stars the command, ('command start'), checks if if is already |
|
|
|
|
* running and calls T::task_spawn() if it's not. |
|
|
|
|
* @return Returns 0 iff successful, -1 otherwise. |
|
|
|
|
*/ |
|
|
|
|
static int start_command_base(int argc, char *argv[]) |
|
|
|
|
{ |
|
|
|
@ -200,8 +214,9 @@ public:
@@ -200,8 +214,9 @@ public:
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* handle 'command stop': check if already running and if it is, request the module to stop |
|
|
|
|
* and wait for it. |
|
|
|
|
* @brief Stops the command, ('command stop'), checks if it is running and if it is, request the module to stop |
|
|
|
|
* and waits for the task to complete. |
|
|
|
|
* @return Returns 0 iff successful, -1 otherwise. |
|
|
|
|
*/ |
|
|
|
|
static int stop_command() |
|
|
|
|
{ |
|
|
|
@ -238,10 +253,10 @@ public:
@@ -238,10 +253,10 @@ public:
|
|
|
|
|
} while (_task_id != -1); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
// very unlikely event and can only happen on work queues:
|
|
|
|
|
// the starting thread does not wait for the work queue to initialize,
|
|
|
|
|
// In the very unlikely event that can only happen on work queues,
|
|
|
|
|
// if the starting thread does not wait for the work queue to initialize,
|
|
|
|
|
// and inside the work queue, the allocation of _object fails
|
|
|
|
|
// and exit_and_cleanup() is not called.
|
|
|
|
|
// and exit_and_cleanup() is not called, set the _task_id as invalid.
|
|
|
|
|
_task_id = -1; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -251,9 +266,8 @@ public:
@@ -251,9 +266,8 @@ public:
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* |
|
|
|
|
* handle 'command status': check if running and call print_status() if it is |
|
|
|
|
* @return 0 on success, -1 if not running |
|
|
|
|
* @brief Handle 'command status': check if running and call print_status() if it is |
|
|
|
|
* @return Returns 0 iff successful, -1 otherwise. |
|
|
|
|
*/ |
|
|
|
|
static int status_command() |
|
|
|
|
{ |
|
|
|
@ -273,9 +287,9 @@ public:
@@ -273,9 +287,9 @@ public:
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print the status if the module is running. This can be overridden by the module to provide |
|
|
|
|
* @brief Print the status if the module is running. This can be overridden by the module to provide |
|
|
|
|
* more specific information. |
|
|
|
|
* @return 0 on success |
|
|
|
|
* @return Returns 0 iff successful, -1 otherwise. |
|
|
|
|
*/ |
|
|
|
|
virtual int print_status() |
|
|
|
|
{ |
|
|
|
@ -284,35 +298,52 @@ public:
@@ -284,35 +298,52 @@ public:
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Main loop method for modules running in their own thread. Called from run_trampoline(). |
|
|
|
|
* This method must return when should_exit() returns true |
|
|
|
|
* @brief Main loop method for modules running in their own thread. Called from run_trampoline(). |
|
|
|
|
* This method must return when should_exit() returns true. |
|
|
|
|
*/ |
|
|
|
|
virtual void run() {} |
|
|
|
|
virtual void run() |
|
|
|
|
{ |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @return true if the module is running |
|
|
|
|
* @brief Returns the status of the module. |
|
|
|
|
* @return Returns true if the module is running, false otherwise. |
|
|
|
|
*/ |
|
|
|
|
static bool is_running() { return _task_id != -1; } |
|
|
|
|
static bool is_running() |
|
|
|
|
{ |
|
|
|
|
return _task_id != -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
protected: |
|
|
|
|
|
|
|
|
|
/** Tell the module to stop (used from outside or inside the module thread) */ |
|
|
|
|
virtual void request_stop() { _task_should_exit = true; } |
|
|
|
|
/**
|
|
|
|
|
* @brief Tells the module to stop (used from outside or inside the module thread). |
|
|
|
|
*/ |
|
|
|
|
virtual void request_stop() |
|
|
|
|
{ |
|
|
|
|
_task_should_exit = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/** check if the module should stop (used within the module thread) */ |
|
|
|
|
bool should_exit() const { return _task_should_exit; } |
|
|
|
|
/**
|
|
|
|
|
* @brief Checks if the module should stop (used within the module thread). |
|
|
|
|
* @return Returns True iff successful, false otherwise. |
|
|
|
|
*/ |
|
|
|
|
bool should_exit() const |
|
|
|
|
{ |
|
|
|
|
return _task_should_exit; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Exit the module and delete the object. Called from within the module's thread. |
|
|
|
|
* For work queue modules, this needs to be called from the derived class in the |
|
|
|
|
* cycle method, when should_exit() returns true. |
|
|
|
|
* @brief Exits the module and delete the object. Called from within the module's thread. |
|
|
|
|
* For work queue modules, this needs to be called from the derived class in the |
|
|
|
|
* cycle method, when should_exit() returns true. |
|
|
|
|
*/ |
|
|
|
|
static void exit_and_cleanup() |
|
|
|
|
{ |
|
|
|
|
// we need to take the lock here:
|
|
|
|
|
// Take the lock here:
|
|
|
|
|
// - if startup fails and we're faster than the parent thread, it will set
|
|
|
|
|
// _task_id and subsequently it will look like the task is running
|
|
|
|
|
// - deleting the object must take place inside the lock
|
|
|
|
|
// _task_id and subsequently it will look like the task is running.
|
|
|
|
|
// - deleting the object must take place inside the lock.
|
|
|
|
|
lock_module(); |
|
|
|
|
|
|
|
|
|
if (_object) { |
|
|
|
@ -320,20 +351,20 @@ protected:
@@ -320,20 +351,20 @@ protected:
|
|
|
|
|
_object = nullptr; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_task_id = -1; // signal a potentially waiting thread for the module to exit that it can continue
|
|
|
|
|
_task_id = -1; // Signal a potentially waiting thread for the module to exit that it can continue.
|
|
|
|
|
unlock_module(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Wait until _object got initialized (from the new thread). This can be called from task_spawn(). |
|
|
|
|
* @return 0 on success, -1 on timeout. |
|
|
|
|
* @brief Waits until _object is initialized, (from the new thread). This can be called from task_spawn(). |
|
|
|
|
* @return Returns 0 iff successful, -1 on timeout or otherwise. |
|
|
|
|
*/ |
|
|
|
|
static int wait_until_running() |
|
|
|
|
{ |
|
|
|
|
int i = 0; |
|
|
|
|
|
|
|
|
|
do { |
|
|
|
|
/* wait up to 1s */ |
|
|
|
|
/* Wait up to 1s. */ |
|
|
|
|
usleep(2500); |
|
|
|
|
|
|
|
|
|
} while (!_object && ++i < 400); |
|
|
|
@ -346,24 +377,45 @@ protected:
@@ -346,24 +377,45 @@ protected:
|
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/** get the module's object instance (this is null if it's not running) */ |
|
|
|
|
/**
|
|
|
|
|
* @brief Get the module's object instance, (this is null if it's not running). |
|
|
|
|
*/ |
|
|
|
|
static T *get_instance() |
|
|
|
|
{ |
|
|
|
|
return (T *)_object; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// there will be one instance for each template type
|
|
|
|
|
static volatile T *_object; ///< instance if the module is running
|
|
|
|
|
static int _task_id; ///< task handle: -1 = invalid, otherwise task is assumed to be running
|
|
|
|
|
/**
|
|
|
|
|
* @param _object Instance if the module is running. |
|
|
|
|
* @note There will be one instance for each template type. |
|
|
|
|
*/ |
|
|
|
|
static volatile T *_object; |
|
|
|
|
|
|
|
|
|
/** @brief _task_id The task handle: -1 = invalid, otherwise task is assumed to be running. */ |
|
|
|
|
static int _task_id; |
|
|
|
|
|
|
|
|
|
static constexpr const int task_id_is_work_queue = -2; ///< special value if task runs on the work queue
|
|
|
|
|
/** @brief task_id_is_work_queue Value to indicate if the task runs on the work queue. */ |
|
|
|
|
static constexpr const int task_id_is_work_queue = -2; |
|
|
|
|
|
|
|
|
|
private: |
|
|
|
|
/**
|
|
|
|
|
* @brief lock_module Mutex to lock the module thread. |
|
|
|
|
*/ |
|
|
|
|
static void lock_module() |
|
|
|
|
{ |
|
|
|
|
pthread_mutex_lock(&px4_modules_mutex); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
volatile bool _task_should_exit = false; |
|
|
|
|
/**
|
|
|
|
|
* @brief unlock_module Mutex to unlock the module thread. |
|
|
|
|
*/ |
|
|
|
|
static void unlock_module() |
|
|
|
|
{ |
|
|
|
|
pthread_mutex_unlock(&px4_modules_mutex); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void lock_module() { pthread_mutex_lock(&px4_modules_mutex); } |
|
|
|
|
static void unlock_module() { pthread_mutex_unlock(&px4_modules_mutex); } |
|
|
|
|
/** @param _task_should_exit Boolean flag to indicate if the task should exit. */ |
|
|
|
|
volatile bool _task_should_exit = false; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
template<class T> |
|
|
|
@ -378,19 +430,24 @@ int ModuleBase<T>::_task_id = -1;
@@ -378,19 +430,24 @@ int ModuleBase<T>::_task_id = -1;
|
|
|
|
|
|
|
|
|
|
__BEGIN_DECLS |
|
|
|
|
|
|
|
|
|
/* Module documentation and command usage help methods.
|
|
|
|
|
* These are extracted with the Tools/px_process_module_doc.py script and must be kept in sync |
|
|
|
|
/**
|
|
|
|
|
* @brief Module documentation and command usage help methods. |
|
|
|
|
* These are extracted with the Tools/px_process_module_doc.py |
|
|
|
|
* script and must be kept in sync. |
|
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
#ifdef __PX4_NUTTX |
|
|
|
|
// disable module description on NuttX to reduce Flash usage.
|
|
|
|
|
// There's a GCC bug (https://gcc.gnu.org/bugzilla/show_bug.cgi?id=55971), preventing us to use
|
|
|
|
|
// a macro, but GCC will remove the string as well with this empty inline method.
|
|
|
|
|
/**
|
|
|
|
|
* @note Disable module description on NuttX to reduce Flash usage. |
|
|
|
|
* There's a GCC bug (https://gcc.gnu.org/bugzilla/show_bug.cgi?id=55971), preventing us to use
|
|
|
|
|
* a macro, but GCC will remove the string as well with this empty inline method. |
|
|
|
|
*/ |
|
|
|
|
static inline void PRINT_MODULE_DESCRIPTION(const char *description) {} |
|
|
|
|
#else |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Print module documentation (will also be used for online documentation). It uses Markdown syntax |
|
|
|
|
* and should include these sections: |
|
|
|
|
* @brief Prints module documentation (will also be used for online documentation). It uses Markdown syntax |
|
|
|
|
* and should include these sections: |
|
|
|
|
* - ### Description |
|
|
|
|
* Provided functionality of the module and potentially the most important parameters. |
|
|
|
|
* - ### Implementation |
|
|
|
@ -405,20 +462,20 @@ __EXPORT void PRINT_MODULE_DESCRIPTION(const char *description);
@@ -405,20 +462,20 @@ __EXPORT void PRINT_MODULE_DESCRIPTION(const char *description);
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Print the command name |
|
|
|
|
* @brief Prints the command name. |
|
|
|
|
* @param executable_name: command name used in scripts & CLI |
|
|
|
|
* @param category one of: driver, estimator, controller, system, communication, command, template |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_NAME(const char *executable_name, const char *category); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Print the name for a command without any sub-commands (@see PRINT_MODULE_USAGE_NAME()) |
|
|
|
|
* @brief Prints the name for a command without any sub-commands (@see PRINT_MODULE_USAGE_NAME()). |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_NAME_SIMPLE(const char *executable_name, const char *category); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Print a command with a short description what it does |
|
|
|
|
* @brief Prints a command with a short description what it does. |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_COMMAND_DESCR(const char *name, const char *description); |
|
|
|
|
|
|
|
|
@ -426,73 +483,80 @@ __EXPORT void PRINT_MODULE_USAGE_COMMAND_DESCR(const char *name, const char *des
@@ -426,73 +483,80 @@ __EXPORT void PRINT_MODULE_USAGE_COMMAND_DESCR(const char *name, const char *des
|
|
|
|
|
PRINT_MODULE_USAGE_COMMAND_DESCR(name, NULL); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print the default commands: stop & status |
|
|
|
|
* @brief Prints the default commands: stop & status. |
|
|
|
|
*/ |
|
|
|
|
#define PRINT_MODULE_USAGE_DEFAULT_COMMANDS() \ |
|
|
|
|
PRINT_MODULE_USAGE_COMMAND("stop"); \
|
|
|
|
|
PRINT_MODULE_USAGE_COMMAND_DESCR("status", "print status info"); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/* all the PRINT_MODULE_USAGE_PARAM_* methods apply to the previous PRINT_MODULE_USAGE_COMMAND_DESCR() */ |
|
|
|
|
/** @note Each of the PRINT_MODULE_USAGE_PARAM_* methods apply to the previous PRINT_MODULE_USAGE_COMMAND_DESCR(). */ |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print an integer parameter |
|
|
|
|
* @param option_char option character |
|
|
|
|
* @param default_val |
|
|
|
|
* @param min_val |
|
|
|
|
* @param max_val |
|
|
|
|
* @param description |
|
|
|
|
* @brief Prints an integer parameter. |
|
|
|
|
* @param option_char The option character. |
|
|
|
|
* @param default_val The parameter default value. |
|
|
|
|
* @param min_val The parameter minimum value. |
|
|
|
|
* @param max_val The parameter value. |
|
|
|
|
* @param description Pointer to the usage description. |
|
|
|
|
* @param is_optional true if this parameter is optional |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_PARAM_INT(char option_char, int default_val, int min_val, int max_val, |
|
|
|
|
const char *description, bool is_optional); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print a float parameter |
|
|
|
|
* @see PRINT_MODULE_USAGE_PARAM_INT() |
|
|
|
|
* @brief Prints a float parameter. |
|
|
|
|
* @note See PRINT_MODULE_USAGE_PARAM_INT(). |
|
|
|
|
* @param default_val The parameter default value. |
|
|
|
|
* @param min_val The parameter minimum value. |
|
|
|
|
* @param max_val The parameter maximum value. |
|
|
|
|
* @param description Pointer to the usage description. Pointer to the usage description. |
|
|
|
|
* @param is_optional true if this parameter is optional |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_PARAM_FLOAT(char option_char, float default_val, float min_val, float max_val, |
|
|
|
|
const char *description, bool is_optional); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print a flag parameter, without any value |
|
|
|
|
* @see PRINT_MODULE_USAGE_PARAM_INT() |
|
|
|
|
* @brief Prints a flag parameter, without any value. |
|
|
|
|
* @note See PRINT_MODULE_USAGE_PARAM_INT(). |
|
|
|
|
* @param option_char The option character. |
|
|
|
|
* @param description Pointer to the usage description. |
|
|
|
|
* @param is_optional true if this parameter is optional |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_PARAM_FLAG(char option_char, const char *description, bool is_optional); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print a string parameter |
|
|
|
|
* @param option_char option character |
|
|
|
|
* @param default_val default value, can be nullptr |
|
|
|
|
* @param values valid values, it has one of the following forms: |
|
|
|
|
* @brief Prints a string parameter. |
|
|
|
|
* @param option_char The option character. |
|
|
|
|
* @param default_val The default value, can be nullptr. |
|
|
|
|
* @param values The valid values, it has one of the following forms: |
|
|
|
|
* - nullptr: leave unspecified, or any value is valid |
|
|
|
|
* - "<file>" or "<file:dev>": a file or more specifically a device file (eg. serial device) |
|
|
|
|
* - "<topic_name>": uORB topic name |
|
|
|
|
* - "<value1> [<value2>]": a list of values |
|
|
|
|
* - "on|off": a concrete set of valid strings separated by | |
|
|
|
|
* @param description |
|
|
|
|
* @param is_optional true if this parameter is optional |
|
|
|
|
* - "on|off": a concrete set of valid strings separated by "|". |
|
|
|
|
* @param description Pointer to the usage description. |
|
|
|
|
* @param is_optional True iff this parameter is optional. |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_PARAM_STRING(char option_char, const char *default_val, const char *values, |
|
|
|
|
const char *description, bool is_optional); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print a comment, that applies to the next arguments or parameters. For example to indicate that |
|
|
|
|
* a parameter applies to several or all commands. |
|
|
|
|
* @brief Prints a comment, that applies to the next arguments or parameters. For example to indicate that |
|
|
|
|
* a parameter applies to several or all commands. |
|
|
|
|
* @param comment |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_PARAM_COMMENT(const char *comment); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* print definition for an argument, which does not have the typical -p <val> form, |
|
|
|
|
* but for example 'param set <param> <value>' |
|
|
|
|
* @brief Prints the definition for an argument, which does not have the typical -p <val> form, |
|
|
|
|
* but for example 'param set <param> <value>' |
|
|
|
|
* @param values eg. "<file>", "<param> <value>" or "<value1> [<value2>]" |
|
|
|
|
* @param description |
|
|
|
|
* @param description Pointer to the usage description. |
|
|
|
|
* @param is_optional true if this parameter is optional |
|
|
|
|
*/ |
|
|
|
|
__EXPORT void PRINT_MODULE_USAGE_ARG(const char *values, const char *description, bool is_optional); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
__END_DECLS |
|
|
|
|
|
|
|
|
|