PX4 Firmware
PX4 Autopilot Software http://px4.io
vmount::OutputBase Class Referenceabstract

class OutputBase Base class for all driver output classes More...

#include <output.h>

Inheritance diagram for vmount::OutputBase:
Collaboration diagram for vmount::OutputBase:

Public Member Functions

 OutputBase (const OutputConfig &output_config)
 
virtual ~OutputBase ()
 
virtual int initialize ()
 
virtual int update (const ControlData *control_data)=0
 Update the output. More...
 
virtual void print_status ()=0
 report status to stdout More...
 
void publish ()
 Publish _angle_outputs as a mount_orientation message. More...
 

Protected Member Functions

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

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
 

Private Attributes

int _vehicle_attitude_sub = -1
 
int _vehicle_global_position_sub = -1
 
orb_advert_t _mount_orientation_pub = nullptr
 

Detailed Description

class OutputBase Base class for all driver output classes

Definition at line 76 of file output.h.

Constructor & Destructor Documentation

◆ OutputBase()

vmount::OutputBase::OutputBase ( const OutputConfig output_config)

Definition at line 59 of file output.cpp.

References _last_update, and hrt_absolute_time().

Here is the call graph for this function:

◆ ~OutputBase()

vmount::OutputBase::~OutputBase ( )
virtual

Definition at line 65 of file output.cpp.

References _mount_orientation_pub, _vehicle_attitude_sub, _vehicle_global_position_sub, orb_unadvertise(), and orb_unsubscribe().

Here is the call graph for this function:

Member Function Documentation

◆ _calculate_output_angles()

void vmount::OutputBase::_calculate_output_angles ( const hrt_abstime t)
protected

calculate the _angle_outputs (with speed) and stabilize if needed

Definition at line 201 of file output.cpp.

References _angle_outputs, _angle_setpoints, _angle_speeds, _last_update, _stabilize, _vehicle_attitude_sub, dt, M_PI_F, orb_copy(), ORB_ID, and vehicle_attitude_s::q.

Referenced by vmount::OutputMavlink::update(), and vmount::OutputRC::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _calculate_pitch()

float vmount::OutputBase::_calculate_pitch ( double  lon,
double  lat,
float  altitude,
const vehicle_global_position_s global_position 
)
protected

Definition at line 105 of file output.cpp.

References _projection_reference, vehicle_global_position_s::alt, vehicle_global_position_s::lat, vehicle_global_position_s::lon, map_projection_init(), map_projection_initialized(), and map_projection_project().

Referenced by _handle_position_update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _get_vehicle_attitude_sub()

int vmount::OutputBase::_get_vehicle_attitude_sub ( ) const
inlineprotected

Definition at line 122 of file output.h.

◆ _handle_position_update()

void vmount::OutputBase::_handle_position_update ( bool  force_update = false)
protected

◆ _set_angle_setpoints()

void vmount::OutputBase::_set_angle_setpoints ( const ControlData control_data)
protected

set angle setpoints, speeds & stabilize flags

Definition at line 122 of file output.cpp.

References _angle_setpoints, _angle_speeds, _cur_control_data, _handle_position_update(), _stabilize, vmount::ControlData::Angle, vmount::ControlData::TypeData::angle, vmount::ControlData::TypeData::TypeAngle::angles, vmount::ControlData::TypeData::TypeAngle::is_speed, vmount::ControlData::LonLat, vmount::ControlData::Neutral, vmount::ControlData::stabilize_axis, vmount::ControlData::type, and vmount::ControlData::type_data.

Referenced by vmount::OutputMavlink::update(), and vmount::OutputRC::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize()

int vmount::OutputBase::initialize ( )
virtual

Definition at line 80 of file output.cpp.

References _vehicle_attitude_sub, _vehicle_global_position_sub, ORB_ID, and orb_subscribe().

Referenced by vmount_thread_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_status()

virtual void vmount::OutputBase::print_status ( )
pure virtual

report status to stdout

Implemented in vmount::OutputRC, and vmount::OutputMavlink.

Referenced by vmount_main().

Here is the caller graph for this function:

◆ publish()

void vmount::OutputBase::publish ( )

Publish _angle_outputs as a mount_orientation message.

Definition at line 93 of file output.cpp.

References _angle_outputs, _mount_orientation_pub, mount_orientation_s::attitude_euler_angle, ll40ls::instance, ORB_ID, ORB_PRIO_DEFAULT, and orb_publish_auto().

Referenced by vmount_thread_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update()

virtual int vmount::OutputBase::update ( const ControlData control_data)
pure virtual

Update the output.

Parameters
datanew command if non null
Returns
0 on success, <0 otherwise

Implemented in vmount::OutputRC, and vmount::OutputMavlink.

Referenced by vmount_thread_main().

Here is the caller graph for this function:

Member Data Documentation

◆ _angle_outputs

float vmount::OutputBase::_angle_outputs[3] = { 0.f, 0.f, 0.f }
protected

calculated output angles (roll, pitch, yaw) [rad]

Definition at line 119 of file output.h.

Referenced by _calculate_output_angles(), publish(), vmount::OutputMavlink::update(), and vmount::OutputRC::update().

◆ _angle_setpoints

float vmount::OutputBase::_angle_setpoints[3] = { 0.f, 0.f, 0.f }
protected

[rad]

Definition at line 112 of file output.h.

Referenced by _calculate_output_angles(), _handle_position_update(), and _set_angle_setpoints().

◆ _angle_speeds

float vmount::OutputBase::_angle_speeds[3] = { 0.f, 0.f, 0.f }
protected

Definition at line 113 of file output.h.

Referenced by _calculate_output_angles(), and _set_angle_setpoints().

◆ _config

const OutputConfig& vmount::OutputBase::_config
protected

Definition at line 103 of file output.h.

Referenced by vmount::OutputMavlink::update(), and vmount::OutputRC::update().

◆ _cur_control_data

const ControlData* vmount::OutputBase::_cur_control_data = nullptr
protected

Definition at line 111 of file output.h.

Referenced by _handle_position_update(), and _set_angle_setpoints().

◆ _last_update

hrt_abstime vmount::OutputBase::_last_update
protected

◆ _mount_orientation_pub

orb_advert_t vmount::OutputBase::_mount_orientation_pub = nullptr
private

Definition at line 128 of file output.h.

Referenced by publish(), and ~OutputBase().

◆ _projection_reference

map_projection_reference_s vmount::OutputBase::_projection_reference = {}
protected

reference to convert (lon, lat) to local [m]

Definition at line 101 of file output.h.

Referenced by _calculate_pitch().

◆ _stabilize

bool vmount::OutputBase::_stabilize[3] = { false, false, false }
protected

Definition at line 114 of file output.h.

Referenced by _calculate_output_angles(), and _set_angle_setpoints().

◆ _vehicle_attitude_sub

int vmount::OutputBase::_vehicle_attitude_sub = -1
private

Definition at line 125 of file output.h.

Referenced by _calculate_output_angles(), initialize(), and ~OutputBase().

◆ _vehicle_global_position_sub

int vmount::OutputBase::_vehicle_global_position_sub = -1
private

Definition at line 126 of file output.h.

Referenced by _handle_position_update(), initialize(), and ~OutputBase().


The documentation for this class was generated from the following files: