Skip to content

Commit

Permalink
GCS_MAVLink: debug output of viso quality and rate -- do not merge
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Feb 24, 2024
1 parent 723271c commit e0bf248
Showing 1 changed file with 11 additions and 0 deletions.
11 changes: 11 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3700,6 +3700,17 @@ void GCS_MAVLINK::handle_odometry(const mavlink_message_t &msg)
Vector3f vel{m.vx, m.vy, m.vz};
vel = q * vel;
visual_odom->handle_vision_speed_estimate(m.time_usec, timestamp_ms, vel, m.reset_counter, m.quality);

// debug
static uint32_t last_print_ms = 0;
static uint16_t received_count = 0;
uint32_t now_ms = AP_HAL::millis();
received_count++;
if (now_ms - last_print_ms > 1000) {
last_print_ms = now_ms;
gcs().send_text(MAV_SEVERITY_INFO, "Odom Qual:%d hz:%d", (int)m.quality,(int)received_count);
received_count = 0;
}
}

// there are several messages which all have identical fields in them.
Expand Down

0 comments on commit e0bf248

Please sign in to comment.