PX4 Firmware
PX4 Autopilot Software http://px4.io
events::SendEvent Class Reference

class manages the RC loss audible alarm, LED status display, and thermal calibration. More...

#include <send_event.h>

Inheritance diagram for events::SendEvent:
Collaboration diagram for events::SendEvent:

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
 

Detailed Description

class manages the RC loss audible alarm, LED status display, and thermal calibration.

Definition at line 46 of file send_event.cpp.

Constructor & Destructor Documentation

◆ SendEvent()

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().

Here is the caller graph for this function:

◆ ~SendEvent()

events::SendEvent::~SendEvent ( )

Definition at line 82 of file send_event.cpp.

References _rc_loss_alarm, and _status_display.

Member Function Documentation

◆ answer_command()

void events::SendEvent::answer_command ( const vehicle_command_s cmd,
unsigned  result 
)
private

Returns an ACK to a vehicle_command.

Parameters
cmdThe vehicle command struct being referenced.
resultThe 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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ custom_command()

int events::SendEvent::custom_command ( int  argc,
char *  argv[] 
)
static

Recognizes custom startup commands, called from the main() function entry.

See also
ModuleBase
Parameters
argcThe task argument count.
argcPointer to the task argument variable array.
Returns
Returns 0 iff successful, otherwise < 0 on error.

Definition at line 204 of file send_event.cpp.

References hrt_absolute_time(), is_running(), ORB_ID, print_usage(), and vehicle_command_s::timestamp.

Here is the call graph for this function:

◆ cycle()

void events::SendEvent::cycle ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ cycle_trampoline()

void events::SendEvent::cycle_trampoline ( void *  arg)
staticprivate

Process cycle trampoline for the work queue.

Parameters
argPointer to the task startup arguments.

Definition at line 116 of file send_event.cpp.

References cycle().

Referenced by cycle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize_trampoline()

void events::SendEvent::initialize_trampoline ( void *  arg)
staticprivate

Trampoline for initialisation.

Parameters
argPointer to the task startup arguments.

Definition at line 103 of file send_event.cpp.

References SendEvent(), and start().

Referenced by task_spawn().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_usage()

int events::SendEvent::print_usage ( const char *  reason = nullptr)
static

Prints usage options to the console.

See also
ModuleBase
Parameters
reasonThe requested usage reason for printing to console.
Returns
Returns 0 iff successful, -1 otherwise.

Definition at line 266 of file send_event.cpp.

Referenced by custom_command().

Here is the caller graph for this function:

◆ process_commands()

void events::SendEvent::process_commands ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

int events::SendEvent::start ( )
private

Starts background task listening for commands.

Returns
Returns 0 iff successful, otherwise < 0 on error.

Definition at line 88 of file send_event.cpp.

References _subscriber_handler, cycle(), is_running(), and events::SubscriberHandler::subscribe().

Referenced by initialize_trampoline().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ task_spawn()

int events::SendEvent::task_spawn ( int  argc,
char *  argv[] 
)
static

Spawns and initializes the class in the same context as the work queue and starts the background listener.

Parameters
argcThe input argument count.
argvPointer to the input argument array.
Returns
Returns 0 iff successful, -1 otherwise.

Definition at line 52 of file send_event.cpp.

References initialize_trampoline().

Here is the call graph for this function:

Member Data Documentation

◆ _rc_loss_alarm

rc_loss::RC_Loss_Alarm* events::SendEvent::_rc_loss_alarm = nullptr
private

Definition at line 134 of file send_event.h.

Referenced by cycle(), SendEvent(), and ~SendEvent().

◆ _status_display

status::StatusDisplay* events::SendEvent::_status_display = nullptr
private

Definition at line 131 of file send_event.h.

Referenced by cycle(), SendEvent(), and ~SendEvent().

◆ _subscriber_handler

SubscriberHandler events::SendEvent::_subscriber_handler
private

Definition at line 128 of file send_event.h.

Referenced by cycle(), process_commands(), SendEvent(), and start().

◆ _work

struct work_s events::SendEvent::_work
staticprivate

Definition at line 125 of file send_event.h.


The documentation for this class was generated from the following files: