param.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2014,2015,2016 Vladimir Ermakov.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <chrono>
18 #include <condition_variable>
19 #include <mavros/mavros_plugin.h>
20 
21 #include <mavros_msgs/ParamSet.h>
22 #include <mavros_msgs/ParamGet.h>
23 #include <mavros_msgs/ParamPull.h>
24 #include <mavros_msgs/ParamPush.h>
25 #include <mavros_msgs/Param.h>
26 
27 namespace mavros {
28 namespace std_plugins {
29 using utils::enum_value;
30 
49 class Parameter {
50 public:
51  using MT = mavlink::common::MAV_PARAM_TYPE;
52  using PARAM_SET = mavlink::common::msg::PARAM_SET;
54 
55  std::string param_id;
57  uint16_t param_index;
58  uint16_t param_count;
59 
60  void set_value(mavlink::common::msg::PARAM_VALUE &pmsg)
61  {
62  mavlink::mavlink_param_union_t uv;
63  uv.param_float = pmsg.param_value;
64 
65  // #170 - copy union value to itermediate var
66  int int_tmp;
67  float float_tmp;
68 
69  switch (pmsg.param_type) {
70  // [[[cog:
71  // param_types = [ (s, 'float' if s == 'real32' else s) for s in (
72  // 'int8', 'uint8',
73  // 'int16', 'uint16',
74  // 'int32', 'uint32',
75  // 'real32',
76  // )]
77  // unsupported_types = ('int64', 'uint64', 'real64')
78  //
79  // for a, b in param_types:
80  // btype = 'int' if 'int' in b else b
81  // cog.outl("case enum_value(MT::%s):" % a.upper())
82  // cog.outl("\t%s_tmp = uv.param_%s;" % (btype, b))
83  // cog.outl("\tparam_value = %s_tmp;" % btype)
84  // cog.outl("\tbreak;")
85  // ]]]
86  case enum_value(MT::INT8):
87  int_tmp = uv.param_int8;
88  param_value = int_tmp;
89  break;
90  case enum_value(MT::UINT8):
91  int_tmp = uv.param_uint8;
92  param_value = int_tmp;
93  break;
94  case enum_value(MT::INT16):
95  int_tmp = uv.param_int16;
96  param_value = int_tmp;
97  break;
98  case enum_value(MT::UINT16):
99  int_tmp = uv.param_uint16;
100  param_value = int_tmp;
101  break;
102  case enum_value(MT::INT32):
103  int_tmp = uv.param_int32;
104  param_value = int_tmp;
105  break;
106  case enum_value(MT::UINT32):
107  int_tmp = uv.param_uint32;
108  param_value = int_tmp;
109  break;
110  case enum_value(MT::REAL32):
111  float_tmp = uv.param_float;
112  param_value = float_tmp;
113  break;
114  // [[[end]]] (checksum: 5950e4ee032d4aa198b953f56909e129)
115 
116  default:
117  ROS_WARN_NAMED("param", "PM: Unsupported param %.16s (%u/%u) type: %u",
118  pmsg.param_id.data(), pmsg.param_index, pmsg.param_count, pmsg.param_type);
119  param_value = 0;
120  };
121  }
122 
126  void set_value_apm_quirk(mavlink::common::msg::PARAM_VALUE &pmsg)
127  {
128  int32_t int_tmp;
129  float float_tmp;
130 
131  switch (pmsg.param_type) {
132  // [[[cog:
133  // for a, b in param_types:
134  // btype = 'int' if 'int' in b else b
135  // cog.outl("case enum_value(MT::%s):" % a.upper())
136  // cog.outl("\t%s_tmp = pmsg.param_value;" % btype)
137  // cog.outl("\tparam_value = %s_tmp;" % btype)
138  // cog.outl("\tbreak;")
139  // ]]]
140  case enum_value(MT::INT8):
141  int_tmp = pmsg.param_value;
142  param_value = int_tmp;
143  break;
144  case enum_value(MT::UINT8):
145  int_tmp = pmsg.param_value;
146  param_value = int_tmp;
147  break;
148  case enum_value(MT::INT16):
149  int_tmp = pmsg.param_value;
150  param_value = int_tmp;
151  break;
152  case enum_value(MT::UINT16):
153  int_tmp = pmsg.param_value;
154  param_value = int_tmp;
155  break;
156  case enum_value(MT::INT32):
157  int_tmp = pmsg.param_value;
158  param_value = int_tmp;
159  break;
160  case enum_value(MT::UINT32):
161  int_tmp = pmsg.param_value;
162  param_value = int_tmp;
163  break;
164  case enum_value(MT::REAL32):
165  float_tmp = pmsg.param_value;
166  param_value = float_tmp;
167  break;
168  // [[[end]]] (checksum: c30ee34dd84213471690612ab49f1f73)
169 
170  default:
171  ROS_WARN_NAMED("param", "PM: Unsupported param %.16s (%u/%u) type: %u",
172  pmsg.param_id.data(), pmsg.param_index, pmsg.param_count, pmsg.param_type);
173  param_value = 0;
174  }
175  }
176 
179  {
180  // Note: XmlRpcValue does not have const cast operators.
181  // This method can't be const.
182 
183  mavlink::mavlink_param_union_t uv;
184  PARAM_SET ret{};
185 
186  mavlink::set_string(ret.param_id, param_id);
187 
188  switch (param_value.getType()) {
189  // [[[cog:
190  // xmlrpc_types = (
191  // ('TypeBoolean', 'uint8', 'bool'),
192  // ('TypeInt', 'int32', 'int32_t'),
193  // ('TypeDouble', 'real32', 'double'),
194  // )
195  //
196  // for a, b, c in xmlrpc_types:
197  // uvb = 'float' if 'real32' == b else b
198  // cog.outl("case XmlRpcValue::%s:" % a)
199  // cog.outl("\tuv.param_%s = static_cast<%s>(param_value);" % (uvb, c))
200  // cog.outl("\tret.param_type = enum_value(MT::%s);" % b.upper())
201  // cog.outl("\tbreak;")
202  // ]]]
204  uv.param_uint8 = static_cast<bool>(param_value);
205  ret.param_type = enum_value(MT::UINT8);
206  break;
208  uv.param_int32 = static_cast<int32_t>(param_value);
209  ret.param_type = enum_value(MT::INT32);
210  break;
212  uv.param_float = static_cast<double>(param_value);
213  ret.param_type = enum_value(MT::REAL32);
214  break;
215  // [[[end]]] (checksum: c414a3950fba234cbbe694a2576ae022)
216 
217  default:
218  ROS_WARN_NAMED("param", "PR: Unsupported XmlRpcValue type: %u", param_value.getType());
219  }
220 
221  ret.param_value = uv.param_float;
222  return ret;
223  }
224 
227  {
228  PARAM_SET ret{};
229 
230  mavlink::set_string(ret.param_id, param_id);
231 
232  switch (param_value.getType()) {
233  // [[[cog:
234  // for a, b, c in xmlrpc_types:
235  // cog.outl("case XmlRpcValue::%s:" % a)
236  // cog.outl("\tret.param_value = static_cast<%s &>(param_value);" % c)
237  // cog.outl("\tret.param_type = enum_value(MT::%s);" % b.upper())
238  // cog.outl("\tbreak;")
239  // ]]]
241  ret.param_value = static_cast<bool &>(param_value);
242  ret.param_type = enum_value(MT::UINT8);
243  break;
245  ret.param_value = static_cast<int32_t &>(param_value);
246  ret.param_type = enum_value(MT::INT32);
247  break;
249  ret.param_value = static_cast<double &>(param_value);
250  ret.param_type = enum_value(MT::REAL32);
251  break;
252  // [[[end]]] (checksum: 5b10c0e1f2e916f1c31313eaa5cc83e0)
253 
254  default:
255  ROS_WARN_NAMED("param", "PR: Unsupported XmlRpcValue type: %u", param_value.getType());
256  }
257 
258  return ret;
259  }
260 
264  int64_t to_integer()
265  {
266  switch (param_value.getType()) {
267  // [[[cog:
268  // for a, b, c in xmlrpc_types:
269  // if 'int' not in b:
270  // continue
271  // cog.outl("case XmlRpcValue::%s:\treturn static_cast<%s>(param_value);" % (a, c))
272  // ]]]
273  case XmlRpcValue::TypeBoolean: return static_cast<bool>(param_value);
274  case XmlRpcValue::TypeInt: return static_cast<int32_t>(param_value);
275  // [[[end]]] (checksum: ce23a3bc04354d8cfcb82341beb83709)
276 
277  default:
278  return 0;
279  }
280  }
281 
282  double to_real()
283  {
284  if (param_value.getType() == XmlRpcValue::TypeDouble)
285  return static_cast<double>(param_value);
286  else
287  return 0.0;
288  }
289 
290  // for debugging
291  std::string to_string() const
292  {
293  return utils::format("%s (%u/%u): %s", param_id.c_str(), param_index, param_count, param_value.toXml().c_str());
294  }
295 
296  mavros_msgs::Param to_msg()
297  {
298  mavros_msgs::Param msg;
299 
300  // XXX(vooon): find better solution
301  msg.header.stamp = ros::Time::now();
302 
303  msg.param_id = param_id;
304  msg.value.integer = to_integer();
305  msg.value.real = to_real();
306  msg.param_index = param_index;
307  msg.param_count = param_count;
308 
309  return msg;
310  }
311 
315  static bool check_exclude_param_id(std::string param_id)
316  {
317  return param_id == "SYSID_SW_MREV" ||
318  param_id == "SYS_NUM_RESETS" ||
319  param_id == "ARSPD_OFFSET" ||
320  param_id == "GND_ABS_PRESS" ||
321  param_id == "GND_TEMP" ||
322  param_id == "CMD_TOTAL" ||
323  param_id == "CMD_INDEX" ||
324  param_id == "LOG_LASTFILE" ||
325  param_id == "FENCE_TOTAL" ||
326  param_id == "FORMAT_VERSION";
327  }
328 };
329 
330 
334 class ParamSetOpt {
335 public:
336  ParamSetOpt(Parameter &_p, size_t _rem) :
337  param(_p),
338  retries_remaining(_rem),
339  is_timedout(false)
340  { }
341 
346  std::condition_variable ack;
347 };
348 
349 
354 public:
355  ParamPlugin() : PluginBase(),
356  param_nh("~param"),
357  param_count(-1),
358  param_state(PR::IDLE),
359  is_timedout(false),
360  RETRIES_COUNT(_RETRIES_COUNT),
361  param_rx_retries(RETRIES_COUNT),
362  BOOTUP_TIME_DT(BOOTUP_TIME_MS / 1000.0),
363  LIST_TIMEOUT_DT(LIST_TIMEOUT_MS / 1000.0),
364  PARAM_TIMEOUT_DT(PARAM_TIMEOUT_MS / 1000.0)
365  { }
366 
367  void initialize(UAS &uas_)
368  {
369  PluginBase::initialize(uas_);
370 
371  pull_srv = param_nh.advertiseService("pull", &ParamPlugin::pull_cb, this);
372  push_srv = param_nh.advertiseService("push", &ParamPlugin::push_cb, this);
373  set_srv = param_nh.advertiseService("set", &ParamPlugin::set_cb, this);
374  get_srv = param_nh.advertiseService("get", &ParamPlugin::get_cb, this);
375 
376  param_value_pub = param_nh.advertise<mavros_msgs::Param>("param_value", 100);
377 
378  shedule_timer = param_nh.createTimer(BOOTUP_TIME_DT, &ParamPlugin::shedule_cb, this, true);
379  shedule_timer.stop();
380  timeout_timer = param_nh.createTimer(PARAM_TIMEOUT_DT, &ParamPlugin::timeout_cb, this, true);
381  timeout_timer.stop();
382  enable_connection_cb();
383  }
384 
386  {
387  return {
388  make_handler(&ParamPlugin::handle_param_value),
389  };
390  }
391 
392 private:
393  using lock_guard = std::lock_guard<std::recursive_mutex>;
394  using unique_lock = std::unique_lock<std::recursive_mutex>;
395 
396  std::recursive_mutex mutex;
398 
403 
405 
408 
409  static constexpr int BOOTUP_TIME_MS = 10000;
410  static constexpr int PARAM_TIMEOUT_MS = 1000;
411  static constexpr int LIST_TIMEOUT_MS = 30000;
412  static constexpr int _RETRIES_COUNT = 3;
413 
417  const int RETRIES_COUNT;
418 
419  std::unordered_map<std::string, Parameter> parameters;
420  std::list<uint16_t> parameters_missing_idx;
421  std::unordered_map<std::string, std::shared_ptr<ParamSetOpt>> set_parameters;
422  ssize_t param_count;
423  enum class PR {
424  IDLE,
425  RXLIST,
426  RXPARAM,
427  RXPARAM_TIMEDOUT,
428  TXPARAM
429  };
431 
435  std::condition_variable list_receiving;
436 
437  /* -*- message handlers -*- */
438 
439  void handle_param_value(const mavlink::mavlink_message_t *msg, mavlink::common::msg::PARAM_VALUE &pmsg)
440  {
441  lock_guard lock(mutex);
442 
443  auto param_id = mavlink::to_string(pmsg.param_id);
444 
445  // search
446  auto param_it = parameters.find(param_id);
447  if (param_it != parameters.end()) {
448  // parameter exists
449  auto &p = param_it->second;
450 
451  if (m_uas->is_ardupilotmega())
452  p.set_value_apm_quirk(pmsg);
453  else
454  p.set_value(pmsg);
455 
456  // check that ack required
457  auto set_it = set_parameters.find(param_id);
458  if (set_it != set_parameters.end()) {
459  set_it->second->ack.notify_all();
460  }
461 
462  param_value_pub.publish(p.to_msg());
463 
465  ((p.param_index != pmsg.param_index &&
466  pmsg.param_index != UINT16_MAX) ||
467  p.param_count != pmsg.param_count),
468  "param",
469  "PR: Param " << p.to_string() << " different index: " << pmsg.param_index << "/" << pmsg.param_count);
470  ROS_DEBUG_STREAM_NAMED("param", "PR: Update param " << p.to_string());
471  }
472  else {
473  // insert new element
474  Parameter p{};
475  p.param_id = param_id;
476  p.param_index = pmsg.param_index;
477  p.param_count = pmsg.param_count;
478 
479  if (m_uas->is_ardupilotmega())
480  p.set_value_apm_quirk(pmsg);
481  else
482  p.set_value(pmsg);
483 
484  parameters[param_id] = p;
485 
486  param_value_pub.publish(p.to_msg());
487 
488  ROS_DEBUG_STREAM_NAMED("param", "PR: New param " << p.to_string());
489  }
490 
491  if (param_state == PR::RXLIST || param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {
492 
493  // we received first param. setup list timeout
494  if (param_state == PR::RXLIST) {
495  param_count = pmsg.param_count;
496  param_state = PR::RXPARAM;
497 
498  parameters_missing_idx.clear();
499  if (param_count != UINT16_MAX) {
500  ROS_DEBUG_NAMED("param", "PR: waiting %zu parameters", param_count);
501  // declare that all parameters are missing
502  for (uint16_t idx = 0; idx < param_count; idx++)
503  parameters_missing_idx.push_back(idx);
504  }
505  else
506  ROS_WARN_NAMED("param", "PR: FCU does not know index for first element! "
507  "Param list may be truncated.");
508  }
509 
510  // trying to avoid endless rerequest loop
511  // Issue #276
512  bool it_is_first_requested = parameters_missing_idx.front() == pmsg.param_index;
513 
514  // remove idx for that message
515  parameters_missing_idx.remove(pmsg.param_index);
516 
517  // in receiving mode we use param_rx_retries for LIST and PARAM
518  if (it_is_first_requested) {
519  ROS_DEBUG_NAMED("param", "PR: got a value of a requested param idx=%u, "
520  "resetting retries count", pmsg.param_index);
521  param_rx_retries = RETRIES_COUNT;
522  } else if (param_state == PR::RXPARAM_TIMEDOUT) {
523  ROS_INFO_NAMED("param", "PR: got an unsolicited param value idx=%u, "
524  "not resetting retries count %zu", pmsg.param_index, param_rx_retries);
525  }
526 
527  restart_timeout_timer();
528 
529  /* index starting from 0, receivig done */
530  if (parameters_missing_idx.empty()) {
531  ssize_t missed = param_count - parameters.size();
532  ROS_INFO_COND_NAMED(missed == 0, "param", "PR: parameters list received");
533  ROS_WARN_COND_NAMED(missed > 0, "param",
534  "PR: parameters list received, but %zd parametars are missed",
535  missed);
536  go_idle();
537  list_receiving.notify_all();
538  } else if (param_state == PR::RXPARAM_TIMEDOUT) {
539  uint16_t first_miss_idx = parameters_missing_idx.front();
540  ROS_DEBUG_NAMED("param", "PR: requesting next timed out parameter idx=%u", first_miss_idx);
541  param_request_read("", first_miss_idx);
542  }
543  }
544  }
545 
546  /* -*- low-level send function -*- */
547 
549  {
550  ROS_DEBUG_NAMED("param", "PR:m: request list");
551 
552  mavlink::common::msg::PARAM_REQUEST_LIST rql{};
553  m_uas->msg_set_target(rql);
554 
555  UAS_FCU(m_uas)->send_message_ignore_drop(rql);
556  }
557 
558  void param_request_read(std::string id, int16_t index = -1)
559  {
560  ROS_ASSERT(index >= -1);
561 
562  ROS_DEBUG_NAMED("param", "PR:m: request '%s', idx %d", id.c_str(), index);
563 
564  mavlink::common::msg::PARAM_REQUEST_READ rqr{};
565  m_uas->msg_set_target(rqr);
566  rqr.param_index = index;
567 
568  if (index != -1) {
569  mavlink::set_string(rqr.param_id, id);
570  }
571 
572  UAS_FCU(m_uas)->send_message_ignore_drop(rqr);
573  }
574 
575  void param_set(Parameter &param)
576  {
577  ROS_DEBUG_STREAM_NAMED("param", "PR:m: set param " << param.to_string());
578 
579  // GCC 4.8 can't type out lambda return
580  auto ps = ([this, &param]() -> mavlink::common::msg::PARAM_SET {
581  if (m_uas->is_ardupilotmega())
582  return param.to_param_set_apm_qurk();
583  else
584  return param.to_param_set();
585  })();
586 
587  m_uas->msg_set_target(ps);
588 
589  UAS_FCU(m_uas)->send_message_ignore_drop(ps);
590  }
591 
592  /* -*- mid-level functions -*- */
593 
594  void connection_cb(bool connected) override
595  {
596  lock_guard lock(mutex);
597  if (connected) {
598  shedule_pull(BOOTUP_TIME_DT);
599  }
600  else {
601  shedule_timer.stop();
602  }
603  }
604 
605  void shedule_pull(const ros::Duration &dt)
606  {
607  shedule_timer.stop();
608  shedule_timer.setPeriod(dt);
609  shedule_timer.start();
610  }
611 
612  void shedule_cb(const ros::TimerEvent &event)
613  {
614  lock_guard lock(mutex);
615  if (param_state != PR::IDLE) {
616  // try later
617  ROS_DEBUG_NAMED("param", "PR: busy, reshedule pull");
618  shedule_pull(BOOTUP_TIME_DT);
619  }
620 
621  ROS_DEBUG_NAMED("param", "PR: start sheduled pull");
622  param_state = PR::RXLIST;
623  param_rx_retries = RETRIES_COUNT;
624  parameters.clear();
625 
626  restart_timeout_timer();
627  param_request_list();
628  }
629 
630  void timeout_cb(const ros::TimerEvent &event)
631  {
632  lock_guard lock(mutex);
633  if (param_state == PR::RXLIST && param_rx_retries > 0) {
634  param_rx_retries--;
635  ROS_WARN_NAMED("param", "PR: request list timeout, retries left %zu", param_rx_retries);
636 
637  restart_timeout_timer();
638  param_request_list();
639  }
640  else if (param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {
641  if (parameters_missing_idx.empty()) {
642  ROS_WARN_NAMED("param", "PR: missing list is clear, but we in RXPARAM state, "
643  "maybe last rerequest fails. Params missed: %zd",
644  param_count - parameters.size());
645  go_idle();
646  list_receiving.notify_all();
647  return;
648  }
649 
650  param_state = PR::RXPARAM_TIMEDOUT;
651  uint16_t first_miss_idx = parameters_missing_idx.front();
652  if (param_rx_retries > 0) {
653  param_rx_retries--;
654  ROS_WARN_NAMED("param", "PR: request param #%u timeout, retries left %zu, and %zu params still missing",
655  first_miss_idx, param_rx_retries, parameters_missing_idx.size());
656  restart_timeout_timer();
657  param_request_read("", first_miss_idx);
658  }
659  else {
660  ROS_ERROR_NAMED("param", "PR: request param #%u completely missing.", first_miss_idx);
661  parameters_missing_idx.pop_front();
662  restart_timeout_timer();
663  if (!parameters_missing_idx.empty()) {
664  param_rx_retries = RETRIES_COUNT;
665  first_miss_idx = parameters_missing_idx.front();
666 
667  ROS_WARN_NAMED("param", "PR: %zu params still missing, trying to request next: #%u",
668  parameters_missing_idx.size(), first_miss_idx);
669  param_request_read("", first_miss_idx);
670  }
671  }
672  }
673  else if (param_state == PR::TXPARAM) {
674  auto it = set_parameters.begin();
675  if (it == set_parameters.end()) {
676  ROS_DEBUG_NAMED("param", "PR: send list empty, but state TXPARAM");
677  go_idle();
678  return;
679  }
680 
681  if (it->second->retries_remaining > 0) {
682  it->second->retries_remaining--;
683  ROS_WARN_NAMED("param", "PR: Resend param set for %s, retries left %zu",
684  it->second->param.param_id.c_str(),
685  it->second->retries_remaining);
686  restart_timeout_timer();
687  param_set(it->second->param);
688  }
689  else {
690  ROS_ERROR_NAMED("param", "PR: Param set for %s timed out.",
691  it->second->param.param_id.c_str());
692  it->second->is_timedout = true;
693  it->second->ack.notify_all();
694  }
695  }
696  else {
697  ROS_DEBUG_NAMED("param", "PR: timeout in IDLE!");
698  }
699  }
700 
702  {
703  is_timedout = false;
704  timeout_timer.stop();
705  timeout_timer.start();
706  }
707 
708  void go_idle()
709  {
710  param_state = PR::IDLE;
711  timeout_timer.stop();
712  }
713 
715  {
716  std::unique_lock<std::mutex> lock(list_cond_mutex);
717 
718  return list_receiving.wait_for(lock, std::chrono::nanoseconds(LIST_TIMEOUT_DT.toNSec()))
719  == std::cv_status::no_timeout
720  && !is_timedout;
721  }
722 
723  bool wait_param_set_ack_for(std::shared_ptr<ParamSetOpt> opt)
724  {
725  std::unique_lock<std::mutex> lock(opt->cond_mutex);
726 
727  return opt->ack.wait_for(lock, std::chrono::nanoseconds(PARAM_TIMEOUT_DT.toNSec()) * (RETRIES_COUNT + 2))
728  == std::cv_status::no_timeout
729  && !opt->is_timedout;
730  }
731 
733  {
734  unique_lock lock(mutex);
735 
736  // add to waiting list
737  auto opt = std::make_shared<ParamSetOpt>(param, RETRIES_COUNT);
738  set_parameters[param.param_id] = opt;
739 
740  param_state = PR::TXPARAM;
741  restart_timeout_timer();
742  param_set(param);
743 
744  lock.unlock();
745  bool is_not_timeout = wait_param_set_ack_for(opt);
746  lock.lock();
747 
748  // free opt data
749  set_parameters.erase(param.param_id);
750 
751  go_idle();
752  return is_not_timeout;
753  }
754 
757  {
758  if (m_uas->is_px4() && p.param_id == "_HASH_CHECK") {
759  auto v = p.param_value; // const XmlRpcValue can't cast
760  ROS_INFO_NAMED("param", "PR: PX4 parameter _HASH_CHECK ignored: 0x%8x", static_cast<int32_t>(v));
761  return false;
762  }
763 
764  param_nh.setParam(p.param_id, p.param_value);
765  return true;
766  }
767 
768  /* -*- ROS callbacks -*- */
769 
774  bool pull_cb(mavros_msgs::ParamPull::Request &req,
775  mavros_msgs::ParamPull::Response &res)
776  {
777  unique_lock lock(mutex);
778 
779  if ((param_state == PR::IDLE && parameters.empty())
780  || req.force_pull) {
781  if (!req.force_pull)
782  ROS_DEBUG_NAMED("param", "PR: start pull");
783  else
784  ROS_INFO_NAMED("param", "PR: start force pull");
785 
786  param_state = PR::RXLIST;
787  param_rx_retries = RETRIES_COUNT;
788  parameters.clear();
789 
790  shedule_timer.stop();
791  restart_timeout_timer();
792  param_request_list();
793 
794  lock.unlock();
795  res.success = wait_fetch_all();
796  }
797  else if (param_state == PR::RXLIST || param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {
798  lock.unlock();
799  res.success = wait_fetch_all();
800  }
801  else {
802  lock.unlock();
803  res.success = true;
804  }
805 
806  lock.lock();
807  res.param_received = parameters.size();
808 
809  for (auto &p : parameters) {
810  lock.unlock();
811  rosparam_set_allowed(p.second);
812  lock.lock();
813  }
814 
815  return true;
816  }
817 
822  bool push_cb(mavros_msgs::ParamPush::Request &req,
823  mavros_msgs::ParamPush::Response &res)
824  {
825  XmlRpc::XmlRpcValue param_dict;
826  if (!param_nh.getParam("", param_dict))
827  return true;
828 
830 
831  int tx_count = 0;
832  for (auto &param : param_dict) {
834  ROS_DEBUG_STREAM_NAMED("param", "PR: Exclude param: " << param.first);
835  continue;
836  }
837 
838  unique_lock lock(mutex);
839  auto param_it = parameters.find(param.first);
840  if (param_it != parameters.end()) {
841  // copy current state of Parameter
842  auto to_send = param_it->second;
843 
844  // Update XmlRpcValue
845  to_send.param_value = param.second;
846 
847  lock.unlock();
848  bool set_res = send_param_set_and_wait(to_send);
849  lock.lock();
850 
851  if (set_res)
852  tx_count++;
853  }
854  else {
855  ROS_WARN_STREAM_NAMED("param", "PR: Unknown rosparam: " << param.first);
856  }
857  }
858 
859  res.success = true;
860  res.param_transfered = tx_count;
861 
862  return true;
863  }
864 
869  bool set_cb(mavros_msgs::ParamSet::Request &req,
870  mavros_msgs::ParamSet::Response &res)
871  {
872  unique_lock lock(mutex);
873 
874  if (param_state == PR::RXLIST || param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {
875  ROS_ERROR_NAMED("param", "PR: receiving not complete");
876  return false;
877  }
878 
879  auto param_it = parameters.find(req.param_id);
880  if (param_it != parameters.end()) {
881  auto to_send = param_it->second;
882 
883  // according to ParamValue description
884  if (req.value.integer != 0)
885  to_send.param_value = static_cast<int>(req.value.integer);
886  else if (req.value.real != 0.0)
887  to_send.param_value = req.value.real;
888  else
889  to_send.param_value = 0;
890 
891  lock.unlock();
892  res.success = send_param_set_and_wait(to_send);
893  lock.lock();
894 
895  res.value.integer = param_it->second.to_integer();
896  res.value.real = param_it->second.to_real();
897 
898  lock.unlock();
899  rosparam_set_allowed(param_it->second);
900  }
901  else {
902  ROS_ERROR_STREAM_NAMED("param", "PR: Unknown parameter to set: " << req.param_id);
903  res.success = false;
904  }
905 
906  return true;
907  }
908 
913  bool get_cb(mavros_msgs::ParamGet::Request &req,
914  mavros_msgs::ParamGet::Response &res)
915  {
916  lock_guard lock(mutex);
917 
918  auto param_it = parameters.find(req.param_id);
919  if (param_it != parameters.end()) {
920  res.success = true;
921 
922  res.value.integer = param_it->second.to_integer();
923  res.value.real = param_it->second.to_real();
924  }
925  else {
926  ROS_ERROR_STREAM_NAMED("param", "PR: Unknown parameter to get: " << req.param_id);
927  res.success = false;
928  }
929 
930  return true;
931  }
932 };
933 } // namespace std_plugins
934 } // namespace mavros
935 
msg
MAVROS Plugin base class.
Definition: mavros_plugin.h:37
#define ROS_WARN_COND_NAMED(cond, name,...)
std::unique_lock< std::recursive_mutex > unique_lock
Definition: param.cpp:394
bool param(const std::string &param_name, T &param_val, const T &default_val)
#define ROS_WARN_STREAM_COND_NAMED(cond, name, args)
#define ROS_INFO_NAMED(name,...)
#define ROS_INFO_COND_NAMED(cond, name,...)
#define ROS_DEBUG_STREAM_NAMED(name, args)
std::string format(const std::string &fmt, Args...args)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_ERROR_STREAM_NAMED(name, args)
void timeout_cb(const ros::TimerEvent &event)
Definition: param.cpp:630
#define ROS_WARN_NAMED(name,...)
std::condition_variable ack
Definition: param.cpp:346
def param_set(param_id, value)
Definition: param.py:136
MAVROS Plugin base.
std::string to_string() const
Definition: param.cpp:291
std::condition_variable list_receiving
Definition: param.cpp:435
void set_value_apm_quirk(mavlink::common::msg::PARAM_VALUE &pmsg)
Definition: param.cpp:126
void initialize(UAS &uas_)
Plugin initializer.
Definition: param.cpp:367
void stop()
ros::Publisher param_value_pub
Definition: param.cpp:404
void setPeriod(const Duration &period, bool reset=true)
void start()
const ros::Duration PARAM_TIMEOUT_DT
Definition: param.cpp:416
mavlink::common::msg::PARAM_SET PARAM_SET
Definition: param.cpp:52
bool wait_param_set_ack_for(std::shared_ptr< ParamSetOpt > opt)
Definition: param.cpp:723
PARAM_SET to_param_set()
Make PARAM_SET message. Set target ids manually!
Definition: param.cpp:178
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
Definition: param.cpp:385
void shedule_cb(const ros::TimerEvent &event)
Definition: param.cpp:612
static bool check_exclude_param_id(std::string param_id)
Definition: param.cpp:315
void set_value(mavlink::common::msg::PARAM_VALUE &pmsg)
Definition: param.cpp:60
mavros_msgs::Param to_msg()
Definition: param.cpp:296
Type const & getType() const
bool set_cb(mavros_msgs::ParamSet::Request &req, mavros_msgs::ParamSet::Response &res)
sets parameter value ~param/set
Definition: param.cpp:869
#define ROS_DEBUG_NAMED(name,...)
PARAM_SET to_param_set_apm_qurk()
Make PARAM_SET message. Set target ids manually!
Definition: param.cpp:226
Parameter manipulation plugin.
Definition: param.cpp:353
std::string toXml() const
void param_request_read(std::string id, int16_t index=-1)
Definition: param.cpp:558
UAS for plugins.
Definition: mavros_uas.h:66
mavlink::common::MAV_PARAM_TYPE MT
Definition: param.cpp:51
ros::ServiceServer push_srv
Definition: param.cpp:400
int64_t toNSec() const
bool send_param_set_and_wait(Parameter &param)
Definition: param.cpp:732
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
Definition: mavros_uas.h:41
ros::Timer shedule_timer
for startup shedule fetch
Definition: param.cpp:406
ParamSetOpt(Parameter &_p, size_t _rem)
Definition: param.cpp:336
void param_set(Parameter &param)
Definition: param.cpp:575
const ros::Duration BOOTUP_TIME_DT
Definition: param.cpp:414
bool get_cb(mavros_msgs::ParamGet::Request &req, mavros_msgs::ParamGet::Response &res)
get parameter ~param/get
Definition: param.cpp:913
bool pull_cb(mavros_msgs::ParamPull::Request &req, mavros_msgs::ParamPull::Response &res)
fetches all parameters from device ~param/pull
Definition: param.cpp:774
void shedule_pull(const ros::Duration &dt)
Definition: param.cpp:605
ros::Timer timeout_timer
for timeout resend
Definition: param.cpp:407
const ros::Duration LIST_TIMEOUT_DT
Definition: param.cpp:415
ros::ServiceServer pull_srv
Definition: param.cpp:399
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:48
Parameter set transaction data.
Definition: param.cpp:334
bool getParam(const std::string &key, std::string &s) const
std::unordered_map< std::string, std::shared_ptr< ParamSetOpt > > set_parameters
Definition: param.cpp:421
Parameter storage.
Definition: param.cpp:49
bool push_cb(mavros_msgs::ParamPush::Request &req, mavros_msgs::ParamPush::Response &res)
push all parameter value to device ~param/push
Definition: param.cpp:822
std::unordered_map< std::string, Parameter > parameters
Definition: param.cpp:419
#define ROS_ERROR_NAMED(name,...)
static Time now()
void handle_param_value(const mavlink::mavlink_message_t *msg, mavlink::common::msg::PARAM_VALUE &pmsg)
Definition: param.cpp:439
ros::ServiceServer set_srv
Definition: param.cpp:401
#define ROS_ASSERT(cond)
std::lock_guard< std::recursive_mutex > lock_guard
Definition: param.cpp:393
ros::ServiceServer get_srv
Definition: param.cpp:402
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void connection_cb(bool connected) override
Definition: param.cpp:594
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
std::list< uint16_t > parameters_missing_idx
Definition: param.cpp:420
std::recursive_mutex mutex
Definition: param.cpp:396
constexpr std::underlying_type< _T >::type enum_value(_T e)
Definition: utils.h:55
std::recursive_mutex mutex
#define ROS_WARN_STREAM_NAMED(name, args)
bool rosparam_set_allowed(const Parameter &p)
Set ROS param only if name is good.
Definition: param.cpp:756


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11