| PX4 Firmware
    PX4 Autopilot Software http://px4.io | 
class OutputRC Output via actuator_controls_2 topic More...
#include <output_rc.h>
| Public Member Functions | |
| OutputRC (const OutputConfig &output_config) | |
| virtual | ~OutputRC () | 
| 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 | |
| orb_advert_t | _actuator_controls_pub = nullptr | 
| bool | _retract_gimbal = true | 
| 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 OutputRC Output via actuator_controls_2 topic
Definition at line 55 of file output_rc.h.
| vmount::OutputRC::OutputRC | ( | const OutputConfig & | output_config | ) | 
Definition at line 50 of file output_rc.cpp.
| 
 | virtual | 
Definition at line 54 of file output_rc.cpp.
References _actuator_controls_pub, and orb_unadvertise().
| 
 | virtual | 
| 
 | virtual | 
Update the output.
| data | new command if non null | 
Implements vmount::OutputBase.
Definition at line 61 of file output_rc.cpp.
References _actuator_controls_pub, vmount::OutputBase::_angle_outputs, vmount::OutputBase::_calculate_output_angles(), vmount::OutputBase::_config, vmount::OutputBase::_handle_position_update(), vmount::OutputBase::_last_update, _retract_gimbal, vmount::OutputBase::_set_angle_setpoints(), actuator_controls, actuator_controls_s::control, vmount::OutputConfig::gimbal_normal_mode_value, vmount::OutputConfig::gimbal_retracted_mode_value, vmount::ControlData::gimbal_shutter_retract, hrt_absolute_time(), hrt_abstime, ll40ls::instance, ORB_ID, ORB_PRIO_DEFAULT, orb_publish_auto(), vmount::OutputConfig::pitch_offset, vmount::OutputConfig::pitch_scale, vmount::OutputConfig::roll_offset, vmount::OutputConfig::roll_scale, actuator_controls_s::timestamp, vmount::OutputConfig::yaw_offset, and vmount::OutputConfig::yaw_scale.
| 
 | private | 
Definition at line 66 of file output_rc.h.
Referenced by update(), and ~OutputRC().
| 
 | private | 
Definition at line 67 of file output_rc.h.
Referenced by update().