|
| 1 | +// Copyright (c) 2018 - for information on the respective copyright owner |
| 2 | +// see the NOTICE file and/or the repository https://github.com/microros/system_modes |
| 3 | +// |
| 4 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 5 | +// you may not use this file except in compliance with the License. |
| 6 | +// You may obtain a copy of the License at |
| 7 | +// |
| 8 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 9 | +// |
| 10 | +// Unless required by applicable law or agreed to in writing, software |
| 11 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 12 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 13 | +// See the License for the specific language governing permissions and |
| 14 | +// limitations under the License. |
| 15 | +#include "system_modes/mode_handling.hpp" |
| 16 | + |
| 17 | +#include <rclcpp/parameter.hpp> |
| 18 | +#include <rclcpp/parameter_map.hpp> |
| 19 | +#include <lifecycle_msgs/msg/state.hpp> |
| 20 | +#include <rcl_yaml_param_parser/parser.h> |
| 21 | + |
| 22 | +#include <map> |
| 23 | +#include <mutex> |
| 24 | +#include <string> |
| 25 | +#include <vector> |
| 26 | +#include <memory> |
| 27 | +#include <utility> |
| 28 | +#include <shared_mutex> |
| 29 | + |
| 30 | +using std::endl; |
| 31 | +using std::pair; |
| 32 | +using std::mutex; |
| 33 | +using std::string; |
| 34 | +using std::lock_guard; |
| 35 | +using rclcpp::Parameter; |
| 36 | +using rclcpp::ParameterMap; |
| 37 | +using rclcpp::ParameterType; |
| 38 | +using lifecycle_msgs::msg::State; |
| 39 | + |
| 40 | +using shared_mutex = std::shared_timed_mutex; |
| 41 | + |
| 42 | +namespace system_modes |
| 43 | +{ |
| 44 | + |
| 45 | +ModeHandling::ModeHandling(const string & model_path) |
| 46 | +{ |
| 47 | + this->read_rules_from_model(model_path); |
| 48 | +} |
| 49 | + |
| 50 | +void |
| 51 | +ModeHandling::read_rules_from_model(const string & model_path) |
| 52 | +{ |
| 53 | + rcl_params_t * yaml_params = rcl_yaml_node_struct_init(rcl_get_default_allocator()); |
| 54 | + if (!rcl_parse_yaml_file(model_path.c_str(), yaml_params)) { |
| 55 | + throw std::runtime_error("Failed to parse rules from " + model_path); |
| 56 | + } |
| 57 | + |
| 58 | + rclcpp::ParameterMap param_map = rclcpp::parameter_map_from(yaml_params); |
| 59 | + rcl_yaml_node_struct_fini(yaml_params); |
| 60 | + |
| 61 | + ParameterMap::iterator it; |
| 62 | + for (it = param_map.begin(); it != param_map.end(); it++) { |
| 63 | + string part_name(it->first.substr(1)); |
| 64 | + for (auto & param : it->second) { |
| 65 | + string param_name(param.get_name()); |
| 66 | + |
| 67 | + if (param_name.find("rules.") != string::npos) { |
| 68 | + this->add_rule(part_name, param_name.substr(6), param); |
| 69 | + } |
| 70 | + } |
| 71 | + } |
| 72 | +} |
| 73 | + |
| 74 | +void |
| 75 | +ModeHandling::add_rule( |
| 76 | + const string & part, |
| 77 | + const string & rule_name, |
| 78 | + const rclcpp::Parameter & rule_param) |
| 79 | +{ |
| 80 | + std::unique_lock<shared_mutex> mlock(this->rules_mutex_); |
| 81 | + |
| 82 | + // Rule specification |
| 83 | + std::size_t split = rule_name.find("."); |
| 84 | + if (split == string::npos) { |
| 85 | + throw std::runtime_error("ModeHandling::add_rule() can't parse rule."); |
| 86 | + } |
| 87 | + string rule_spec = rule_name.substr(split + 1); |
| 88 | + string rule_name_ = rule_name.substr(0, split); |
| 89 | + |
| 90 | + if (rule_spec.compare("if_target") != 0 && |
| 91 | + rule_spec.compare("if_part") != 0 && |
| 92 | + rule_spec.compare("new_target") != 0) |
| 93 | + { |
| 94 | + throw std::runtime_error("ModeHandling::add_rule() can't parse rule spec."); |
| 95 | + } |
| 96 | + |
| 97 | + if (rule_param.get_type() != ParameterType::PARAMETER_STRING && |
| 98 | + rule_param.get_type() != ParameterType::PARAMETER_STRING_ARRAY) |
| 99 | + { |
| 100 | + throw std::runtime_error("ModeHandling::add_rule() rule is neither string nor string array."); |
| 101 | + } |
| 102 | + |
| 103 | + // Insert rule if not existing already |
| 104 | + this->rules_.insert(std::make_pair(part, RulesMap())); |
| 105 | + auto it = this->rules_[part].insert(std::make_pair(rule_name_, ModeRule())); |
| 106 | + auto rule = it.first->second; |
| 107 | + |
| 108 | + rule.system = part; |
| 109 | + if (rule_spec.compare("if_target") == 0) { |
| 110 | + if (rule_param.get_type() != ParameterType::PARAMETER_STRING) { |
| 111 | + throw std::runtime_error("ModeHandling::parse_rule() if_target expects string."); |
| 112 | + } |
| 113 | + rule.name = rule_name_; |
| 114 | + rule.system_target.from_string(rule_param.as_string()); |
| 115 | + } else if (rule_spec.compare("if_part") == 0) { |
| 116 | + if (rule_param.get_type() != ParameterType::PARAMETER_STRING_ARRAY) { |
| 117 | + throw std::runtime_error("ModeHandling::parse_rule() if_part expects string array."); |
| 118 | + } |
| 119 | + auto spec = rule_param.as_string_array(); |
| 120 | + rule.name = rule_name_; |
| 121 | + rule.part = spec[0]; |
| 122 | + rule.part_actual.from_string(spec[1]); |
| 123 | + } else if (rule_spec.compare("new_target") == 0) { |
| 124 | + if (rule_param.get_type() != ParameterType::PARAMETER_STRING) { |
| 125 | + throw std::runtime_error("ModeHandling::parse_rule() new_target expects string."); |
| 126 | + } |
| 127 | + rule.name = rule_name_; |
| 128 | + rule.new_system_target.from_string(rule_param.as_string()); |
| 129 | + } |
| 130 | + this->rules_[part][rule_name_] = rule; |
| 131 | +} |
| 132 | + |
| 133 | +const std::vector<ModeRule> |
| 134 | +ModeHandling::get_rules_for(const std::string & system, const StateAndMode & target) |
| 135 | +{ |
| 136 | + std::vector<ModeRule> rules; |
| 137 | + try { |
| 138 | + auto rulesmap = this->rules_[system]; |
| 139 | + for (auto rule : rulesmap) { |
| 140 | + if (target == rule.second.system_target) { |
| 141 | + rules.push_back(rule.second); |
| 142 | + } |
| 143 | + } |
| 144 | + } catch (...) { |
| 145 | + // no problem, if we don't find any rule |
| 146 | + } |
| 147 | + |
| 148 | + return rules; |
| 149 | +} |
| 150 | + |
| 151 | +} // namespace system_modes |
0 commit comments