40 #include <px4_platform_common/workqueue.h> 41 #include <px4_platform_common/module.h> 42 #include <px4_platform_common/module_params.h> 53 class SendEvent :
public ModuleBase<SendEvent>,
public ModuleParams
76 static int print_usage(
const char *reason =
nullptr);
139 (ParamBool<px4::params::EV_TSK_STAT_DIS>) _param_ev_tsk_stat_dis,
142 (ParamBool<px4::params::EV_TSK_RC_LOSS>) _param_ev_tsk_rc_loss
Contains a list of uORB subscriptions and maintains their update state.
void answer_command(const vehicle_command_s &cmd, unsigned result)
Returns an ACK to a vehicle_command.
static int task_spawn(int argc, char *argv[])
Spawns and initializes the class in the same context as the work queue and starts the background list...
int send_event_main(int argc, char *argv[])
rc_loss::RC_Loss_Alarm * _rc_loss_alarm
Status Display decouples LED and tunes from commander.
void process_commands()
Checks for new commands and processes them.
int start()
Starts background task listening for commands.
void cycle()
Calls process_commands() and schedules the next cycle.
static int print_usage(const char *reason=nullptr)
Prints usage options to the console.
status::StatusDisplay * _status_display
static int custom_command(int argc, char *argv[])
Recognizes custom startup commands, called from the main() function entry.
SubscriberHandler _subscriber_handler
static void cycle_trampoline(void *arg)
Process cycle trampoline for the work queue.
Tone alarm in the event of RC loss.
static void initialize_trampoline(void *arg)
Trampoline for initialisation.