Browse Source

GCS_MAVLink: make DataFlash a pointer

handle sketches where DataFlash is not available
mission-4.1.18
Andrew Tridgell 11 years ago committed by Randy Mackay
parent
commit
965f6bd3bd
  1. 2
      libraries/GCS_MAVLink/GCS.h
  2. 6
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS.h

@ -299,7 +299,7 @@ private: @@ -299,7 +299,7 @@ private:
void handle_request_data_stream(mavlink_message_t *msg, bool save);
void handle_param_request_list(mavlink_message_t *msg);
void handle_param_request_read(mavlink_message_t *msg);
void handle_param_set(mavlink_message_t *msg, DataFlash_Class &DataFlash);
void handle_param_set(mavlink_message_t *msg, DataFlash_Class *DataFlash);
void handle_radio_status(mavlink_message_t *msg);
// return true if this channel has hardware flow control

6
libraries/GCS_MAVLink/GCS_Common.cpp

@ -518,7 +518,7 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg) @@ -518,7 +518,7 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg)
packet.param_index);
}
void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class &DataFlash)
void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class *DataFlash)
{
AP_Param *vp;
enum ap_var_type var_type;
@ -581,7 +581,9 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class &Data @@ -581,7 +581,9 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class &Data
mav_var_type(var_type),
_count_parameters(),
-1); // XXX we don't actually know what its index is...
DataFlash.Log_Write_Parameter(key, vp->cast_to_float(var_type));
if (DataFlash != NULL) {
DataFlash->Log_Write_Parameter(key, vp->cast_to_float(var_type));
}
}
}

Loading…
Cancel
Save