Qualcomm Navigator Flight Control Interface
2.0
|
Structure containing the inputs to the sn_send_rc_command() Qualcomm Navigator API function. More...
#include <rc_command.hpp>
Public Member Functions | |
RcCommand () | |
Default constructor. | |
Public Member Functions inherited from snav_fci::TxCommand | |
Mode | get_mode () const |
Public Attributes | |
SnRcCommandType | type |
SnRcCommandOptions | options |
std::array< float, kNumRcCommands > | commands |
Static Public Attributes | |
static const size_t | kNumRcCommands = 4 |
Additional Inherited Members | |
Public Types inherited from snav_fci::TxCommand | |
enum | Mode { UNDEFINED, RC, RPM, PWM, THRUST_ATT_ANG_VEL, TRAJECTORY } |
Protected Attributes inherited from snav_fci::TxCommand | |
Mode | mode_ |
Structure containing the inputs to the sn_send_rc_command() Qualcomm Navigator API function.
std::array<float, kNumRcCommands> snav_fci::RcCommand::commands |
Dimensionless commands in the range [-1, 1].
|
static |
Number of RC commands is 4 as defined by the Qualcomm Navigator API
SnRcCommandOptions snav_fci::RcCommand::options |
Options for RC commands.
SnRcCommandType snav_fci::RcCommand::type |
Specifies how the commands should be interpreted.