Skip to content

Commit

Permalink
AntennaTracker: don't repeat the target angles in guided mode
Browse files Browse the repository at this point in the history
Prevents AT from spamming the messages when in GUIDED.

The implementation may miss back-and-forth changes that happen during the printing interval of 5 s, but it matches the original behavior in this aspect as well.
  • Loading branch information
landswellsong committed Jul 27, 2024
1 parent 2ce6532 commit 9214be1
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion AntennaTracker/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,23 @@
#include "Tracker.h"
#include <GCS_MAVLink/GCS.h>

constexpr uint32_t DEBUG_TIMEOUT = 5000;
constexpr float eps = 0.01f;

void ModeGuided::update()
{
static float last_target_yaw = NAN, last_target_pitch = NAN;
static uint32_t last_debug;
const uint32_t now = AP_HAL::millis();
float target_roll, target_pitch, target_yaw;
_target_att.to_euler(target_roll, target_pitch, target_yaw);
if (now - last_debug > 5000) {
bool yaw_changed = isnan(last_target_yaw) || fabsf(last_target_yaw - target_yaw) > eps;
bool pitch_changed = isnan(last_target_pitch) || fabsf(last_target_pitch - target_pitch) > eps;
if (now - last_debug > DEBUG_TIMEOUT && (yaw_changed || pitch_changed)) {
last_debug = now;
gcs().send_text(MAV_SEVERITY_INFO, "target_yaw=%f target_pitch=%f", degrees(target_yaw), degrees(target_pitch));
last_target_yaw = target_yaw;
last_target_pitch = target_pitch;
}
calc_angle_error(degrees(target_pitch)*100, degrees(target_yaw)*100, false);
float bf_pitch;
Expand Down

0 comments on commit 9214be1

Please sign in to comment.