diff --git a/src/modules/events/send_event.cpp b/src/modules/events/send_event.cpp index 5d52a1bc77..9630d80446 100644 --- a/src/modules/events/send_event.cpp +++ b/src/modules/events/send_event.cpp @@ -94,10 +94,10 @@ int SendEvent::start() return 0; } - // subscribe to the topics + // Subscribe to the topics. _subscriber_handler.subscribe(); - // Kick off the cycling. We can call it directly because we're already in the work queue context + // Kick off the cycling. We can call it directly because we're already in the work queue context. cycle(); return 0; @@ -116,8 +116,7 @@ void SendEvent::initialize_trampoline(void *arg) _object = send_event; } -void -SendEvent::cycle_trampoline(void *arg) +void SendEvent::cycle_trampoline(void *arg) { SendEvent *obj = reinterpret_cast(arg); @@ -236,13 +235,6 @@ The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, e return 0; } - -int send_event_main(int argc, char *argv[]) -{ - return SendEvent::main(argc, argv); -} - - int SendEvent::custom_command(int argc, char *argv[]) { if (!strcmp(argv[0], "temperature_calibration")) { @@ -301,4 +293,9 @@ int SendEvent::custom_command(int argc, char *argv[]) return 0; } +int send_event_main(int argc, char *argv[]) +{ + return SendEvent::main(argc, argv); +} + } /* namespace events */ diff --git a/src/modules/events/send_event.h b/src/modules/events/send_event.h index 0cb57e96f0..bdfd9101e9 100644 --- a/src/modules/events/send_event.h +++ b/src/modules/events/send_event.h @@ -48,55 +48,101 @@ namespace events extern "C" __EXPORT int send_event_main(int argc, char *argv[]); +/** @class SendEvent The SendEvent class manages the RC loss audible alarm, LED status display, and thermal calibration. */ class SendEvent : public ModuleBase, public ModuleParams { public: + SendEvent(); + ~SendEvent(); /** - * Initialize class in the same context as the work queue. And start the background listener. - * @return 0 if successful, <0 on error */ - static int task_spawn(int argc, char *argv[]); - - /** @see ModuleBase */ + * @see ModuleBase + * @brief Recognizes custom startup commands, called from the main() function entry. + * @param argc The task argument count. + * @param argc Pointer to the task argument variable array. + * @return Returns 0 iff successful, otherwise < 0 on error. + */ static int custom_command(int argc, char *argv[]); - /** @see ModuleBase */ + /** + * @see ModuleBase + * @brief Prints usage options to the console. + * @param reason The requested usage reason for printing to console. + * @return Returns 0 iff successful, -1 otherwise. + */ static int print_usage(const char *reason = nullptr); + /** + * @brief Spawns and initializes the class in the same context as the + * work queue and starts the background listener. + * @param argc The input argument count. + * @param argv Pointer to the input argument array. + * @return Returns 0 iff successful, -1 otherwise. + */ + static int task_spawn(int argc, char *argv[]); + private: - /** Start background listening for commands - * - * @return 0 if successful, <0 on error. */ - int start(); - - - /** Trampoline for initialisation. */ - static void initialize_trampoline(void *arg); - /** Trampoline for the work queue. */ - static void cycle_trampoline(void *arg); - - /** call process_commands() and schedule the next cycle. */ - void cycle(); - - /** check for new commands and process them. */ - void process_commands(); - - /** return an ACK to a vehicle_command */ + /** + * @brief Returns an ACK to a vehicle_command. + * @param cmd The vehicle command struct being referenced. + * @param result The command acknowledgement result. + */ void answer_command(const vehicle_command_s &cmd, unsigned result); + /** + * @brief Process cycle trampoline for the work queue. + * @param arg Pointer to the task startup arguments. + */ + static void cycle_trampoline(void *arg); + + /** + * @brief Calls process_commands() and schedules the next cycle. + */ + void cycle(); + + /** + * @brief Trampoline for initialisation. + * @param arg Pointer to the task startup arguments. + */ + static void initialize_trampoline(void *arg); + + /** + * @brief Checks for new commands and processes them. + */ + void process_commands(); + + /** + * @brief Starts background task listening for commands. + * @return Returns 0 iff successful, otherwise < 0 on error. + */ + int start(); + + /** @struct _work The work queue struct. */ static struct work_s _work; + + /** @var _subscriber_handler The uORB subscriber handler. */ SubscriberHandler _subscriber_handler; + + /** @var _status_display Pointer to the status display object. */ status::StatusDisplay *_status_display = nullptr; + + /** @var _rc_loss_alarm Pointer to the RC loss alarm object. */ rc_loss::RC_Loss_Alarm *_rc_loss_alarm = nullptr; + + /** @var _command_ack_pub The command ackowledgement topic. */ orb_advert_t _command_ack_pub = nullptr; + /** @note Declare local parameters using defined parameters. */ DEFINE_PARAMETERS( + /** @var _param_status_display Parameter to enable/disable the LED status display. */ (ParamBool) _param_status_display, + + /** @var _param_rc_loss The RC comms loss status flag. */ (ParamBool) _param_rc_loss ) }; -} /* namespace events */ +} // namespace events diff --git a/src/platforms/px4_module.h b/src/platforms/px4_module.h index 4a201e43dc..5292959ead 100644 --- a/src/platforms/px4_module.h +++ b/src/platforms/px4_module.h @@ -119,6 +119,8 @@ public: /** * @brief main Main entry point to the module that should be * called directly from the module's main method. + * @param argc The task argument count. + * @param argc Pointer to the task argument variable array. * @return Returns 0 iff successful, -1 otherwise. */ static int main(int argc, char *argv[]) @@ -157,8 +159,8 @@ public: * - 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. + * @param argc The task argument count. + * @param argc Pointer to the task argument variable array. * @return Returns 0 iff successful, -1 otherwise. */ static int run_trampoline(int argc, char *argv[]) @@ -190,6 +192,8 @@ public: /** * @brief Stars the command, ('command start'), checks if if is already * running and calls T::task_spawn() if it's not. + * @param argc The task argument count. + * @param argc Pointer to the task argument variable array. * @return Returns 0 iff successful, -1 otherwise. */ static int start_command_base(int argc, char *argv[]) @@ -386,15 +390,15 @@ protected: } /** - * @param _object Instance if the module is running. + * @var _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. */ + /** @var _task_id The task handle: -1 = invalid, otherwise task is assumed to be running. */ static int _task_id; - /** @brief task_id_is_work_queue Value to indicate if the task runs on the work queue. */ + /** @var 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: @@ -414,7 +418,7 @@ private: pthread_mutex_unlock(&px4_modules_mutex); } - /** @param _task_should_exit Boolean flag to indicate if the task should exit. */ + /** @var _task_should_exit Boolean flag to indicate if the task should exit. */ volatile bool _task_should_exit = false; }; @@ -441,6 +445,7 @@ __BEGIN_DECLS * @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. + * @param description The provided functionality of the module and potentially the most important parameters. */ static inline void PRINT_MODULE_DESCRIPTION(const char *description) {} #else