43 #include <yaml-cpp/yaml.h> 47 template <
typename DerivedLogger>
52 unsaved_changes_(false),
53 write_request_in_progress_(false),
54 first_param_received_(false),
56 got_all_params_(false),
57 param_set_in_progress_(false),
59 timer_provider_(timer_provider)
61 comm_->register_mavlink_listener(
this);
65 timer_provider_.create_timer(std::chrono::milliseconds(10), bound_callback,
false,
69 template <
typename DerivedLogger>
72 if (first_param_received_)
78 template <
typename DerivedLogger>
84 handle_param_value_msg(msg);
87 handle_command_ack_msg(msg);
92 template <
typename DerivedLogger>
95 return unsaved_changes_;
98 template <
typename DerivedLogger>
101 if (is_param_id(name))
103 *value = params_[name].getValue();
113 template <
typename DerivedLogger>
116 if (is_param_id(name))
118 mavlink_message_t msg;
119 params_[name].requestSet(value, &msg);
121 param_set_queue_.push_back(msg);
122 if (!param_set_in_progress_)
124 param_set_timer_->start();
125 param_set_in_progress_ =
true;
136 template <
typename DerivedLogger>
139 if (!write_request_in_progress_)
141 mavlink_message_t msg;
145 comm_->send_message(msg);
147 write_request_in_progress_ =
true;
156 template <
typename DerivedLogger>
159 if (listener == NULL)
162 bool already_registered =
false;
163 for (
int i = 0; i < listeners_.size(); i++)
165 if (listener == listeners_[i])
167 already_registered =
true;
172 if (!already_registered)
173 listeners_.push_back(listener);
176 template <
typename DerivedLogger>
179 if (listener == NULL)
182 for (
int i = 0; i < listeners_.size(); i++)
184 if (listener == listeners_[i])
186 listeners_.erase(listeners_.begin() + i);
192 template <
typename DerivedLogger>
197 yaml << YAML::BeginSeq;
198 std::map<std::string, Param>::iterator it;
199 for (it = params_.begin(); it != params_.end(); it++)
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;
208 yaml << YAML::EndSeq;
214 fout.open(filename.c_str());
215 fout << yaml.c_str();
226 template <
typename DerivedLogger>
231 YAML::Node root = YAML::LoadFile(filename);
232 assert(root.IsSequence());
234 for (
int i = 0; i < root.size(); i++)
236 if (root[i].IsMap() && root[i][
"name"] && root[i][
"type"] && root[i][
"value"])
238 if (is_param_id(root[i][
"name"].as<std::string>()))
240 Param param = params_.find(root[i][
"name"].as<std::string>())->second;
243 set_param_value(root[i][
"name"].as<std::string>(), root[i][
"value"].as<double>());
257 template <
typename DerivedLogger>
260 if (!first_param_received_)
262 request_param_list();
266 for (
size_t i = 0; i < num_params_; i++)
276 template <
typename DerivedLogger>
279 mavlink_message_t param_list_msg;
281 comm_->send_message(param_list_msg);
284 template <
typename DerivedLogger>
287 mavlink_message_t param_request_msg;
290 comm_->send_message(param_request_msg);
293 template <
typename DerivedLogger>
299 if (!first_param_received_)
301 first_param_received_ =
true;
303 received_ =
new bool[num_params_];
304 for (
int i = 0; i < num_params_; i++)
306 received_[i] =
false;
315 std::string name(c_name);
317 if (!is_param_id(name))
319 params_[name] =
Param(param);
324 if (received_count_ == num_params_)
326 got_all_params_ =
true;
329 for (
int i = 0; i < listeners_.size(); i++) listeners_[i]->on_new_param_received(name, params_[name].getValue());
333 if (params_[name].handleUpdate(param))
335 unsaved_changes_ =
true;
336 for (
int i = 0; i < listeners_.size(); i++)
338 listeners_[i]->on_param_value_updated(name, params_[name].getValue());
339 listeners_[i]->on_params_saved_change(unsaved_changes_);
345 template <
typename DerivedLogger>
348 if (write_request_in_progress_)
355 write_request_in_progress_ =
false;
358 logger_.info(
"Param write succeeded");
359 unsaved_changes_ =
false;
361 for (
int i = 0; i < listeners_.size(); i++) listeners_[i]->on_params_saved_change(unsaved_changes_);
365 logger_.info(
"Param write failed - maybe disarm the aricraft and try again?");
366 write_request_in_progress_ =
false;
367 unsaved_changes_ =
true;
373 template <
typename DerivedLogger>
376 return (params_.find(name) != params_.end());
379 template <
typename DerivedLogger>
382 if (first_param_received_)
392 template <
typename DerivedLogger>
395 return received_count_;
398 template <
typename DerivedLogger>
401 return got_all_params_;
404 template <
typename DerivedLogger>
407 if (param_set_queue_.empty())
409 param_set_timer_->stop();
410 param_set_in_progress_ =
false;
414 comm_->send_message(param_set_queue_.front());
415 param_set_queue_.pop_front();
static uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component)
Pack a param_request_list message.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
static void mavlink_msg_rosflight_cmd_ack_decode(const mavlink_message_t *msg, mavlink_rosflight_cmd_ack_t *rosflight_cmd_ack)
Decode a rosflight_cmd_ack message into a struct.
ParamManager(MavlinkComm *const comm, LoggerInterface< DerivedLogger > &logger, TimerProviderInterface &timer_provider)
#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
static uint16_t mavlink_msg_rosflight_cmd_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t command)
Pack a rosflight_cmd message.
#define MAVLINK_MSG_ID_PARAM_VALUE
Describes an interface classes can implement to receive and handle mavlink messages.
MAV_PARAM_TYPE getType() const
static void mavlink_msg_param_value_decode(const mavlink_message_t *msg, mavlink_param_value_t *param_value)
Decode a param_value message into a struct.
#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK
Provide an interface for creating timers.
static uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
Pack a param_request_read message.