mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: use send_to_active_channels for parameters
This commit is contained in:
parent
7780e8ed00
commit
a2c4bfea0c
@ -304,21 +304,16 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg)
|
||||
*/
|
||||
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) {
|
||||
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,
|
||||
param_name,
|
||||
param_value,
|
||||
mav_param_type(param_type),
|
||||
AP_Param::count_parameters(),
|
||||
-1);
|
||||
}
|
||||
}
|
||||
}
|
||||
mavlink_param_value_t packet;
|
||||
strncpy(packet.param_id, param_name, ARRAY_SIZE(packet.param_id));
|
||||
packet.param_value = param_value;
|
||||
packet.param_type = mav_param_type(param_type);
|
||||
packet.param_count = AP_Param::count_parameters();
|
||||
packet.param_index = -1;
|
||||
|
||||
gcs().send_to_active_channels(MAVLINK_MSG_ID_PARAM_VALUE,
|
||||
(const char *)&packet);
|
||||
|
||||
// also log to AP_Logger
|
||||
AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger != nullptr) {
|
||||
|
Loading…
Reference in New Issue
Block a user