Skip to content

Commit 761dcda

Browse files
authored
Merge pull request #29 from micro-ROS/feature/rules
Simple prototype of error handling rules
2 parents 0ada932 + 07b3190 commit 761dcda

File tree

13 files changed

+373
-13
lines changed

13 files changed

+373
-13
lines changed

README.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ standards, e.g., ISO 26262.
1717

1818
## How to Build, Test, Install, and Use
1919

20-
After you cloned this repository into your ROS 2 workspace folder, you may build and install the [system_modes](./system_modes/) package and the [system_modes_examples](./system_modes_examples/) package using colcon:
20+
After you cloned this repository into your ROS 2 workspace folder, you may build and install the [system_modes](./system_modes/) package and the [system_modes_examples](./system_modes_examples/) package using colcon:
2121
$ `colcon build --packages-select-regex system_modes`
2222

2323
Have a look at the [system_modes_examples](./system_modes_examples/) documentation to try your installation.
@@ -37,6 +37,7 @@ see the file [3rd-party-licenses.txt](3rd-party-licenses.txt).
3737
Please notice the following issues/limitations:
3838

3939
* Currently, (sub-)systems managed by the mode manager are not recognized by the `ros2 lifecycle` tool (*"Node not found"*). So to trigger lifecycle transitions in (sub-)systems, you have to go with the `ros2 service call` tool. Check the [system_modes_examples](./system_modes_examples/) documentation for example calls.
40+
* The [Error Handling and Rules](./system_modes/README.md#error-handling-and-rules-experimental) feature is still experimental and might be subject to major changes. However, if no rules are specified in the model file, this feature is not used.
4041

4142
## Acknowledgments
4243

system_modes/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
4040
add_library(mode SHARED
4141
src/system_modes/mode.cpp
4242
src/system_modes/mode_impl.cpp
43+
src/system_modes/mode_handling.cpp
4344
src/system_modes/mode_inference.cpp)
4445
target_include_directories(mode PUBLIC
4546
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>

system_modes/README.md

Lines changed: 20 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
1-
General information about this repository, including legal information, project context, build instructions and known issues/limitations, are given in [README.md](../README.md) in the repository root.
2-
31
# ROS 2 System Modes
42

53
The system modes concept assumes that a robotics system is built from components with a lifecycle. It adds a notion of (sub-)systems, hiararchically grouping these nodes, as well as a notion of *modes* that determine the configuration of these nodes and (sub-)systems in terms of their parameter values.
64

75
A list of (current and future) requirements for system modes can be found here: [requirements](./doc/requirements.md#system-runtime-configuration).
86

7+
General information about this repository, including legal information, project context, build instructions and known issues/limitations, are given in [README.md](../README.md) in the repository root.
8+
99
## System Modes Package
1010

1111
The system modes concept is implemented as a package for ROS 2. This package provides a library for system mode inference, a mode manager, and a mode monitor.
@@ -105,7 +105,7 @@ The mode manager is a ROS node that accepts an SHM file (see [above](#system-mod
105105
* `/{system_or_node}/transition_request_info` - lifecycle_msgs/TransitionEvent
106106
* `/{system_or_node}/mode_request_info` - [system_modes/ModeEvent](./msg/ModeEvent.msg)
107107

108-
Running the manager:
108+
Running the manager:
109109
$ `ros2 launch system_modes mode_manager.launch.py modelfile:=[path/to/modelfile.yaml]`
110110

111111
### Mode Monitor
@@ -118,9 +118,25 @@ The mode monitor is a ROS node that accepts an SHM file (see [above](#system-mod
118118

119119
![mode_monitor](../system_modes_examples/doc/screenshot-monitor.png "Screenshot of the mode monitor from system_modes_examples")
120120

121-
Running the monitor:
121+
Running the monitor:
122122
$ `ros2 launch system_modes mode_monitor.launch.py modelfile:=[path/to/modelfile.yaml]`
123123

124+
### Error Handling and Rules (Experimental)
125+
126+
If the _actual_ state/mode of the system or any of its parts diverges from the _target_ state/mode, we define rules that try to bring the system back to a valid _target_ state/mode, e.g., a degraded mode. Rules work in a bottom-up manner, i.e. starting from correcting nodes before sub-systems before systems. Rules are basically defined in the following way:
127+
128+
```pseudo
129+
if:
130+
system.target == {target state/mode} && system.actual != {target state/mode} && part.actual == {specific state/mode}
131+
then:
132+
system.target := {specific state/mode}
133+
```
134+
135+
if _actual_ state/mode and _target_ state/mode diverge, but there is no rule for this exact situation, the bottom-up rules will just try to return the system/part to its _target_ state/mode.
136+
*Potentiall dangereous, to be discussed:* what's happening, if the system is already on its way. E.g., a system or part was just commanded to transition to _ACTIVE.foo_, but is currently _activating_ (so doing everything right). In this case we have to avoid that the bottom-up rules will trigger.
137+
138+
*Note:* This feature is still experimental and might be subject to major changes. However, if no rules are specified in the model file, this feature is not used.
139+
124140
## How to Apply
125141

126142
When designing the hierarchy of your system, try to group parts semantically, e.g., everything that belongs to *perception* or *navigation*. You want to group those parts of a system that are often jointly managed (initialized, shutdown, configured). Hierarchies don't necessarily need to be designed in one big tree, but can form several parallel trees.
Lines changed: 74 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,74 @@
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+
#pragma once
16+
17+
#include <stdint.h>
18+
#include <shared_mutex>
19+
#include <rclcpp/parameter.hpp>
20+
#include <rclcpp/parameter_map.hpp>
21+
22+
#include <map>
23+
#include <mutex>
24+
#include <string>
25+
#include <memory>
26+
#include <vector>
27+
#include <utility>
28+
29+
#include "system_modes/mode.hpp"
30+
#include "system_modes/mode_impl.hpp"
31+
32+
namespace system_modes
33+
{
34+
35+
struct ModeRule
36+
{
37+
std::string name;
38+
39+
std::string system;
40+
StateAndMode system_target;
41+
42+
std::string part;
43+
StateAndMode part_actual;
44+
45+
StateAndMode new_system_target;
46+
};
47+
48+
using RulesMap = std::map<std::string, ModeRule>;
49+
50+
class ModeHandling
51+
{
52+
public:
53+
explicit ModeHandling(const std::string & model_path);
54+
RCLCPP_DISABLE_COPY(ModeHandling)
55+
56+
virtual ~ModeHandling() = default;
57+
virtual const std::vector<ModeRule> get_rules_for(
58+
const std::string & system,
59+
const StateAndMode & target);
60+
61+
protected:
62+
mutable std::shared_timed_mutex rules_mutex_;
63+
64+
private:
65+
std::map<std::string, RulesMap> rules_;
66+
67+
virtual void read_rules_from_model(const std::string & model_path);
68+
virtual void add_rule(
69+
const std::string & part,
70+
const std::string & rule_name,
71+
const rclcpp::Parameter & rule_param);
72+
};
73+
74+
} // namespace system_modes

system_modes/include/system_modes/mode_inference.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#include <utility>
2828

2929
#include "system_modes/mode.hpp"
30+
#include "system_modes/mode_handling.hpp"
3031

3132
namespace system_modes
3233
{
@@ -69,6 +70,7 @@ class ModeInference
6970
* mode transitions.
7071
*/
7172
virtual Deviation infer_transitions();
73+
virtual Deviation get_deviation();
7274

7375
virtual StateAndMode get_target(const std::string & part) const;
7476
virtual ModeConstPtr get_mode(const std::string & part, const std::string & mode) const;
@@ -82,9 +84,10 @@ class ModeInference
8284
virtual void add_param_to_mode(ModeBasePtr, const rclcpp::Parameter &);
8385

8486
private:
87+
ModeHandling * mode_handling_;
88+
8589
StatesMap nodes_, nodes_target_, nodes_cache_;
8690
StatesMap systems_, systems_target_, systems_cache_;
87-
8891
std::map<std::string, ModeMap> modes_;
8992
ParametersMap parameters_;
9093

system_modes/include/system_modes/mode_manager.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
#include <memory>
2929
#include <utility>
3030

31+
#include "system_modes/mode_handling.hpp"
3132
#include "system_modes/mode_inference.hpp"
3233
#include "system_modes/srv/change_mode.hpp"
3334
#include "system_modes/srv/get_mode.hpp"
@@ -44,6 +45,7 @@ class ModeManager : public rclcpp::Node
4445
ModeManager(const ModeManager &) = delete;
4546

4647
std::shared_ptr<ModeInference> inference();
48+
virtual void handle_system_deviation(const std::string & reason);
4749

4850
virtual ~ModeManager() = default;
4951

@@ -94,6 +96,9 @@ class ModeManager : public rclcpp::Node
9496

9597
private:
9698
std::shared_ptr<ModeInference> mode_inference_;
99+
std::shared_ptr<ModeHandling> mode_handling_;
100+
rclcpp::TimerBase::SharedPtr periodic_timer_;
101+
std::string model_path_;
97102

98103
// Lifecycle change services
99104
std::map<std::string, rclcpp::Service<lifecycle_msgs::srv::ChangeState>::SharedPtr>

system_modes/src/mode_manager_node.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,7 @@ void transition_callback(
5555
const string & node_name)
5656
{
5757
manager->inference()->update_state(node_name, msg->goal_state.id);
58+
manager->handle_system_deviation("transition");
5859
}
5960

6061
void mode_change_callback(
@@ -63,6 +64,7 @@ void mode_change_callback(
6364
{
6465
manager->inference()->update_state(node_name, State::PRIMARY_STATE_ACTIVE);
6566
manager->inference()->update_mode(node_name, msg->goal_mode.label.c_str());
67+
manager->handle_system_deviation("mode change");
6668
}
6769

6870
void transition_request_callback(
@@ -104,6 +106,7 @@ parameter_event_callback(const ParameterEvent::SharedPtr event)
104106
auto param = rclcpp::Parameter::from_parameter_msg(p);
105107
manager->inference()->update_param(event->node, param);
106108
}
109+
manager->handle_system_deviation("parameter event");
107110
}
108111

109112
int main(int argc, char * argv[])
Lines changed: 151 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,151 @@
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

Comments
 (0)