PX4 Firmware
PX4 Autopilot Software http://px4.io
|
This defines the common API between an input and an output of the vmount driver. More...
#include <common.h>
Classes | |
union | TypeData |
Public Types | |
enum | Type : uint8_t { Type::Neutral = 0, Type::Angle, Type::LonLat } |
Public Attributes | |
Type | type = Type::Neutral |
union vmount::ControlData::TypeData | type_data |
bool | stabilize_axis [3] = { false, false, false } |
whether the vmount driver should stabilize an axis (if the output supports it, this can also be done externally) More... | |
bool | gimbal_shutter_retract = false |
whether to lock the gimbal (only in RC output mode) More... | |
This defines the common API between an input and an output of the vmount driver.
Each output must support the (full) set of the commands, and an input can create all or a subset of the types.
|
strong |
bool vmount::ControlData::gimbal_shutter_retract = false |
whether to lock the gimbal (only in RC output mode)
Definition at line 88 of file common.h.
Referenced by vmount::InputRC::_read_control_data_from_subscription(), vmount::OutputRC::update(), vmount::InputTest::update(), vmount::InputBase::update(), vmount::InputMavlinkROI::update_impl(), and vmount::InputMavlinkCmdMount::update_impl().
bool vmount::ControlData::stabilize_axis[3] = { false, false, false } |
whether the vmount driver should stabilize an axis (if the output supports it, this can also be done externally)
Definition at line 85 of file common.h.
Referenced by vmount::InputRC::_read_control_data_from_subscription(), vmount::OutputBase::_set_angle_setpoints(), vmount::InputTest::update(), vmount::InputMavlinkROI::update_impl(), and vmount::InputMavlinkCmdMount::update_impl().
Type vmount::ControlData::type = Type::Neutral |
Definition at line 64 of file common.h.
Referenced by vmount::OutputBase::_handle_position_update(), vmount::InputRC::_read_control_data_from_subscription(), vmount::OutputBase::_set_angle_setpoints(), vmount::InputBase::control_data_set_lon_lat(), vmount::OutputMavlink::update(), vmount::InputTest::update(), vmount::InputBase::update(), vmount::InputMavlinkROI::update_impl(), and vmount::InputMavlinkCmdMount::update_impl().
union vmount::ControlData::TypeData vmount::ControlData::type_data |
Referenced by vmount::OutputBase::_handle_position_update(), vmount::InputMavlinkROI::_read_control_data_from_position_setpoint_sub(), vmount::InputRC::_read_control_data_from_subscription(), vmount::OutputBase::_set_angle_setpoints(), vmount::InputBase::control_data_set_lon_lat(), vmount::InputTest::update(), vmount::InputMavlinkROI::update_impl(), and vmount::InputMavlinkCmdMount::update_impl().