PX4 Firmware
PX4 Autopilot Software http://px4.io
|
class InputMavlinkCmdMount Input based on the VEHICLE_CMD_DO_MOUNT_CONTROL mavlink command More...
#include <input_mavlink.h>
Public Member Functions | |
InputMavlinkCmdMount (bool stabilize) | |
virtual | ~InputMavlinkCmdMount () |
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 () |
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 Member Functions | |
void | _ack_vehicle_command (vehicle_command_s *cmd) |
Private Attributes | |
int | _vehicle_command_sub = -1 |
bool | _stabilize [3] = { false, false, false } |
int32_t | _mav_sys_id {1} |
our mavlink system id More... | |
int32_t | _mav_comp_id {1} |
our mavlink component id More... | |
Additional Inherited Members | |
Protected Attributes inherited from vmount::InputBase | |
ControlData | _control_data |
class InputMavlinkCmdMount Input based on the VEHICLE_CMD_DO_MOUNT_CONTROL mavlink command
Definition at line 80 of file input_mavlink.h.
vmount::InputMavlinkCmdMount::InputMavlinkCmdMount | ( | bool | stabilize | ) |
Definition at line 178 of file input_mavlink.cpp.
References _mav_comp_id, _mav_sys_id, param_find(), param_get(), and PARAM_INVALID.
|
virtual |
Definition at line 194 of file input_mavlink.cpp.
References _vehicle_command_sub, and orb_unsubscribe().
|
private |
Definition at line 334 of file input_mavlink.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 update_impl().
|
protectedvirtual |
Reimplemented from vmount::InputBase.
Definition at line 201 of file input_mavlink.cpp.
References _vehicle_command_sub, ORB_ID, orb_set_interval(), and orb_subscribe().
|
virtual |
report status to stdout
Implements vmount::InputBase.
Definition at line 348 of file input_mavlink.cpp.
|
protectedvirtual |
Implements vmount::InputBase.
Definition at line 216 of file input_mavlink.cpp.
References _ack_vehicle_command(), vmount::InputBase::_control_data, _mav_comp_id, _mav_sys_id, _stabilize, _vehicle_command_sub, vmount::ControlData::Angle, vmount::ControlData::TypeData::angle, vmount::ControlData::TypeData::TypeAngle::angles, vehicle_command_s::command, vmount::InputBase::control_data_set_lon_lat(), vmount::ControlData::gimbal_shutter_retract, hrt_absolute_time(), hrt_abstime, vmount::ControlData::TypeData::TypeAngle::is_speed, M_PI_F, vmount::ControlData::Neutral, orb_copy(), ORB_ID, vehicle_command_s::param1, vehicle_command_s::param2, vehicle_command_s::param3, vehicle_command_s::param4, vehicle_command_s::param7, px4_poll(), vmount::ControlData::stabilize_axis, vehicle_command_s::target_component, vehicle_command_s::target_system, vmount::ControlData::type, and vmount::ControlData::type_data.
|
private |
our mavlink component id
Definition at line 99 of file input_mavlink.h.
Referenced by InputMavlinkCmdMount(), and update_impl().
|
private |
our mavlink system id
Definition at line 98 of file input_mavlink.h.
Referenced by InputMavlinkCmdMount(), and update_impl().
|
private |
Definition at line 96 of file input_mavlink.h.
Referenced by update_impl().
|
private |
Definition at line 95 of file input_mavlink.h.
Referenced by initialize(), update_impl(), and ~InputMavlinkCmdMount().