Browse Source

GCS_MAVLink: stop passing dataflash into handle_radio_status

It can use the singleton instead
master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
778bff966c
  1. 3
      libraries/GCS_MAVLink/GCS.h
  2. 5
      libraries/GCS_MAVLink/GCS_Common.cpp

3
libraries/GCS_MAVLink/GCS.h

@ -6,7 +6,6 @@ @@ -6,7 +6,6 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "GCS_MAVLink.h"
#include <AP_Logger/AP_Logger.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <stdint.h>
@ -360,7 +359,7 @@ protected: @@ -360,7 +359,7 @@ protected:
virtual void handle_mount_message(const mavlink_message_t *msg);
void handle_fence_message(mavlink_message_t *msg);
void handle_param_value(mavlink_message_t *msg);
void handle_radio_status(mavlink_message_t *msg, AP_Logger &dataflash, bool log_radio);
void handle_radio_status(mavlink_message_t *msg, bool log_radio);
void handle_serial_control(const mavlink_message_t *msg);
void handle_vision_position_delta(mavlink_message_t *msg);

5
libraries/GCS_MAVLink/GCS_Common.cpp

@ -17,6 +17,7 @@ @@ -17,6 +17,7 @@
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_RangeFinder/RangeFinder_Backend.h>
@ -694,7 +695,7 @@ void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...) @@ -694,7 +695,7 @@ void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
va_end(arg_list);
}
void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, AP_Logger &dataflash, bool log_radio)
void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, bool log_radio)
{
mavlink_radio_t packet;
mavlink_msg_radio_decode(msg, &packet);
@ -730,7 +731,7 @@ void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, AP_Logger &datafla @@ -730,7 +731,7 @@ void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, AP_Logger &datafla
//log rssi, noise, etc if logging Performance monitoring data
if (log_radio) {
dataflash.Write_Radio(packet);
AP::logger().Write_Radio(packet);
}
}

Loading…
Cancel
Save