|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
class OutputMavlink Output via vehicle_command topic More...
#include <output_mavlink.h>
Public Member Functions | |
| OutputMavlink (const OutputConfig &output_config) | |
| virtual | ~OutputMavlink ()=default |
| virtual int | update (const ControlData *control_data) |
| Update the output. More... | |
| virtual void | print_status () |
| report status to stdout More... | |
Public Member Functions inherited from vmount::OutputBase | |
| OutputBase (const OutputConfig &output_config) | |
| virtual | ~OutputBase () |
| virtual int | initialize () |
| void | publish () |
| Publish _angle_outputs as a mount_orientation message. More... | |
Private Attributes | |
| uORB::PublicationQueued< vehicle_command_s > | _vehicle_command_pub {ORB_ID(vehicle_command)} |
Additional Inherited Members | |
Protected Member Functions inherited from vmount::OutputBase | |
| float | _calculate_pitch (double lon, double lat, float altitude, const vehicle_global_position_s &global_position) |
| void | _set_angle_setpoints (const ControlData *control_data) |
| set angle setpoints, speeds & stabilize flags More... | |
| void | _handle_position_update (bool force_update=false) |
| check if vehicle position changed and update the setpoint angles if in gps mode More... | |
| void | _calculate_output_angles (const hrt_abstime &t) |
| calculate the _angle_outputs (with speed) and stabilize if needed More... | |
| int | _get_vehicle_attitude_sub () const |
Protected Attributes inherited from vmount::OutputBase | |
| map_projection_reference_s | _projection_reference = {} |
| reference to convert (lon, lat) to local [m] More... | |
| const OutputConfig & | _config |
| const ControlData * | _cur_control_data = nullptr |
| float | _angle_setpoints [3] = { 0.f, 0.f, 0.f } |
| [rad] More... | |
| float | _angle_speeds [3] = { 0.f, 0.f, 0.f } |
| bool | _stabilize [3] = { false, false, false } |
| float | _angle_outputs [3] = { 0.f, 0.f, 0.f } |
| calculated output angles (roll, pitch, yaw) [rad] More... | |
| hrt_abstime | _last_update |
class OutputMavlink Output via vehicle_command topic
Definition at line 53 of file output_mavlink.h.
| vmount::OutputMavlink::OutputMavlink | ( | const OutputConfig & | output_config | ) |
Definition at line 52 of file output_mavlink.cpp.
|
virtualdefault |
|
virtual |
report status to stdout
Implements vmount::OutputBase.
Definition at line 103 of file output_mavlink.cpp.
|
virtual |
Update the output.
| data | new command if non null |
Implements vmount::OutputBase.
Definition at line 57 of file output_mavlink.cpp.
References vmount::OutputBase::_angle_outputs, vmount::OutputBase::_calculate_output_angles(), vmount::OutputBase::_config, vmount::OutputBase::_handle_position_update(), vmount::OutputBase::_last_update, vmount::OutputBase::_set_angle_setpoints(), _vehicle_command_pub, hrt_absolute_time(), hrt_abstime, vmount::OutputConfig::mavlink_comp_id, vmount::OutputConfig::mavlink_sys_id, vmount::ControlData::Neutral, vmount::OutputConfig::pitch_offset, uORB::PublicationQueued< T >::publish(), vmount::OutputConfig::roll_offset, vehicle_command_s::timestamp, vmount::ControlData::type, and vmount::OutputConfig::yaw_offset.
|
private |
Definition at line 65 of file output_mavlink.h.
Referenced by update().