PX4 Firmware
PX4 Autopilot Software http://px4.io
|
class manages the RC loss audible alarm, LED status display, and thermal calibration. More...
#include <send_event.h>
Public Member Functions | |
SendEvent () | |
~SendEvent () | |
Static Public Member Functions | |
static int | custom_command (int argc, char *argv[]) |
Recognizes custom startup commands, called from the main() function entry. More... | |
static int | print_usage (const char *reason=nullptr) |
Prints usage options to the console. More... | |
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 listener. More... | |
Private Member Functions | |
void | answer_command (const vehicle_command_s &cmd, unsigned result) |
Returns an ACK to a vehicle_command. More... | |
void | cycle () |
Calls process_commands() and schedules the next cycle. More... | |
void | process_commands () |
Checks for new commands and processes them. More... | |
int | start () |
Starts background task listening for commands. More... | |
Static Private Member Functions | |
static void | cycle_trampoline (void *arg) |
Process cycle trampoline for the work queue. More... | |
static void | initialize_trampoline (void *arg) |
Trampoline for initialisation. More... | |
Private Attributes | |
SubscriberHandler | _subscriber_handler |
status::StatusDisplay * | _status_display = nullptr |
rc_loss::RC_Loss_Alarm * | _rc_loss_alarm = nullptr |
Static Private Attributes | |
static struct work_s | _work |
class manages the RC loss audible alarm, LED status display, and thermal calibration.
Definition at line 46 of file send_event.cpp.
events::SendEvent::SendEvent | ( | ) |
Definition at line 71 of file send_event.cpp.
References _rc_loss_alarm, _status_display, and _subscriber_handler.
Referenced by initialize_trampoline().
events::SendEvent::~SendEvent | ( | ) |
Definition at line 82 of file send_event.cpp.
References _rc_loss_alarm, and _status_display.
|
private |
Returns an ACK to a vehicle_command.
cmd | The vehicle command struct being referenced. |
result | The command acknowledgement result. |
Definition at line 190 of file send_event.cpp.
References vehicle_command_s::command, hrt_absolute_time(), ORB_ID, vehicle_command_s::source_component, vehicle_command_s::source_system, and vehicle_command_ack_s::timestamp.
Referenced by process_commands().
|
static |
Recognizes custom startup commands, called from the main() function entry.
argc | The task argument count. |
argc | Pointer to the task argument variable array. |
Definition at line 204 of file send_event.cpp.
References hrt_absolute_time(), is_running(), ORB_ID, print_usage(), and vehicle_command_s::timestamp.
|
private |
Calls process_commands() and schedules the next cycle.
Definition at line 123 of file send_event.cpp.
References _rc_loss_alarm, _status_display, _subscriber_handler, events::SubscriberHandler::check_for_updates(), cycle_trampoline(), events::rc_loss::RC_Loss_Alarm::process(), events::status::StatusDisplay::process(), process_commands(), and events::SubscriberHandler::unsubscribe().
Referenced by cycle_trampoline(), and start().
|
staticprivate |
Process cycle trampoline for the work queue.
arg | Pointer to the task startup arguments. |
Definition at line 116 of file send_event.cpp.
References cycle().
Referenced by cycle().
|
staticprivate |
Trampoline for initialisation.
arg | Pointer to the task startup arguments. |
Definition at line 103 of file send_event.cpp.
References SendEvent(), and start().
Referenced by task_spawn().
|
static |
Prints usage options to the console.
reason | The requested usage reason for printing to console. |
Definition at line 266 of file send_event.cpp.
Referenced by custom_command().
|
private |
Checks for new commands and processes them.
Definition at line 147 of file send_event.cpp.
References _subscriber_handler, answer_command(), vehicle_command_s::command, events::SubscriberHandler::get_vehicle_command_sub(), orb_copy(), ORB_ID, vehicle_command_s::param1, vehicle_command_s::param5, vehicle_command_s::param7, run_temperature_calibration(), and events::SubscriberHandler::vehicle_command_updated().
Referenced by cycle().
|
private |
Starts background task listening for commands.
Definition at line 88 of file send_event.cpp.
References _subscriber_handler, cycle(), is_running(), and events::SubscriberHandler::subscribe().
Referenced by initialize_trampoline().
|
static |
Spawns and initializes the class in the same context as the work queue and starts the background listener.
argc | The input argument count. |
argv | Pointer to the input argument array. |
Definition at line 52 of file send_event.cpp.
References initialize_trampoline().
|
private |
Definition at line 134 of file send_event.h.
Referenced by cycle(), SendEvent(), and ~SendEvent().
|
private |
Definition at line 131 of file send_event.h.
Referenced by cycle(), SendEvent(), and ~SendEvent().
|
private |
Definition at line 128 of file send_event.h.
Referenced by cycle(), process_commands(), SendEvent(), and start().
|
staticprivate |
Definition at line 125 of file send_event.h.