46 #include <px4_platform_common/defines.h> 68 vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE;
72 vehicle_command.param1 = vehicle_command_s::VEHICLE_MOUNT_MODE_NEUTRAL;
75 vehicle_command.param1 = vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING;
86 vehicle_command.timestamp = t;
87 vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL;
94 vehicle_command.param7 = 2.0f;
105 PX4_INFO(
"Output: Mavlink");
uint32_t mavlink_sys_id
Mavlink target system id for mavlink output.
float pitch_offset
Offset for pitch channel in radians.
void _handle_position_update(bool force_update=false)
check if vehicle position changed and update the setpoint angles if in gps mode
const OutputConfig & _config
bool publish(const T &data)
Publish the struct.
void _calculate_output_angles(const hrt_abstime &t)
calculate the _angle_outputs (with speed) and stabilize if needed
float yaw_offset
Offset for yaw channel in radians.
virtual int update(const ControlData *control_data)
Update the output.
uORB::PublicationQueued< vehicle_command_s > _vehicle_command_pub
__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.
void _set_angle_setpoints(const ControlData *control_data)
set angle setpoints, speeds & stabilize flags
float _angle_outputs[3]
calculated output angles (roll, pitch, yaw) [rad]
virtual void print_status()
report status to stdout
class OutputBase Base class for all driver output classes
float roll_offset
Offset for roll channel in radians.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
OutputMavlink(const OutputConfig &output_config)