param_manager.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
37 #include <fstream>
38 #include <functional>
39 
43 #include <yaml-cpp/yaml.h>
44 
45 namespace mavrosflight
46 {
47 template <typename DerivedLogger>
50  TimerProviderInterface &timer_provider) :
51  comm_(comm),
52  unsaved_changes_(false),
53  write_request_in_progress_(false),
54  first_param_received_(false),
55  received_count_(0),
56  got_all_params_(false),
57  param_set_in_progress_(false),
58  logger_(logger),
59  timer_provider_(timer_provider)
60 {
62 
63  std::function<void()> bound_callback = std::bind(&ParamManager<DerivedLogger>::param_set_timer_callback, this);
65  timer_provider_.create_timer(std::chrono::milliseconds(10), bound_callback, false, /* not oneshot */
66  false /* not autostart */);
67 }
68 
69 template <typename DerivedLogger>
71 {
73  {
74  delete[] received_;
75  }
76 }
77 
78 template <typename DerivedLogger>
79 void ParamManager<DerivedLogger>::handle_mavlink_message(const mavlink_message_t &msg)
80 {
81  switch (msg.msgid)
82  {
85  break;
88  break;
89  }
90 }
91 
92 template <typename DerivedLogger>
94 {
95  return unsaved_changes_;
96 }
97 
98 template <typename DerivedLogger>
99 bool ParamManager<DerivedLogger>::get_param_value(std::string name, double *value)
100 {
101  if (is_param_id(name))
102  {
103  *value = params_[name].getValue();
104  return true;
105  }
106  else
107  {
108  *value = 0.0;
109  return false;
110  }
111 }
112 
113 template <typename DerivedLogger>
114 bool ParamManager<DerivedLogger>::set_param_value(std::string name, double value)
115 {
116  if (is_param_id(name))
117  {
118  mavlink_message_t msg;
119  params_[name].requestSet(value, &msg);
120 
121  param_set_queue_.push_back(msg);
123  {
124  param_set_timer_->start();
125  param_set_in_progress_ = true;
126  }
127 
128  return true;
129  }
130  else
131  {
132  return false;
133  }
134 }
135 
136 template <typename DerivedLogger>
138 {
140  {
141  mavlink_message_t msg;
142  uint8_t sysid = 1;
143  uint8_t compid = 1;
145  comm_->send_message(msg);
146 
148  return true;
149  }
150  else
151  {
152  return false;
153  }
154 }
155 
156 template <typename DerivedLogger>
158 {
159  if (listener == NULL)
160  return;
161 
162  bool already_registered = false;
163  for (int i = 0; i < listeners_.size(); i++)
164  {
165  if (listener == listeners_[i])
166  {
167  already_registered = true;
168  break;
169  }
170  }
171 
172  if (!already_registered)
173  listeners_.push_back(listener);
174 }
175 
176 template <typename DerivedLogger>
178 {
179  if (listener == NULL)
180  return;
181 
182  for (int i = 0; i < listeners_.size(); i++)
183  {
184  if (listener == listeners_[i])
185  {
186  listeners_.erase(listeners_.begin() + i);
187  i--;
188  }
189  }
190 }
191 
192 template <typename DerivedLogger>
194 {
195  // build YAML document
196  YAML::Emitter yaml;
197  yaml << YAML::BeginSeq;
198  std::map<std::string, Param>::iterator it;
199  for (it = params_.begin(); it != params_.end(); it++)
200  {
201  yaml << YAML::Flow;
202  yaml << YAML::BeginMap;
203  yaml << YAML::Key << "name" << YAML::Value << it->second.getName();
204  yaml << YAML::Key << "type" << YAML::Value << (int)it->second.getType();
205  yaml << YAML::Key << "value" << YAML::Value << it->second.getValue();
206  yaml << YAML::EndMap;
207  }
208  yaml << YAML::EndSeq;
209 
210  // write to file
211  try
212  {
213  std::ofstream fout;
214  fout.open(filename.c_str());
215  fout << yaml.c_str();
216  fout.close();
217  }
218  catch (...)
219  {
220  return false;
221  }
222 
223  return true;
224 }
225 
226 template <typename DerivedLogger>
228 {
229  try
230  {
231  YAML::Node root = YAML::LoadFile(filename);
232  assert(root.IsSequence());
233 
234  for (int i = 0; i < root.size(); i++)
235  {
236  if (root[i].IsMap() && root[i]["name"] && root[i]["type"] && root[i]["value"])
237  {
238  if (is_param_id(root[i]["name"].as<std::string>()))
239  {
240  Param param = params_.find(root[i]["name"].as<std::string>())->second;
241  if ((MAV_PARAM_TYPE)root[i]["type"].as<int>() == param.getType())
242  {
243  set_param_value(root[i]["name"].as<std::string>(), root[i]["value"].as<double>());
244  }
245  }
246  }
247  }
248 
249  return true;
250  }
251  catch (...)
252  {
253  return false;
254  }
255 }
256 
257 template <typename DerivedLogger>
259 {
261  {
263  }
264  else
265  {
266  for (size_t i = 0; i < num_params_; i++)
267  {
268  if (!received_[i])
269  {
270  request_param(i);
271  }
272  }
273  }
274 }
275 
276 template <typename DerivedLogger>
278 {
279  mavlink_message_t param_list_msg;
280  mavlink_msg_param_request_list_pack(1, 50, &param_list_msg, 1, MAV_COMP_ID_ALL);
281  comm_->send_message(param_list_msg);
282 }
283 
284 template <typename DerivedLogger>
286 {
287  mavlink_message_t param_request_msg;
289  mavlink_msg_param_request_read_pack(1, 50, &param_request_msg, 1, MAV_COMP_ID_ALL, empty, (int16_t)index);
290  comm_->send_message(param_request_msg);
291 }
292 
293 template <typename DerivedLogger>
294 void ParamManager<DerivedLogger>::handle_param_value_msg(const mavlink_message_t &msg)
295 {
297  mavlink_msg_param_value_decode(&msg, &param);
298 
300  {
301  first_param_received_ = true;
302  num_params_ = param.param_count;
303  received_ = new bool[num_params_];
304  for (int i = 0; i < num_params_; i++)
305  {
306  received_[i] = false;
307  }
308  }
309 
310  // ensure null termination of name
314 
315  std::string name(c_name);
316 
317  if (!is_param_id(name)) // if we haven't received this param before, add it
318  {
319  params_[name] = Param(param);
320  received_[param.param_index] = true;
321 
322  // increase the param count
323  received_count_++;
325  {
326  got_all_params_ = true;
327  }
328 
329  for (int i = 0; i < listeners_.size(); i++) listeners_[i]->on_new_param_received(name, params_[name].getValue());
330  }
331  else // otherwise check if we have new unsaved changes as a result of a param set request
332  {
333  if (params_[name].handleUpdate(param))
334  {
335  unsaved_changes_ = true;
336  for (int i = 0; i < listeners_.size(); i++)
337  {
338  listeners_[i]->on_param_value_updated(name, params_[name].getValue());
339  listeners_[i]->on_params_saved_change(unsaved_changes_);
340  }
341  }
342  }
343 }
344 
345 template <typename DerivedLogger>
346 void ParamManager<DerivedLogger>::handle_command_ack_msg(const mavlink_message_t &msg)
347 {
349  {
352 
354  {
356  if (ack.success == ROSFLIGHT_CMD_SUCCESS)
357  {
358  logger_.info("Param write succeeded");
359  unsaved_changes_ = false;
360 
361  for (int i = 0; i < listeners_.size(); i++) listeners_[i]->on_params_saved_change(unsaved_changes_);
362  }
363  else
364  {
365  logger_.info("Param write failed - maybe disarm the aricraft and try again?");
367  unsaved_changes_ = true;
368  }
369  }
370  }
371 }
372 
373 template <typename DerivedLogger>
375 {
376  return (params_.find(name) != params_.end());
377 }
378 
379 template <typename DerivedLogger>
381 {
383  {
384  return num_params_;
385  }
386  else
387  {
388  return 0;
389  }
390 }
391 
392 template <typename DerivedLogger>
394 {
395  return received_count_;
396 }
397 
398 template <typename DerivedLogger>
400 {
401  return got_all_params_;
402 }
403 
404 template <typename DerivedLogger>
406 {
407  if (param_set_queue_.empty())
408  {
409  param_set_timer_->stop();
410  param_set_in_progress_ = false;
411  }
412  else
413  {
415  param_set_queue_.pop_front();
416  }
417 }
418 
419 template class ParamManager<DerivedLoggerType>;
420 
421 } // namespace mavrosflight
bool param(const std::string &param_name, T &param_val, const T &default_val)
void info(const char *format, const Args &...args)
MAV_PARAM_TYPE
Definition: common.h:508
bool set_param_value(std::string name, double value)
bool get_param_value(std::string name, double *value)
void unregister_param_listener(ParamListenerInterface *listener)
std::vector< ParamListenerInterface * > listeners_
Definition: param_manager.h:92
ParamManager(MavlinkComm *const comm, LoggerInterface< DerivedLogger > &logger, TimerProviderInterface &timer_provider)
bool load_from_file(std::string filename)
void handle_command_ack_msg(const mavlink_message_t &msg)
void register_mavlink_listener(MavlinkListenerInterface *const listener)
Register a listener for mavlink messages.
bool save_to_file(std::string filename)
virtual std::shared_ptr< TimerInterface > create_timer(std::chrono::nanoseconds period, std::function< void()> callback, const bool oneshot=false, const bool autostart=true)=0
LoggerInterface< DerivedLogger > & logger_
std::deque< mavlink_message_t > param_set_queue_
Describes an interface classes can implement to receive and handle mavlink messages.
bool is_param_id(std::string name)
virtual void handle_mavlink_message(const mavlink_message_t &msg)
The handler function for mavlink messages to be implemented by derived classes.
MAV_PARAM_TYPE getType() const
Definition: param.cpp:70
void handle_param_value_msg(const mavlink_message_t &msg)
Provide an interface for creating timers.
void register_param_listener(ParamListenerInterface *listener)
std::map< std::string, Param > params_
Definition: param_manager.h:95
TimerProviderInterface & timer_provider_
void send_message(const mavlink_message_t &msg)
Send a mavlink message.
std::shared_ptr< TimerInterface > param_set_timer_


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:09:26