GCS_Param.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455
  1. /*
  2. GCS MAVLink functions related to parameter handling
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. #include <AP_AHRS/AP_AHRS.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include "AP_Common/AP_FWVersion.h"
  17. #include "GCS.h"
  18. #include <AP_Logger/AP_Logger.h>
  19. extern const AP_HAL::HAL& hal;
  20. // queue of pending parameter requests and replies
  21. ObjectBuffer<GCS_MAVLINK::pending_param_request> GCS_MAVLINK::param_requests(20);
  22. ObjectBuffer<GCS_MAVLINK::pending_param_reply> GCS_MAVLINK::param_replies(5);
  23. bool GCS_MAVLINK::param_timer_registered;
  24. /**
  25. * @brief Send the next pending parameter, called from deferred message
  26. * handling code
  27. */
  28. void
  29. GCS_MAVLINK::queued_param_send()
  30. {
  31. // send parameter async replies
  32. uint8_t async_replies_sent_count = send_parameter_async_replies();
  33. const uint32_t tnow = AP_HAL::millis();
  34. const uint32_t tstart = AP_HAL::micros();
  35. // use at most 30% of bandwidth on parameters. The constant 26 is
  36. // 1/(1000 * 1/8 * 0.001 * 0.3)
  37. const uint32_t link_bw = _port->bw_in_kilobytes_per_second();
  38. uint32_t bytes_allowed = link_bw * (tnow - _queued_parameter_send_time_ms) * 26;
  39. const uint16_t size_for_one_param_value_msg = MAVLINK_MSG_ID_PARAM_VALUE_LEN + packet_overhead();
  40. if (bytes_allowed < size_for_one_param_value_msg) {
  41. bytes_allowed = size_for_one_param_value_msg;
  42. }
  43. if (bytes_allowed > comm_get_txspace(chan)) {
  44. bytes_allowed = comm_get_txspace(chan);
  45. }
  46. uint32_t count = bytes_allowed / size_for_one_param_value_msg;
  47. // when we don't have flow control we really need to keep the
  48. // param download very slow, or it tends to stall
  49. if (!have_flow_control() && count > 5) {
  50. count = 5;
  51. }
  52. if (async_replies_sent_count >= count) {
  53. return;
  54. }
  55. count -= async_replies_sent_count;
  56. if (_queued_parameter == nullptr) {
  57. return;
  58. }
  59. while (count && _queued_parameter != nullptr) {
  60. char param_name[AP_MAX_NAME_SIZE];
  61. _queued_parameter->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);
  62. mavlink_msg_param_value_send(
  63. chan,
  64. param_name,
  65. _queued_parameter->cast_to_float(_queued_parameter_type),
  66. mav_param_type(_queued_parameter_type),
  67. _queued_parameter_count,
  68. _queued_parameter_index);
  69. _queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
  70. _queued_parameter_index++;
  71. if (AP_HAL::micros() - tstart > 1000) {
  72. // don't use more than 1ms sending blocks of parameters
  73. break;
  74. }
  75. count--;
  76. }
  77. _queued_parameter_send_time_ms = tnow;
  78. }
  79. /*
  80. return true if a channel has flow control
  81. */
  82. bool GCS_MAVLINK::have_flow_control(void)
  83. {
  84. if (_port == nullptr) {
  85. return false;
  86. }
  87. if (_port->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE) {
  88. return true;
  89. }
  90. if (chan == MAVLINK_COMM_0) {
  91. // assume USB console has flow control
  92. return hal.gpio->usb_connected();
  93. }
  94. return false;
  95. }
  96. /*
  97. handle a request to change stream rate. Note that copter passes in
  98. save==false so we don't want the save to happen when the user connects the
  99. ground station.
  100. */
  101. void GCS_MAVLINK::handle_request_data_stream(const mavlink_message_t &msg)
  102. {
  103. mavlink_request_data_stream_t packet;
  104. mavlink_msg_request_data_stream_decode(&msg, &packet);
  105. int16_t freq = 0; // packet frequency
  106. if (packet.start_stop == 0)
  107. freq = 0; // stop sending
  108. else if (packet.start_stop == 1)
  109. freq = packet.req_message_rate; // start sending
  110. else
  111. return;
  112. // if stream_id is still NUM_STREAMS at the end of this switch
  113. // block then either we set stream rates for all streams, or we
  114. // were asked to set the streamrate for an unrecognised stream
  115. streams stream_id = NUM_STREAMS;
  116. switch (packet.req_stream_id) {
  117. case MAV_DATA_STREAM_ALL:
  118. for (uint8_t i=0; i<NUM_STREAMS; i++) {
  119. if (i == STREAM_PARAMS) {
  120. // don't touch parameter streaming rate; it is
  121. // considered "internal".
  122. continue;
  123. }
  124. if (persist_streamrates()) {
  125. streamRates[i].set_and_save_ifchanged(freq);
  126. } else {
  127. streamRates[i].set(freq);
  128. }
  129. initialise_message_intervals_for_stream((streams)i);
  130. }
  131. break;
  132. case MAV_DATA_STREAM_RAW_SENSORS:
  133. stream_id = STREAM_RAW_SENSORS;
  134. break;
  135. case MAV_DATA_STREAM_EXTENDED_STATUS:
  136. stream_id = STREAM_EXTENDED_STATUS;
  137. break;
  138. case MAV_DATA_STREAM_RC_CHANNELS:
  139. stream_id = STREAM_RC_CHANNELS;
  140. break;
  141. case MAV_DATA_STREAM_RAW_CONTROLLER:
  142. stream_id = STREAM_RAW_CONTROLLER;
  143. break;
  144. case MAV_DATA_STREAM_POSITION:
  145. stream_id = STREAM_POSITION;
  146. break;
  147. case MAV_DATA_STREAM_EXTRA1:
  148. stream_id = STREAM_EXTRA1;
  149. break;
  150. case MAV_DATA_STREAM_EXTRA2:
  151. stream_id = STREAM_EXTRA2;
  152. break;
  153. case MAV_DATA_STREAM_EXTRA3:
  154. stream_id = STREAM_EXTRA3;
  155. break;
  156. }
  157. if (stream_id == NUM_STREAMS) {
  158. // asked to set rate on unknown stream (or all were set already)
  159. return;
  160. }
  161. AP_Int16 *rate = &streamRates[stream_id];
  162. if (rate != nullptr) {
  163. if (persist_streamrates()) {
  164. rate->set_and_save_ifchanged(freq);
  165. } else {
  166. rate->set(freq);
  167. }
  168. initialise_message_intervals_for_stream(stream_id);
  169. }
  170. }
  171. void GCS_MAVLINK::handle_param_request_list(const mavlink_message_t &msg)
  172. {
  173. if (!params_ready()) {
  174. return;
  175. }
  176. mavlink_param_request_list_t packet;
  177. mavlink_msg_param_request_list_decode(&msg, &packet);
  178. // requesting parameters is a convenient way to get extra information
  179. // send_banner();
  180. // Start sending parameters - next call to ::update will kick the first one out
  181. _queued_parameter = AP_Param::first(&_queued_parameter_token, &_queued_parameter_type);
  182. _queued_parameter_index = 0;
  183. _queued_parameter_count = AP_Param::count_parameters();
  184. _queued_parameter_send_time_ms = AP_HAL::millis(); // avoid initial flooding
  185. }
  186. void GCS_MAVLINK::handle_param_request_read(const mavlink_message_t &msg)
  187. {
  188. if (param_requests.space() == 0) {
  189. // we can't process this right now, drop it
  190. return;
  191. }
  192. mavlink_param_request_read_t packet;
  193. mavlink_msg_param_request_read_decode(&msg, &packet);
  194. /*
  195. we reserve some space for sending parameters if the client ever
  196. fails to get a parameter due to lack of space
  197. */
  198. uint32_t saved_reserve_param_space_start_ms = reserve_param_space_start_ms;
  199. reserve_param_space_start_ms = 0; // bypass packet_overhead_chan reservation checking
  200. if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
  201. reserve_param_space_start_ms = AP_HAL::millis();
  202. } else {
  203. reserve_param_space_start_ms = saved_reserve_param_space_start_ms;
  204. }
  205. struct pending_param_request req;
  206. req.chan = chan;
  207. req.param_index = packet.param_index;
  208. memcpy(req.param_name, packet.param_id, MIN(sizeof(packet.param_id), sizeof(req.param_name)));
  209. req.param_name[AP_MAX_NAME_SIZE] = 0;
  210. // queue it for processing by io timer
  211. param_requests.push(req);
  212. // speaking of which, we'd best make sure it is running:
  213. if (!param_timer_registered) {
  214. param_timer_registered = true;
  215. hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::param_io_timer, void));
  216. }
  217. }
  218. void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg)
  219. {
  220. mavlink_param_set_t packet;
  221. mavlink_msg_param_set_decode(&msg, &packet);
  222. enum ap_var_type var_type;
  223. // set parameter
  224. AP_Param *vp;
  225. char key[AP_MAX_NAME_SIZE+1];
  226. strncpy(key, (char *)packet.param_id, AP_MAX_NAME_SIZE);
  227. key[AP_MAX_NAME_SIZE] = 0;
  228. // find existing param so we can get the old value
  229. uint16_t parameter_flags = 0;
  230. vp = AP_Param::find(key, &var_type, &parameter_flags);
  231. if (vp == nullptr) {
  232. return;
  233. }
  234. float old_value = vp->cast_to_float(var_type);
  235. if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) {
  236. gcs().send_text(MAV_SEVERITY_WARNING, "Param write denied (%s)", key);
  237. // echo back the incorrect value so that we fulfull the
  238. // parameter state machine requirements:
  239. send_parameter_value(key, var_type, packet.param_value);
  240. // and then announce what the correct value is:
  241. send_parameter_value(key, var_type, old_value);
  242. return;
  243. }
  244. // set the value
  245. vp->set_float(packet.param_value, var_type);
  246. /*
  247. we force the save if the value is not equal to the old
  248. value. This copes with the use of override values in
  249. constructors, such as PID elements. Otherwise a set to the
  250. default value which differs from the constructor value doesn't
  251. save the change
  252. */
  253. bool force_save = !is_equal(packet.param_value, old_value);
  254. // save the change
  255. vp->save(force_save);
  256. AP_Logger *logger = AP_Logger::get_singleton();
  257. if (logger != nullptr) {
  258. logger->Write_Parameter(key, vp->cast_to_float(var_type));
  259. }
  260. }
  261. void GCS_MAVLINK::send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
  262. {
  263. if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
  264. return;
  265. }
  266. mavlink_msg_param_value_send(
  267. chan,
  268. param_name,
  269. param_value,
  270. mav_param_type(param_type),
  271. AP_Param::count_parameters(),
  272. -1);
  273. }
  274. /*
  275. send a parameter value message to all active MAVLink connections
  276. */
  277. void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
  278. {
  279. mavlink_param_value_t packet{};
  280. const uint8_t to_copy = MIN(ARRAY_SIZE(packet.param_id), strlen(param_name));
  281. memcpy(packet.param_id, param_name, to_copy);
  282. packet.param_value = param_value;
  283. packet.param_type = GCS_MAVLINK::mav_param_type(param_type);
  284. packet.param_count = AP_Param::count_parameters();
  285. packet.param_index = -1;
  286. gcs().send_to_active_channels(MAVLINK_MSG_ID_PARAM_VALUE,
  287. (const char *)&packet);
  288. // also log to AP_Logger
  289. AP_Logger *logger = AP_Logger::get_singleton();
  290. if (logger != nullptr) {
  291. logger->Write_Parameter(param_name, param_value);
  292. }
  293. }
  294. /*
  295. timer callback for async parameter requests
  296. */
  297. void GCS_MAVLINK::param_io_timer(void)
  298. {
  299. struct pending_param_request req;
  300. // this is mostly a no-op, but doing this here means we won't
  301. // block the main thread counting parameters (~30ms on PH)
  302. AP_Param::count_parameters();
  303. if (param_replies.space() == 0) {
  304. // no room
  305. return;
  306. }
  307. if (!param_requests.pop(req)) {
  308. // nothing to do
  309. return;
  310. }
  311. struct pending_param_reply reply;
  312. AP_Param *vp;
  313. if (req.param_index != -1) {
  314. AP_Param::ParamToken token;
  315. vp = AP_Param::find_by_index(req.param_index, &reply.p_type, &token);
  316. if (vp == nullptr) {
  317. return;
  318. }
  319. vp->copy_name_token(token, reply.param_name, AP_MAX_NAME_SIZE, true);
  320. } else {
  321. strncpy(reply.param_name, req.param_name, AP_MAX_NAME_SIZE+1);
  322. vp = AP_Param::find(req.param_name, &reply.p_type);
  323. if (vp == nullptr) {
  324. return;
  325. }
  326. }
  327. reply.chan = req.chan;
  328. reply.param_name[AP_MAX_NAME_SIZE] = 0;
  329. reply.value = vp->cast_to_float(reply.p_type);
  330. reply.param_index = req.param_index;
  331. reply.count = AP_Param::count_parameters();
  332. // queue for transmission
  333. param_replies.push(reply);
  334. }
  335. /*
  336. send replies to PARAM_REQUEST_READ
  337. */
  338. uint8_t GCS_MAVLINK::send_parameter_async_replies()
  339. {
  340. uint8_t async_replies_sent_count = 0;
  341. while (async_replies_sent_count < 5) {
  342. if (param_replies.empty()) {
  343. // nothing to do
  344. return async_replies_sent_count;
  345. }
  346. /*
  347. we reserve some space for sending parameters if the client ever
  348. fails to get a parameter due to lack of space
  349. */
  350. uint32_t saved_reserve_param_space_start_ms = reserve_param_space_start_ms;
  351. reserve_param_space_start_ms = 0; // bypass packet_overhead_chan reservation checking
  352. if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
  353. reserve_param_space_start_ms = AP_HAL::millis();
  354. return async_replies_sent_count;
  355. }
  356. reserve_param_space_start_ms = saved_reserve_param_space_start_ms;
  357. struct pending_param_reply reply;
  358. if (!param_replies.pop(reply)) {
  359. // internal error
  360. return async_replies_sent_count;
  361. }
  362. mavlink_msg_param_value_send(
  363. reply.chan,
  364. reply.param_name,
  365. reply.value,
  366. mav_param_type(reply.p_type),
  367. reply.count,
  368. reply.param_index);
  369. _queued_parameter_send_time_ms = AP_HAL::millis();
  370. async_replies_sent_count++;
  371. }
  372. return async_replies_sent_count;
  373. }
  374. void GCS_MAVLINK::handle_common_param_message(const mavlink_message_t &msg)
  375. {
  376. switch (msg.msgid) {
  377. case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
  378. handle_param_request_list(msg);
  379. break;
  380. case MAVLINK_MSG_ID_PARAM_SET:
  381. handle_param_set(msg);
  382. break;
  383. case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
  384. handle_param_request_read(msg);
  385. break;
  386. }
  387. }