Class ParameterManager
- Defined in File parameters.hpp 
Class Documentation
- 
class ParameterManager
- Public Functions - 
explicit ParameterManager(rclcpp::Logger logger)
 - 
void set_device_batch_callback(std::function<bool(const std::vector<std::string>&)> callback)
 - 
void initialize_ubx_config(const ubx_cfg_item_map_t &config_map)
 - 
void set_parameter_cache(const std::string ¶m_name, std::optional<rclcpp::ParameterValue>, ParamStatus initial_status, ParamValueSource source)
 - 
void update_parameter_cache(const std::string ¶m_name, const rclcpp::ParameterValue &value, ParamStatus new_status, ParamValueSource source)
 - 
std::optional<ParamState> get_parameter_state(const std::string ¶m_name)
 - 
bool update_parameter_status(const std::string ¶m_name, ParamStatus p_status)
 - 
void process_parameter_cache()
 - 
void restore_user_parameters_to_device()
 - 
void reset_device_parameters()
 - 
bool is_valid_parameter(const std::string ¶m_name)
 - 
bool parameter_exists(const std::string ¶m_name)
 - 
const ubx::cfg::ubx_cfg_item_t *find_config_item(const std::string ¶m_name)
 - 
const ubx::cfg::ubx_cfg_item_t *find_config_item_by_key(const ubx::cfg::ubx_key_id_t &key_id)
 - 
void load_config_items(const ubx_cfg_item_map_t &item_map)
 - 
void iterate_config_items(std::function<void(const ubx::cfg::ubx_cfg_item_t&)> callback)
 - 
void parameter_processing_callback()
 - 
void log_parameter_cache_state()
 
- 
explicit ParameterManager(rclcpp::Logger logger)