PX4 Firmware
PX4 Autopilot Software http://px4.io
|
class InputRC RC input class using manual_control_setpoint topic More...
#include <input_rc.h>
Public Member Functions | |
InputRC (bool do_stabilization, int aux_channel_roll, int aux_channel_pitch, int aux_channel_yaw) | |
virtual | ~InputRC () |
virtual void | print_status () |
report status to stdout More... | |
Public Member Functions inherited from vmount::InputBase | |
virtual | ~InputBase () |
virtual int | update (unsigned int timeout_ms, ControlData **control_data, bool already_active) |
Wait for an input update, with a timeout. More... | |
Protected Member Functions | |
virtual int | update_impl (unsigned int timeout_ms, ControlData **control_data, bool already_active) |
virtual int | initialize () |
virtual bool | _read_control_data_from_subscription (ControlData &control_data, bool already_active) |
int | _get_subscription_fd () const |
float | _get_aux_value (const manual_control_setpoint_s &manual_control_setpoint, int channel_idx) |
Protected Member Functions inherited from vmount::InputBase | |
void | control_data_set_lon_lat (double lon, double lat, float altitude, float roll_angle=0.f, float pitch_fixed_angle=-10.f) |
Private Attributes | |
const bool | _do_stabilization |
int | _aux_channels [3] |
int | _manual_control_setpoint_sub = -1 |
bool | _first_time = true |
float | _last_set_aux_values [3] = {} |
Additional Inherited Members | |
Protected Attributes inherited from vmount::InputBase | |
ControlData | _control_data |
class InputRC RC input class using manual_control_setpoint topic
Definition at line 55 of file input_rc.h.
vmount::InputRC::InputRC | ( | bool | do_stabilization, |
int | aux_channel_roll, | ||
int | aux_channel_pitch, | ||
int | aux_channel_yaw | ||
) |
do_stabilization | |
aux_channel_roll | which aux channel to use for roll (set to 0 to use a fixed angle of 0) |
aux_channel_pitch | |
aux_channel_yaw |
Definition at line 52 of file input_rc.cpp.
References _aux_channels.
|
virtual |
Definition at line 60 of file input_rc.cpp.
References _manual_control_setpoint_sub, and orb_unsubscribe().
|
protected |
Definition at line 150 of file input_rc.cpp.
References _aux_channels, manual_control_setpoint_s::aux1, manual_control_setpoint_s::aux2, manual_control_setpoint_s::aux3, manual_control_setpoint_s::aux4, manual_control_setpoint_s::aux5, and manual_control_setpoint_s::aux6.
Referenced by _get_subscription_fd(), and _read_control_data_from_subscription().
|
inlineprotected |
Definition at line 79 of file input_rc.h.
References _get_aux_value(), and _manual_control_setpoint_sub.
|
protectedvirtual |
Definition at line 107 of file input_rc.cpp.
References _do_stabilization, _first_time, _get_aux_value(), _last_set_aux_values, _manual_control_setpoint_sub, vmount::ControlData::Angle, vmount::ControlData::TypeData::angle, vmount::ControlData::TypeData::TypeAngle::angles, f(), vmount::ControlData::gimbal_shutter_retract, vmount::ControlData::TypeData::TypeAngle::is_speed, M_PI_F, orb_copy(), ORB_ID, vmount::ControlData::stabilize_axis, vmount::ControlData::type, and vmount::ControlData::type_data.
Referenced by update_impl().
|
protectedvirtual |
Reimplemented from vmount::InputBase.
Definition at line 67 of file input_rc.cpp.
References _manual_control_setpoint_sub, ORB_ID, and orb_subscribe().
|
virtual |
report status to stdout
Implements vmount::InputBase.
Definition at line 177 of file input_rc.cpp.
References _aux_channels.
|
protectedvirtual |
Implements vmount::InputBase.
Definition at line 78 of file input_rc.cpp.
References vmount::InputBase::_control_data, _manual_control_setpoint_sub, _read_control_data_from_subscription(), and px4_poll().
|
private |
Definition at line 85 of file input_rc.h.
Referenced by _get_aux_value(), InputRC(), and print_status().
|
private |
Definition at line 84 of file input_rc.h.
Referenced by _read_control_data_from_subscription().
|
private |
Definition at line 88 of file input_rc.h.
Referenced by _read_control_data_from_subscription().
|
private |
Definition at line 89 of file input_rc.h.
Referenced by _read_control_data_from_subscription().
|
private |
Definition at line 86 of file input_rc.h.
Referenced by _get_subscription_fd(), _read_control_data_from_subscription(), initialize(), update_impl(), and ~InputRC().