GCS_MAVLink: make send_parameter_value_all a GCS method rather than static

This commit is contained in:
Peter Barker 2018-03-12 09:50:51 +11:00 committed by Andrew Tridgell
parent 1a640e3405
commit bf124e9333
2 changed files with 10 additions and 7 deletions

View File

@ -187,9 +187,6 @@ public:
// return a bitmap of streaming channels
static uint8_t streaming_channel_mask(void) { return chan_is_streaming; }
// send a PARAM_VALUE message to all active MAVLink connections.
static void send_parameter_value_all(const char *param_name, ap_var_type param_type, float param_value);
// send queued parameters if needed
void send_queued_parameters(void);
@ -522,6 +519,11 @@ public:
void send_mission_item_reached_message(uint16_t mission_index);
void send_home(const Location &home) const;
void send_ekf_origin(const Location &ekf_origin) const;
void send_parameter_value(const char *param_name,
ap_var_type param_type,
float param_value);
// push send_message() messages and queued statustext messages etc:
void retry_deferred();
void data_stream_send();

View File

@ -322,14 +322,15 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
/*
send a parameter value message to all active MAVLink connections
*/
void GCS_MAVLINK::send_parameter_value_all(const char *param_name, ap_var_type param_type, float param_value)
void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
{
const uint8_t mavlink_active = GCS_MAVLINK::active_channel_mask();
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
if ((1U<<i) & mavlink_active) {
mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
if (HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
const mavlink_channel_t _chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
if (HAVE_PAYLOAD_SPACE(_chan, PARAM_VALUE)) {
mavlink_msg_param_value_send(
chan,
_chan,
param_name,
param_value,
mav_var_type(param_type),