82 virtual int initialize();
89 virtual int update(
const ControlData *control_data) = 0;
98 float _calculate_pitch(
double lon,
double lat,
float altitude,
106 void _set_angle_setpoints(
const ControlData *control_data);
109 void _handle_position_update(
bool force_update =
false);
112 float _angle_setpoints[3] = { 0.f, 0.f, 0.f };
113 float _angle_speeds[3] = { 0.f, 0.f, 0.f };
114 bool _stabilize[3] = {
false,
false,
false };
117 void _calculate_output_angles(
const hrt_abstime &t);
119 float _angle_outputs[3] = { 0.f, 0.f, 0.f };
125 int _vehicle_attitude_sub = -1;
126 int _vehicle_global_position_sub = -1;
uint32_t mavlink_sys_id
Mavlink target system id for mavlink output.
float pitch_offset
Offset for pitch channel in radians.
float yaw_scale
Scale factor for yaw channel (maps from angle in radians to actuator output in [-1,1]).
API for the uORB lightweight object broker.
Definition of geo / math functions to perform geodesic calculations.
const OutputConfig & _config
int _get_vehicle_attitude_sub() const
float yaw_offset
Offset for yaw channel in radians.
High-resolution timer with callouts and timekeeping.
float gimbal_normal_mode_value
Mixer output value for selecting gimbal normal mode.
float gimbal_retracted_mode_value
Mixer output value for selecting gimbal retracted mode.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
This defines the common API between an input and an output of the vmount driver.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
float pitch_scale
Scale factor for pitch channel (maps from angle in radians to actuator output in [-1,1]).
float roll_scale
Scale factor for roll channel (maps from angle in radians to actuator output in [-1,1]).
class OutputBase Base class for all driver output classes
float roll_offset
Offset for roll channel in radians.