mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_Mount: block forwarding of MAVlink by bitmask
This commit is contained in:
parent
c8b3c527f9
commit
20a569a4d5
@ -8,6 +8,7 @@
|
|||||||
#include "SoloGimbal.h"
|
#include "SoloGimbal.h"
|
||||||
#include <DataFlash/DataFlash.h>
|
#include <DataFlash/DataFlash.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -107,6 +108,9 @@ void AP_Mount_SoloGimbal::status_msg(mavlink_channel_t chan)
|
|||||||
if (_gimbal.aligned()) {
|
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);
|
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…
Reference in New Issue
Block a user