vmount: set correct MAV_MOUNT_MODE

This commit is contained in:
Julian Oes 2019-11-22 16:10:16 +01:00 committed by Lorenz Meier
parent bbd37ada41
commit 1e8ebe20d1
1 changed files with 2 additions and 1 deletions

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
* Copyright (c) 2016-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -91,6 +91,7 @@ int OutputMavlink::update(const ControlData *control_data)
vehicle_command.param1 = (_angle_outputs[1] + _config.pitch_offset) * M_RAD_TO_DEG_F;
vehicle_command.param2 = (_angle_outputs[0] + _config.roll_offset) * M_RAD_TO_DEG_F;
vehicle_command.param3 = (_angle_outputs[2] + _config.yaw_offset) * M_RAD_TO_DEG_F;
vehicle_command.param7 = 2.0f; // MAV_MOUNT_MODE_MAVLINK_TARGETING;
_vehicle_command_pub.publish(vehicle_command);