PX4 Firmware
PX4 Autopilot Software http://px4.io
|
class InputBase Base class for all driver input classes More...
#include <input.h>
Public Member Functions | |
virtual | ~InputBase () |
virtual int | update (unsigned int timeout_ms, ControlData **control_data, bool already_active) |
Wait for an input update, with a timeout. More... | |
virtual void | print_status ()=0 |
report status to stdout More... | |
Protected Member Functions | |
virtual int | update_impl (unsigned int timeout_ms, ControlData **control_data, bool already_active)=0 |
virtual int | initialize () |
void | control_data_set_lon_lat (double lon, double lat, float altitude, float roll_angle=0.f, float pitch_fixed_angle=-10.f) |
Protected Attributes | |
ControlData | _control_data |
Private Attributes | |
bool | _initialized = false |
|
inlinevirtual |
Definition at line 55 of file input.h.
References print_status(), timeout_ms, update(), and update_impl().
|
protected |
Definition at line 66 of file input.cpp.
References _control_data, vmount::ControlData::TypeData::TypeLonLat::altitude, vmount::ControlData::TypeData::TypeLonLat::lat, vmount::ControlData::TypeData::TypeLonLat::lon, vmount::ControlData::LonLat, vmount::ControlData::TypeData::lonlat, vmount::ControlData::TypeData::TypeLonLat::pitch_angle_offset, vmount::ControlData::TypeData::TypeLonLat::pitch_fixed_angle, vmount::ControlData::TypeData::TypeLonLat::roll_angle, vmount::ControlData::type, vmount::ControlData::type_data, and vmount::ControlData::TypeData::TypeLonLat::yaw_angle_offset.
Referenced by initialize(), vmount::InputMavlinkROI::update_impl(), and vmount::InputMavlinkCmdMount::update_impl().
|
inlineprotectedvirtual |
Reimplemented in vmount::InputMavlinkCmdMount, vmount::InputRC, vmount::InputTest, and vmount::InputMavlinkROI.
Definition at line 78 of file input.h.
References control_data_set_lon_lat(), and f().
Referenced by update().
|
pure virtual |
report status to stdout
Implemented in vmount::InputMavlinkCmdMount, vmount::InputTest, vmount::InputRC, and vmount::InputMavlinkROI.
Referenced by vmount_main(), and ~InputBase().
|
virtual |
Wait for an input update, with a timeout.
timeout_ms | timeout in ms |
control_data | unchanged on error. On success it is nullptr if no new data is available, otherwise set to an object. If it is set, the returned object will not be changed for subsequent calls to update() that return no new data (in other words: if (some) control_data values change, non-null will be returned). |
already_active | true if the mode was already active last time, false if it was not and "major" change is necessary such as big stick movement for RC. |
Reimplemented in vmount::InputTest.
Definition at line 46 of file input.cpp.
References _control_data, _initialized, vmount::ControlData::gimbal_shutter_retract, initialize(), vmount::ControlData::Neutral, vmount::ControlData::type, and update_impl().
Referenced by vmount_thread_main(), and ~InputBase().
|
protectedpure virtual |
Implemented in vmount::InputMavlinkCmdMount, vmount::InputRC, vmount::InputTest, and vmount::InputMavlinkROI.
Referenced by update(), and ~InputBase().
|
protected |
Definition at line 83 of file input.h.
Referenced by vmount::InputMavlinkROI::_read_control_data_from_position_setpoint_sub(), control_data_set_lon_lat(), vmount::InputTest::update(), update(), vmount::InputMavlinkROI::update_impl(), vmount::InputRC::update_impl(), and vmount::InputMavlinkCmdMount::update_impl().
|
private |