APM:Libraries
GCS_Param.cpp
Go to the documentation of this file.
1 /*
2  GCS MAVLink functions related to parameter handling
3 
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include <AP_AHRS/AP_AHRS.h>
18 #include <AP_HAL/AP_HAL.h>
19 
20 #include "AP_Common/AP_FWVersion.h"
21 #include "GCS.h"
22 
23 extern const AP_HAL::HAL& hal;
24 
25 // queue of pending parameter requests and replies
28 
30 
35 void
37 {
38  if (!initialised) {
39  return;
40  }
41 
42  // send one parameter async reply if pending
44 
45  if (_queued_parameter == nullptr) {
46  return;
47  }
48 
49  uint16_t bytes_allowed;
50  uint8_t count;
51  uint32_t tnow = AP_HAL::millis();
52  uint32_t tstart = AP_HAL::micros();
53 
54  // use at most 30% of bandwidth on parameters. The constant 26 is
55  // 1/(1000 * 1/8 * 0.001 * 0.3)
56  bytes_allowed = 57 * (tnow - _queued_parameter_send_time_ms) * 26;
57  if (bytes_allowed > comm_get_txspace(chan)) {
58  bytes_allowed = comm_get_txspace(chan);
59  }
60  count = bytes_allowed / (MAVLINK_MSG_ID_PARAM_VALUE_LEN + packet_overhead());
61 
62  // when we don't have flow control we really need to keep the
63  // param download very slow, or it tends to stall
64  if (!have_flow_control() && count > 5) {
65  count = 5;
66  }
67 
68  while (_queued_parameter != nullptr && count--) {
69  AP_Param *vp;
70  float value;
71 
72  // copy the current parameter and prepare to move to the next
73  vp = _queued_parameter;
74 
75  // if the parameter can be cast to float, report it here and break out of the loop
77 
78  char param_name[AP_MAX_NAME_SIZE];
79  vp->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);
80 
81  mavlink_msg_param_value_send(
82  chan,
83  param_name,
84  value,
88 
91 
92  if (AP_HAL::micros() - tstart > 1000) {
93  // don't use more than 1ms sending blocks of parameters
94  break;
95  }
96  }
98 }
99 
100 /*
101  return true if a channel has flow control
102  */
104 {
105  if (_port == nullptr) {
106  return false;
107  }
108 
110  return true;
111  }
112 
113  if (chan == MAVLINK_COMM_0) {
114  // assume USB console has flow control
115  return hal.gpio->usb_connected();
116  }
117 
118  return false;
119 }
120 
121 
122 /*
123  handle a request to change stream rate. Note that copter passes in
124  save==false so we don't want the save to happen when the user connects the
125  ground station.
126  */
127 void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg)
128 {
129  mavlink_request_data_stream_t packet;
130  mavlink_msg_request_data_stream_decode(msg, &packet);
131 
132  int16_t freq = 0; // packet frequency
133 
134  if (packet.start_stop == 0)
135  freq = 0; // stop sending
136  else if (packet.start_stop == 1)
137  freq = packet.req_message_rate; // start sending
138  else
139  return;
140 
141  AP_Int16 *rate = nullptr;
142  switch (packet.req_stream_id) {
143  case MAV_DATA_STREAM_ALL:
144  // note that we don't set STREAM_PARAMS - that is internal only
145  for (uint8_t i=0; i<STREAM_PARAMS; i++) {
146  if (persist_streamrates()) {
147  streamRates[i].set_and_save_ifchanged(freq);
148  } else {
149  streamRates[i].set(freq);
150  }
151  }
152  break;
153  case MAV_DATA_STREAM_RAW_SENSORS:
155  break;
156  case MAV_DATA_STREAM_EXTENDED_STATUS:
158  break;
159  case MAV_DATA_STREAM_RC_CHANNELS:
161  break;
162  case MAV_DATA_STREAM_RAW_CONTROLLER:
164  break;
165  case MAV_DATA_STREAM_POSITION:
166  rate = &streamRates[STREAM_POSITION];
167  break;
168  case MAV_DATA_STREAM_EXTRA1:
169  rate = &streamRates[STREAM_EXTRA1];
170  break;
171  case MAV_DATA_STREAM_EXTRA2:
172  rate = &streamRates[STREAM_EXTRA2];
173  break;
174  case MAV_DATA_STREAM_EXTRA3:
175  rate = &streamRates[STREAM_EXTRA3];
176  break;
177  }
178 
179  if (rate != nullptr) {
180  if (persist_streamrates()) {
181  rate->set_and_save_ifchanged(freq);
182  } else {
183  rate->set(freq);
184  }
185  }
186 }
187 
188 void GCS_MAVLINK::handle_param_request_list(mavlink_message_t *msg)
189 {
190  if (!params_ready()) {
191  return;
192  }
193 
194  mavlink_param_request_list_t packet;
195  mavlink_msg_param_request_list_decode(msg, &packet);
196 
197  // requesting parameters is a convenient way to get extra information
198  send_banner();
199 
200  // Start sending parameters - next call to ::update will kick the first one out
204 }
205 
206 void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg)
207 {
208  if (param_requests.space() == 0) {
209  // we can't process this right now, drop it
210  return;
211  }
212 
213  mavlink_param_request_read_t packet;
214  mavlink_msg_param_request_read_decode(msg, &packet);
215 
216  /*
217  we reserve some space for sending parameters if the client ever
218  fails to get a parameter due to lack of space
219  */
220  uint32_t saved_reserve_param_space_start_ms = reserve_param_space_start_ms;
222  if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
224  return;
225  }
226  reserve_param_space_start_ms = saved_reserve_param_space_start_ms;
227 
228  struct pending_param_request req;
229  req.chan = chan;
230  req.param_index = packet.param_index;
231  memcpy(req.param_name, packet.param_id, MIN(sizeof(packet.param_id), sizeof(req.param_name)));
232  req.param_name[AP_MAX_NAME_SIZE] = 0;
233 
234  // queue it for processing by io timer
235  param_requests.push(req);
236 }
237 
238 void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg)
239 {
240  mavlink_param_set_t packet;
241  mavlink_msg_param_set_decode(msg, &packet);
242  enum ap_var_type var_type;
243 
244  // set parameter
245  AP_Param *vp;
246  char key[AP_MAX_NAME_SIZE+1];
247  strncpy(key, (char *)packet.param_id, AP_MAX_NAME_SIZE);
248  key[AP_MAX_NAME_SIZE] = 0;
249 
250  // find existing param so we can get the old value
251  vp = AP_Param::find(key, &var_type);
252  if (vp == nullptr) {
253  return;
254  }
255  float old_value = vp->cast_to_float(var_type);
256 
257  // set the value
258  vp->set_float(packet.param_value, var_type);
259 
260  /*
261  we force the save if the value is not equal to the old
262  value. This copes with the use of override values in
263  constructors, such as PID elements. Otherwise a set to the
264  default value which differs from the constructor value doesn't
265  save the change
266  */
267  bool force_save = !is_equal(packet.param_value, old_value);
268 
269  // save the change
270  vp->save(force_save);
271 
273  if (DataFlash != nullptr) {
274  DataFlash->Log_Write_Parameter(key, vp->cast_to_float(var_type));
275  }
276 }
277 
278 // see if we should send a stream now. Called at 50Hz
280 {
281  if (stream_num >= NUM_STREAMS) {
282  return false;
283  }
284  float rate = (uint8_t)streamRates[stream_num].get();
285 
286  rate *= adjust_rate_for_stream_trigger(stream_num);
287 
288  if (rate <= 0) {
289  if (chan_is_streaming & (1U<<(chan-MAVLINK_COMM_0))) {
290  // if currently streaming then check if all streams are disabled
291  // to allow runtime detection of user disabling streaming
292  bool is_streaming = false;
293  for (uint8_t i=0; i<stream_num; i++) {
294  if (streamRates[stream_num] > 0) {
295  is_streaming = true;
296  }
297  }
298  if (!is_streaming) {
299  // all streams have been turned off, clear the bit flag
300  chan_is_streaming &= ~(1U<<(chan-MAVLINK_COMM_0));
301  }
302  }
303  return false;
304  } else {
305  chan_is_streaming |= (1U<<(chan-MAVLINK_COMM_0));
306  }
307 
308  if (stream_ticks[stream_num] == 0) {
309  // we're triggering now, setup the next trigger point
310  if (rate > 50) {
311  rate = 50;
312  }
313  stream_ticks[stream_num] = (50 / rate) - 1 + stream_slowdown;
314  return true;
315  }
316 
317  // count down at 50Hz
318  stream_ticks[stream_num]--;
319  return false;
320 }
321 
322 /*
323  send a parameter value message to all active MAVLink connections
324  */
325 void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
326 {
328  for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
329  if ((1U<<i) & mavlink_active) {
330  const mavlink_channel_t _chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
331  if (HAVE_PAYLOAD_SPACE(_chan, PARAM_VALUE)) {
332  mavlink_msg_param_value_send(
333  _chan,
334  param_name,
335  param_value,
336  mav_var_type(param_type),
338  -1);
339  }
340  }
341  }
342  // also log to DataFlash
344  if (dataflash != nullptr) {
345  dataflash->Log_Write_Parameter(param_name, param_value);
346  }
347 }
348 
349 /*
350  send queued parameters if needed
351  */
353 {
354  if (!param_timer_registered) {
355  param_timer_registered = true;
357  }
358 
359  if (_queued_parameter == nullptr &&
360  param_replies.empty()) {
361  return;
362  }
363  if (streamRates[STREAM_PARAMS].get() <= 0) {
364  streamRates[STREAM_PARAMS].set(10);
365  }
368  }
369 }
370 
371 
372 /*
373  timer callback for async parameter requests
374  */
376 {
377  struct pending_param_request req;
378 
379  // this is mostly a no-op, but doing this here means we won't
380  // block the main thread counting parameters (~30ms on PH)
382 
383  if (param_replies.space() == 0) {
384  // no room
385  return;
386  }
387 
388  if (!param_requests.pop(req)) {
389  // nothing to do
390  return;
391  }
392 
393  struct pending_param_reply reply;
394  AP_Param *vp;
395 
396  if (req.param_index != -1) {
397  AP_Param::ParamToken token;
398  vp = AP_Param::find_by_index(req.param_index, &reply.p_type, &token);
399  if (vp == nullptr) {
400  return;
401  }
402  vp->copy_name_token(token, reply.param_name, AP_MAX_NAME_SIZE, true);
403  } else {
404  strncpy(reply.param_name, req.param_name, AP_MAX_NAME_SIZE+1);
405  vp = AP_Param::find(req.param_name, &reply.p_type);
406  if (vp == nullptr) {
407  return;
408  }
409  }
410 
411  reply.chan = req.chan;
412  reply.param_name[AP_MAX_NAME_SIZE] = 0;
413  reply.value = vp->cast_to_float(reply.p_type);
414  reply.param_index = req.param_index;
416 
417  // queue for transmission
418  param_replies.push(reply);
419 }
420 
421 /*
422  send a reply to a PARAM_REQUEST_READ
423  */
425 {
426  struct pending_param_reply reply;
427 
428  if (!param_replies.pop(reply)) {
429  // nothing to do
430  return;
431  }
432 
433  mavlink_msg_param_value_send(
434  reply.chan,
435  reply.param_name,
436  reply.value,
437  mav_var_type(reply.p_type),
438  reply.count,
439  reply.param_index);
440 }
441 
442 void GCS_MAVLINK::handle_common_param_message(mavlink_message_t *msg)
443 {
444  switch (msg->msgid) {
445  case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
447  break;
448  case MAVLINK_MSG_ID_PARAM_SET:
449  handle_param_set(msg);
450  break;
451  case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
453  break;
454  }
455 }
ap_var_type
Definition: AP_Param.h:124
#define AP_MAX_NAME_SIZE
Definition: AP_Param.h:32
static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype)
Definition: AP_Param.cpp:1535
Interface definition for the various Ground Control System.
void send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
Definition: GCS_Param.cpp:325
void Log_Write_Parameter(const char *name, float value)
Definition: DataFlash.cpp:603
static AP_Param * find(const char *name, enum ap_var_type *ptype)
Definition: AP_Param.cpp:821
virtual bool usb_connected(void)=0
#define MIN(a, b)
Definition: usb_conf.h:215
static uint16_t count_parameters(void)
Definition: AP_Param.cpp:2090
#define HAVE_PAYLOAD_SPACE(chan, id)
Definition: GCS.h:28
static AP_Param * first(ParamToken *token, enum ap_var_type *ptype)
Definition: AP_Param.cpp:1387
uint32_t millis()
Definition: system.cpp:157
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
void set_float(float value, enum ap_var_type var_type)
Definition: AP_Param.cpp:1726
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual void register_io_process(AP_HAL::MemberProc)=0
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
Definition: AP_Param.cpp:1587
DataFlash_Class DataFlash
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
virtual enum flow_control get_flow_control(void)
Definition: UARTDriver.h:51
AP_HAL::GPIO * gpio
Definition: HAL.h:111
void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const
Definition: AP_Param.cpp:714
float value
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool save(bool force_save=false)
Definition: AP_Param.cpp:982
static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)
Definition: AP_Param.cpp:856
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114