Browse Source

AP_Mount: block forwarding of MAVlink by bitmask

master
proficnc 9 years ago committed by Andrew Tridgell
parent
commit
20a569a4d5
  1. 4
      libraries/AP_Mount/AP_Mount_SoloGimbal.cpp

4
libraries/AP_Mount/AP_Mount_SoloGimbal.cpp

@ -8,6 +8,7 @@ @@ -8,6 +8,7 @@
#include "SoloGimbal.h"
#include <DataFlash/DataFlash.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;
@ -107,6 +108,9 @@ void AP_Mount_SoloGimbal::status_msg(mavlink_channel_t chan) @@ -107,6 +108,9 @@ void AP_Mount_SoloGimbal::status_msg(mavlink_channel_t chan)
if (_gimbal.aligned()) {
mavlink_msg_mount_status_send(chan, 0, 0, degrees(_angle_ef_target_rad.y)*100, degrees(_angle_ef_target_rad.x)*100, degrees(_angle_ef_target_rad.z)*100);
}
// block heartbeat from transmitting to the GCS
GCS_MAVLINK::disable_channel_routing(chan);
}
/*

Loading…
Cancel
Save