2017-04-29 01:11:11 -03:00
|
|
|
/*
|
|
|
|
GCS MAVLink functions related to parameter handling
|
|
|
|
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
#include "GCS.h"
|
2019-04-04 07:49:44 -03:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2017-04-29 02:30:57 -03:00
|
|
|
// queue of pending parameter requests and replies
|
|
|
|
ObjectBuffer<GCS_MAVLINK::pending_param_request> GCS_MAVLINK::param_requests(20);
|
|
|
|
ObjectBuffer<GCS_MAVLINK::pending_param_reply> GCS_MAVLINK::param_replies(5);
|
|
|
|
|
|
|
|
bool GCS_MAVLINK::param_timer_registered;
|
|
|
|
|
2017-04-29 01:11:11 -03:00
|
|
|
/**
|
|
|
|
* @brief Send the next pending parameter, called from deferred message
|
|
|
|
* handling code
|
|
|
|
*/
|
|
|
|
void
|
|
|
|
GCS_MAVLINK::queued_param_send()
|
|
|
|
{
|
2019-03-13 22:22:04 -03:00
|
|
|
// send parameter async replies
|
|
|
|
uint8_t async_replies_sent_count = send_parameter_async_replies();
|
|
|
|
|
2019-03-13 22:11:34 -03:00
|
|
|
const uint32_t tnow = AP_HAL::millis();
|
|
|
|
const uint32_t tstart = AP_HAL::micros();
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
// use at most 30% of bandwidth on parameters. The constant 26 is
|
|
|
|
// 1/(1000 * 1/8 * 0.001 * 0.3)
|
2018-04-05 22:59:40 -03:00
|
|
|
const uint32_t link_bw = _port->bw_in_kilobytes_per_second();
|
|
|
|
|
2019-03-13 22:11:34 -03:00
|
|
|
uint32_t bytes_allowed = link_bw * (tnow - _queued_parameter_send_time_ms) * 26;
|
2018-04-05 22:59:40 -03:00
|
|
|
const uint16_t size_for_one_param_value_msg = MAVLINK_MSG_ID_PARAM_VALUE_LEN + packet_overhead();
|
|
|
|
if (bytes_allowed < size_for_one_param_value_msg) {
|
|
|
|
bytes_allowed = size_for_one_param_value_msg;
|
|
|
|
}
|
2017-04-29 01:11:11 -03:00
|
|
|
if (bytes_allowed > comm_get_txspace(chan)) {
|
|
|
|
bytes_allowed = comm_get_txspace(chan);
|
|
|
|
}
|
2019-03-13 22:11:34 -03:00
|
|
|
uint32_t count = bytes_allowed / size_for_one_param_value_msg;
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
// when we don't have flow control we really need to keep the
|
|
|
|
// param download very slow, or it tends to stall
|
|
|
|
if (!have_flow_control() && count > 5) {
|
|
|
|
count = 5;
|
|
|
|
}
|
2019-03-13 22:22:04 -03:00
|
|
|
if (async_replies_sent_count >= count) {
|
|
|
|
return;
|
2019-01-13 06:13:30 -04:00
|
|
|
}
|
2019-03-13 22:22:04 -03:00
|
|
|
count -= async_replies_sent_count;
|
2019-01-13 06:13:30 -04:00
|
|
|
|
|
|
|
if (_queued_parameter == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
while (count && _queued_parameter != nullptr) {
|
2017-04-29 01:11:11 -03:00
|
|
|
char param_name[AP_MAX_NAME_SIZE];
|
2018-12-17 23:13:17 -04:00
|
|
|
_queued_parameter->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
mavlink_msg_param_value_send(
|
|
|
|
chan,
|
|
|
|
param_name,
|
2018-12-17 23:13:17 -04:00
|
|
|
_queued_parameter->cast_to_float(_queued_parameter_type),
|
2019-02-06 22:55:46 -04:00
|
|
|
mav_param_type(_queued_parameter_type),
|
2017-04-29 01:11:11 -03:00
|
|
|
_queued_parameter_count,
|
|
|
|
_queued_parameter_index);
|
|
|
|
|
|
|
|
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
|
|
|
|
_queued_parameter_index++;
|
2017-04-29 02:53:39 -03:00
|
|
|
|
|
|
|
if (AP_HAL::micros() - tstart > 1000) {
|
|
|
|
// don't use more than 1ms sending blocks of parameters
|
|
|
|
break;
|
|
|
|
}
|
2019-01-13 06:13:30 -04:00
|
|
|
count--;
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
_queued_parameter_send_time_ms = tnow;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return true if a channel has flow control
|
|
|
|
*/
|
|
|
|
bool GCS_MAVLINK::have_flow_control(void)
|
|
|
|
{
|
2018-03-31 06:11:45 -03:00
|
|
|
if (_port == nullptr) {
|
2017-04-29 01:11:11 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-03-31 06:11:45 -03:00
|
|
|
if (_port->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE) {
|
|
|
|
return true;
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (chan == MAVLINK_COMM_0) {
|
|
|
|
// assume USB console has flow control
|
2018-03-31 06:11:45 -03:00
|
|
|
return hal.gpio->usb_connected();
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
2018-03-31 06:11:45 -03:00
|
|
|
|
|
|
|
return false;
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
handle a request to change stream rate. Note that copter passes in
|
|
|
|
save==false so we don't want the save to happen when the user connects the
|
|
|
|
ground station.
|
|
|
|
*/
|
2019-07-11 05:31:45 -03:00
|
|
|
void GCS_MAVLINK::handle_request_data_stream(const mavlink_message_t &msg)
|
2017-04-29 01:11:11 -03:00
|
|
|
{
|
|
|
|
mavlink_request_data_stream_t packet;
|
2019-07-11 05:31:45 -03:00
|
|
|
mavlink_msg_request_data_stream_decode(&msg, &packet);
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
int16_t freq = 0; // packet frequency
|
|
|
|
|
|
|
|
if (packet.start_stop == 0)
|
|
|
|
freq = 0; // stop sending
|
|
|
|
else if (packet.start_stop == 1)
|
|
|
|
freq = packet.req_message_rate; // start sending
|
|
|
|
else
|
|
|
|
return;
|
|
|
|
|
2018-05-20 23:18:57 -03:00
|
|
|
// if stream_id is still NUM_STREAMS at the end of this switch
|
|
|
|
// block then either we set stream rates for all streams, or we
|
|
|
|
// were asked to set the streamrate for an unrecognised stream
|
|
|
|
streams stream_id = NUM_STREAMS;
|
2017-04-29 01:11:11 -03:00
|
|
|
switch (packet.req_stream_id) {
|
|
|
|
case MAV_DATA_STREAM_ALL:
|
2018-05-20 23:18:57 -03:00
|
|
|
for (uint8_t i=0; i<NUM_STREAMS; i++) {
|
2019-01-13 16:47:31 -04:00
|
|
|
if (i == STREAM_PARAMS) {
|
|
|
|
// don't touch parameter streaming rate; it is
|
|
|
|
// considered "internal".
|
|
|
|
continue;
|
|
|
|
}
|
2018-05-21 09:34:22 -03:00
|
|
|
if (persist_streamrates()) {
|
2017-04-29 01:11:11 -03:00
|
|
|
streamRates[i].set_and_save_ifchanged(freq);
|
|
|
|
} else {
|
|
|
|
streamRates[i].set(freq);
|
|
|
|
}
|
2018-05-20 23:18:57 -03:00
|
|
|
initialise_message_intervals_for_stream((streams)i);
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_RAW_SENSORS:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_RAW_SENSORS;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_EXTENDED_STATUS:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_EXTENDED_STATUS;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_RC_CHANNELS:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_RC_CHANNELS;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_RAW_CONTROLLER:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_RAW_CONTROLLER;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_POSITION:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_POSITION;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_EXTRA1:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_EXTRA1;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_EXTRA2:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_EXTRA2;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
case MAV_DATA_STREAM_EXTRA3:
|
2018-05-20 23:18:57 -03:00
|
|
|
stream_id = STREAM_EXTRA3;
|
2017-04-29 01:11:11 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2018-05-20 23:18:57 -03:00
|
|
|
if (stream_id == NUM_STREAMS) {
|
|
|
|
// asked to set rate on unknown stream (or all were set already)
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_Int16 *rate = &streamRates[stream_id];
|
|
|
|
|
2017-04-29 01:11:11 -03:00
|
|
|
if (rate != nullptr) {
|
2018-05-21 09:34:22 -03:00
|
|
|
if (persist_streamrates()) {
|
2017-04-29 01:11:11 -03:00
|
|
|
rate->set_and_save_ifchanged(freq);
|
|
|
|
} else {
|
|
|
|
rate->set(freq);
|
|
|
|
}
|
2018-05-20 23:18:57 -03:00
|
|
|
initialise_message_intervals_for_stream(stream_id);
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void GCS_MAVLINK::handle_param_request_list(const mavlink_message_t &msg)
|
2017-04-29 01:11:11 -03:00
|
|
|
{
|
2017-08-19 08:23:19 -03:00
|
|
|
if (!params_ready()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-04-29 01:11:11 -03:00
|
|
|
mavlink_param_request_list_t packet;
|
2019-07-11 05:31:45 -03:00
|
|
|
mavlink_msg_param_request_list_decode(&msg, &packet);
|
2017-04-29 01:11:11 -03:00
|
|
|
|
2017-08-19 08:23:19 -03:00
|
|
|
// requesting parameters is a convenient way to get extra information
|
|
|
|
send_banner();
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
// Start sending parameters - next call to ::update will kick the first one out
|
|
|
|
_queued_parameter = AP_Param::first(&_queued_parameter_token, &_queued_parameter_type);
|
|
|
|
_queued_parameter_index = 0;
|
|
|
|
_queued_parameter_count = AP_Param::count_parameters();
|
2019-01-13 05:55:07 -04:00
|
|
|
_queued_parameter_send_time_ms = AP_HAL::millis(); // avoid initial flooding
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void GCS_MAVLINK::handle_param_request_read(const mavlink_message_t &msg)
|
2017-04-29 01:11:11 -03:00
|
|
|
{
|
2017-04-29 02:30:57 -03:00
|
|
|
if (param_requests.space() == 0) {
|
|
|
|
// we can't process this right now, drop it
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-04-29 01:11:11 -03:00
|
|
|
mavlink_param_request_read_t packet;
|
2019-07-11 05:31:45 -03:00
|
|
|
mavlink_msg_param_request_read_decode(&msg, &packet);
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
we reserve some space for sending parameters if the client ever
|
|
|
|
fails to get a parameter due to lack of space
|
|
|
|
*/
|
|
|
|
uint32_t saved_reserve_param_space_start_ms = reserve_param_space_start_ms;
|
2019-03-13 22:48:23 -03:00
|
|
|
reserve_param_space_start_ms = 0; // bypass packet_overhead_chan reservation checking
|
2017-04-29 01:11:11 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
|
|
|
|
reserve_param_space_start_ms = AP_HAL::millis();
|
2019-03-13 22:48:23 -03:00
|
|
|
} else {
|
|
|
|
reserve_param_space_start_ms = saved_reserve_param_space_start_ms;
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
2017-04-29 02:30:57 -03:00
|
|
|
|
|
|
|
struct pending_param_request req;
|
|
|
|
req.chan = chan;
|
|
|
|
req.param_index = packet.param_index;
|
2017-10-20 15:26:56 -03:00
|
|
|
memcpy(req.param_name, packet.param_id, MIN(sizeof(packet.param_id), sizeof(req.param_name)));
|
2017-04-29 02:30:57 -03:00
|
|
|
req.param_name[AP_MAX_NAME_SIZE] = 0;
|
|
|
|
|
|
|
|
// queue it for processing by io timer
|
|
|
|
param_requests.push(req);
|
2018-05-20 23:18:57 -03:00
|
|
|
|
|
|
|
// speaking of which, we'd best make sure it is running:
|
|
|
|
if (!param_timer_registered) {
|
|
|
|
param_timer_registered = true;
|
|
|
|
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::param_io_timer, void));
|
|
|
|
}
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
2017-05-10 03:30:20 -03:00
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg)
|
2017-04-29 01:11:11 -03:00
|
|
|
{
|
|
|
|
mavlink_param_set_t packet;
|
2019-07-11 05:31:45 -03:00
|
|
|
mavlink_msg_param_set_decode(&msg, &packet);
|
2017-04-29 01:11:11 -03:00
|
|
|
enum ap_var_type var_type;
|
|
|
|
|
|
|
|
// set parameter
|
|
|
|
AP_Param *vp;
|
|
|
|
char key[AP_MAX_NAME_SIZE+1];
|
|
|
|
strncpy(key, (char *)packet.param_id, AP_MAX_NAME_SIZE);
|
|
|
|
key[AP_MAX_NAME_SIZE] = 0;
|
|
|
|
|
|
|
|
// find existing param so we can get the old value
|
2019-06-04 01:15:36 -03:00
|
|
|
uint16_t parameter_flags = 0;
|
|
|
|
vp = AP_Param::find(key, &var_type, ¶meter_flags);
|
2017-04-29 01:11:11 -03:00
|
|
|
if (vp == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2019-06-04 01:15:36 -03:00
|
|
|
|
2017-04-29 01:11:11 -03:00
|
|
|
float old_value = vp->cast_to_float(var_type);
|
|
|
|
|
2019-08-19 07:05:55 -03:00
|
|
|
if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) {
|
2019-06-04 01:15:36 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Param write denied (%s)", key);
|
|
|
|
// echo back the incorrect value so that we fulfull the
|
|
|
|
// parameter state machine requirements:
|
|
|
|
send_parameter_value(key, var_type, packet.param_value);
|
|
|
|
// and then announce what the correct value is:
|
|
|
|
send_parameter_value(key, var_type, old_value);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-04-29 01:11:11 -03:00
|
|
|
// set the value
|
|
|
|
vp->set_float(packet.param_value, var_type);
|
|
|
|
|
|
|
|
/*
|
|
|
|
we force the save if the value is not equal to the old
|
|
|
|
value. This copes with the use of override values in
|
|
|
|
constructors, such as PID elements. Otherwise a set to the
|
|
|
|
default value which differs from the constructor value doesn't
|
|
|
|
save the change
|
|
|
|
*/
|
|
|
|
bool force_save = !is_equal(packet.param_value, old_value);
|
|
|
|
|
|
|
|
// save the change
|
|
|
|
vp->save(force_save);
|
|
|
|
|
2019-02-11 04:34:50 -04:00
|
|
|
AP_Logger *logger = AP_Logger::get_singleton();
|
|
|
|
if (logger != nullptr) {
|
|
|
|
logger->Write_Parameter(key, vp->cast_to_float(var_type));
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-06-04 01:15:36 -03:00
|
|
|
void GCS_MAVLINK::send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
|
|
|
|
{
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
mavlink_msg_param_value_send(
|
|
|
|
chan,
|
|
|
|
param_name,
|
|
|
|
param_value,
|
|
|
|
mav_param_type(param_type),
|
|
|
|
AP_Param::count_parameters(),
|
|
|
|
-1);
|
|
|
|
}
|
|
|
|
|
2017-04-29 01:11:11 -03:00
|
|
|
/*
|
|
|
|
send a parameter value message to all active MAVLink connections
|
|
|
|
*/
|
2018-03-11 19:50:51 -03:00
|
|
|
void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
|
2017-04-29 01:11:11 -03:00
|
|
|
{
|
2019-07-05 01:16:48 -03:00
|
|
|
mavlink_param_value_t packet{};
|
|
|
|
const uint8_t to_copy = MIN(ARRAY_SIZE(packet.param_id), strlen(param_name));
|
|
|
|
memcpy(packet.param_id, param_name, to_copy);
|
2019-06-06 07:51:24 -03:00
|
|
|
packet.param_value = param_value;
|
2019-07-17 01:50:12 -03:00
|
|
|
packet.param_type = GCS_MAVLINK::mav_param_type(param_type);
|
2019-06-06 07:51:24 -03:00
|
|
|
packet.param_count = AP_Param::count_parameters();
|
|
|
|
packet.param_index = -1;
|
|
|
|
|
|
|
|
gcs().send_to_active_channels(MAVLINK_MSG_ID_PARAM_VALUE,
|
|
|
|
(const char *)&packet);
|
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
// also log to AP_Logger
|
2019-02-11 04:34:50 -04:00
|
|
|
AP_Logger *logger = AP_Logger::get_singleton();
|
|
|
|
if (logger != nullptr) {
|
|
|
|
logger->Write_Parameter(param_name, param_value);
|
2017-04-29 01:11:11 -03:00
|
|
|
}
|
|
|
|
}
|
2017-04-29 01:36:59 -03:00
|
|
|
|
2017-04-29 02:30:57 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
timer callback for async parameter requests
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::param_io_timer(void)
|
|
|
|
{
|
|
|
|
struct pending_param_request req;
|
|
|
|
|
2017-05-10 03:30:20 -03:00
|
|
|
// this is mostly a no-op, but doing this here means we won't
|
|
|
|
// block the main thread counting parameters (~30ms on PH)
|
|
|
|
AP_Param::count_parameters();
|
|
|
|
|
2017-04-29 02:30:57 -03:00
|
|
|
if (param_replies.space() == 0) {
|
|
|
|
// no room
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!param_requests.pop(req)) {
|
|
|
|
// nothing to do
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct pending_param_reply reply;
|
|
|
|
AP_Param *vp;
|
|
|
|
|
|
|
|
if (req.param_index != -1) {
|
|
|
|
AP_Param::ParamToken token;
|
|
|
|
vp = AP_Param::find_by_index(req.param_index, &reply.p_type, &token);
|
|
|
|
if (vp == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
vp->copy_name_token(token, reply.param_name, AP_MAX_NAME_SIZE, true);
|
|
|
|
} else {
|
|
|
|
strncpy(reply.param_name, req.param_name, AP_MAX_NAME_SIZE+1);
|
|
|
|
vp = AP_Param::find(req.param_name, &reply.p_type);
|
|
|
|
if (vp == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
reply.chan = req.chan;
|
|
|
|
reply.param_name[AP_MAX_NAME_SIZE] = 0;
|
|
|
|
reply.value = vp->cast_to_float(reply.p_type);
|
|
|
|
reply.param_index = req.param_index;
|
|
|
|
reply.count = AP_Param::count_parameters();
|
|
|
|
|
|
|
|
// queue for transmission
|
|
|
|
param_replies.push(reply);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2019-03-13 22:22:04 -03:00
|
|
|
send replies to PARAM_REQUEST_READ
|
2017-04-29 02:30:57 -03:00
|
|
|
*/
|
2019-03-13 22:22:04 -03:00
|
|
|
uint8_t GCS_MAVLINK::send_parameter_async_replies()
|
2017-04-29 02:30:57 -03:00
|
|
|
{
|
2019-03-13 22:22:04 -03:00
|
|
|
uint8_t async_replies_sent_count = 0;
|
|
|
|
|
|
|
|
while (async_replies_sent_count < 5) {
|
|
|
|
if (param_replies.empty()) {
|
|
|
|
// nothing to do
|
|
|
|
return async_replies_sent_count;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
we reserve some space for sending parameters if the client ever
|
|
|
|
fails to get a parameter due to lack of space
|
|
|
|
*/
|
|
|
|
uint32_t saved_reserve_param_space_start_ms = reserve_param_space_start_ms;
|
|
|
|
reserve_param_space_start_ms = 0; // bypass packet_overhead_chan reservation checking
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
|
|
|
|
reserve_param_space_start_ms = AP_HAL::millis();
|
|
|
|
return async_replies_sent_count;
|
|
|
|
}
|
|
|
|
reserve_param_space_start_ms = saved_reserve_param_space_start_ms;
|
|
|
|
|
|
|
|
struct pending_param_reply reply;
|
|
|
|
if (!param_replies.pop(reply)) {
|
|
|
|
// internal error
|
|
|
|
return async_replies_sent_count;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_msg_param_value_send(
|
|
|
|
reply.chan,
|
|
|
|
reply.param_name,
|
|
|
|
reply.value,
|
|
|
|
mav_param_type(reply.p_type),
|
|
|
|
reply.count,
|
|
|
|
reply.param_index);
|
|
|
|
|
|
|
|
_queued_parameter_send_time_ms = AP_HAL::millis();
|
|
|
|
async_replies_sent_count++;
|
2017-04-29 02:30:57 -03:00
|
|
|
}
|
2019-03-13 22:22:04 -03:00
|
|
|
return async_replies_sent_count;
|
2017-04-29 02:30:57 -03:00
|
|
|
}
|
2017-08-19 07:17:09 -03:00
|
|
|
|
2019-07-11 05:31:45 -03:00
|
|
|
void GCS_MAVLINK::handle_common_param_message(const mavlink_message_t &msg)
|
2017-08-19 07:17:09 -03:00
|
|
|
{
|
2019-07-11 05:31:45 -03:00
|
|
|
switch (msg.msgid) {
|
2017-08-19 07:26:10 -03:00
|
|
|
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
|
|
|
handle_param_request_list(msg);
|
|
|
|
break;
|
2017-08-19 07:22:58 -03:00
|
|
|
case MAVLINK_MSG_ID_PARAM_SET:
|
|
|
|
handle_param_set(msg);
|
|
|
|
break;
|
2017-08-19 07:17:09 -03:00
|
|
|
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
|
|
|
|
handle_param_request_read(msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|