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)
69 template <
typename DerivedLogger>
78 template <
typename DerivedLogger>
92 template <
typename DerivedLogger>
98 template <
typename DerivedLogger>
103 *value =
params_[name].getValue();
113 template <
typename DerivedLogger>
118 mavlink_message_t msg;
119 params_[name].requestSet(value, &msg);
136 template <
typename DerivedLogger>
141 mavlink_message_t msg;
156 template <
typename DerivedLogger>
159 if (listener == NULL)
162 bool already_registered =
false;
167 already_registered =
true;
172 if (!already_registered)
176 template <
typename DerivedLogger>
179 if (listener == NULL)
192 template <
typename DerivedLogger>
197 yaml << YAML::BeginSeq;
198 std::map<std::string, Param>::iterator 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>()))
243 set_param_value(root[i][
"name"].as<std::string>(), root[i][
"value"].as<double>());
257 template <
typename DerivedLogger>
276 template <
typename DerivedLogger>
279 mavlink_message_t param_list_msg;
284 template <
typename DerivedLogger>
287 mavlink_message_t param_request_msg;
293 template <
typename DerivedLogger>
315 std::string name(c_name);
333 if (
params_[name].handleUpdate(param))
345 template <
typename DerivedLogger>
365 logger_.
info(
"Param write failed - maybe disarm the aricraft and try again?");
373 template <
typename DerivedLogger>
379 template <
typename DerivedLogger>
392 template <
typename DerivedLogger>
398 template <
typename DerivedLogger>
404 template <
typename DerivedLogger>
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)
void info(const char *format, const Args &...args)
bool first_param_received_
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.
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_
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_
void request_param_list()
std::deque< mavlink_message_t > param_set_queue_
void param_set_timer_callback()
#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
int get_params_received()
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.
bool is_param_id(std::string name)
void request_param(int index)
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.
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
#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK
void handle_param_value_msg(const mavlink_message_t &msg)
Provide an interface for creating timers.
bool param_set_in_progress_
void register_param_listener(ParamListenerInterface *listener)
std::map< std::string, Param > params_
bool write_request_in_progress_
TimerProviderInterface & timer_provider_
void send_message(const mavlink_message_t &msg)
Send a mavlink message.
std::shared_ptr< TimerInterface > param_set_timer_
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.