forked from nasa/astrobee
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathbehaviors.dot
126 lines (123 loc) · 4.58 KB
/
behaviors.dot
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
# dot -Tpdf architecture.dot -o architecture.pdf
digraph G {
ratio="fill";
size="8.3,11.7!";
subgraph cluster_0 {
label="mgt";
node [shape=box, style=filled, fillcolor=lightblue, color=black];
EXECUTIVE;
}
subgraph cluster_1 {
label="proc";
node [shape=box, style=filled, fillcolor=lightblue, color=black];
DOCK;
PERCH;
ARM;
node [shape=ellipse, style=filled, fillcolor=gold, color=black];
PerchAction [label="/proc/perch\nff_msgs::PerchAction"];
DockAction [label="/proc/dock\nff_msgs::DockAction"];
ArmAction [label="/proc/arm\nff_msgs::ArmAction"];
node [shape=ellipse, style=filled, fillcolor=aquamarine, color=black];
PerchState [label="/proc/perch/state\nff_msgs::PerchState", style=dashed];
DockState [label="/proc/dock/state\nff_msgs::DockState", style=dashed];
ArmState [label="/proc/arm/state\nff_msgs::ArmState", style=dashed];
}
subgraph cluster_2 {
label="mob";
node [shape=box, style=filled, fillcolor=lightblue, color=black];
CHOREOGRAPHER;
node [shape=ellipse, style=filled, fillcolor=gold, color=black];
MotionAction [label="/mob/motion\nff_msgs::MotionAction"];
node [shape=ellipse, style=filled, fillcolor=aquamarine, color=black];
MotionState [label="/mob/motion/state\nff_msgs::MotionState", style=dashed];
}
subgraph cluster_3 {
label="loc";
node [shape=box, style=filled, fillcolor=lightblue, color=black];
LOCALIZATION_MANAGER;
node [shape=ellipse, style=filled, fillcolor=gold, color=black];
SwitchAction [label="/loc/switch\nff_msgs::SwitchAction"];
}
subgraph cluster_4 {
label="gnc";
node [shape=box, style=filled, fillcolor=lightblue, color=black];
CTL;
FAM;
EKF;
node [shape=ellipse, style=filled, fillcolor=gold, color=black];
ControlAction [label="/gnc/control\nff_msgs::ControlAction"];
node [shape=ellipse, style=filled, fillcolor=lightpink, color=black];
EkfSetInput [label="/gnc/ekf/set_input\nff_msgs::SetEkfInput"];
node [shape=ellipse, style=filled, fillcolor=aquamarine, color=black];
EkfState [label="/gnc/ekf\nff_msgs::EkfState"];
PoseStamped [label="/gnc/pose\ngeometry_msgs::PoseStamped"];
TwistStamped [label="/gnc/twist\ngeometry_msgs::TwistStamped"];
WrenchStamped [label="/gnc/wrench\ngeometry_msgs::WrenchStamped"];
InertiaStamped [label="/gnc/inertia\ngeometry_msgs::InertiaStamped", style=dashed];
SpeedGain [label="/gnc/speed\nff_msgs::SpeedGain", style=dashed];
}
subgraph cluster_5 {
label="drv";
node [shape=box, style=filled, fillcolor=lightblue, color=black];
PERCHING_ARM;
PMC_ACTUATOR;
node [shape=ellipse, style=filled, fillcolor=aquamarine, color=black];
PmcTelemetry [label="/hw/pmc/telemetry\nff_hw_msgs::PmcTelemetry"];
PmcState [label="/hw/pmc/state\nff_hw_msgs::PmcState", style=dashed];
PmcCommand [label="/hw/pmc/command\nff_hw_msgs::PmcCommand"];
node [shape=ellipse, style=filled, fillcolor=aquamarine, color=black];
JointStates [label="/joint_states\nsensor_msgs::JointState"];
JointGoals [label="/joint_goals\nsensor_msgs::JointState"];
}
# Relationships
EXECUTIVE -> MotionAction [dir="both"];
EXECUTIVE -> DockAction [dir="both"];
EXECUTIVE -> PerchAction [dir="both"];
EXECUTIVE -> ArmAction [dir="both"];
EXECUTIVE -> InertiaStamped;
InertiaStamped -> FAM;
InertiaStamped -> CTL;
InertiaStamped -> EKF;
DockAction -> DOCK [dir="both"];
PerchAction -> PERCH [dir="both"];
DOCK -> SwitchAction [dir="both"];
PERCH -> SwitchAction [dir="both"];
SwitchAction -> LOCALIZATION_MANAGER [dir="both"];
LOCALIZATION_MANAGER -> EkfSetInput;
EkfSetInput -> EKF;
DOCK -> MotionAction [dir="both"];
PERCH -> MotionAction [dir="both"];
PERCH -> ArmAction [dir="both"];
MotionAction -> CHOREOGRAPHER [dir="both"];
CHOREOGRAPHER -> ControlAction [dir="both"];
CHOREOGRAPHER -> SpeedGain;
SpeedGain -> EKF;
SpeedGain -> FAM;
ControlAction -> CTL [dir="both"];
CTL -> WrenchStamped;
PmcCommand -> PMC_ACTUATOR;
PMC_ACTUATOR -> PmcTelemetry;
PMC_ACTUATOR -> PmcState;
PmcTelemetry -> CTL;
PmcState -> CHOREOGRAPHER;
ArmAction -> ARM [dir="both"];
WrenchStamped -> FAM;
FAM -> PmcCommand;
ARM -> JointGoals;
EKF -> PoseStamped;
EKF -> TwistStamped;
EKF -> EkfState;
TwistStamped -> CTL;
PoseStamped -> CTL;
JointStates -> ARM;
JointGoals -> PERCHING_ARM;
PERCHING_ARM -> JointStates;
PERCH -> PerchState;
DOCK -> DockState;
ARM -> ArmState;
CHOREOGRAPHER -> MotionState;
PerchState -> EXECUTIVE;
DockState -> EXECUTIVE;
ArmState -> EXECUTIVE;
MotionState -> EXECUTIVE;
}