Skip to content

Commit 2bf7cf9

Browse files
committed
system/topic_state_monitor
Signed-off-by: karishma <karishma@interpl.ai>
1 parent 8e209a1 commit 2bf7cf9

File tree

2 files changed

+86
-7
lines changed

2 files changed

+86
-7
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for topic_state_monitor",
4+
"type": "object",
5+
"definitions": {
6+
"topic_state_monitor": {
7+
"type": "object",
8+
"properties": {
9+
"warn_rate": {
10+
"type": "number",
11+
"default": 0.5,
12+
"description": "If the topic rate is lower than this value, the topic status becomes warn_rate"
13+
},
14+
"error_rate": {
15+
"type": "number",
16+
"default": 0.1,
17+
"description": "If the topic rate is lower than this value, the topic status becomes."
18+
},
19+
"timeout": {
20+
"type": "number",
21+
"default": 1.0,
22+
"description": "If the topic subscription is stopped for more than this time [s], the topic status becomes timeout."
23+
},
24+
"window_size": {
25+
"type": "number",
26+
"default": 10,
27+
"description": "Window size of target topic for calculating frequency."
28+
},
29+
"update_rate": {
30+
"type": "number",
31+
"default": 10.0,
32+
"description": "Timer callback period."
33+
},
34+
"topic": {
35+
"type": "string",
36+
"description": "Name of target."
37+
},
38+
"transient_local": {
39+
"type": "boolean",
40+
"default": "false",
41+
"description": "QoS policy of topic subscription (Transient Local/Volatile)."
42+
},
43+
"best_effort": {
44+
"type": "boolean",
45+
"default": "false",
46+
"description": "QoS policy of topic subscription (Best Effort/Reliable)."
47+
},
48+
"diag_name": {
49+
"type": "boolean",
50+
"default": "string",
51+
"description": "Name used for the diagnostics to publish."
52+
}
53+
},
54+
"required": [
55+
"warn_rate",
56+
"window_size",
57+
"timeout",
58+
"error_rate",
59+
"update_rate",
60+
"topic",
61+
"transient_local",
62+
"best_effort",
63+
"diag_name"
64+
]
65+
}
66+
},
67+
"properties": {
68+
"/**": {
69+
"type": "object",
70+
"properties": {
71+
"ros__parameters": {
72+
"$ref": "#/definitions/topic_state_monitor"
73+
}
74+
},
75+
"required": ["ros__parameters"]
76+
}
77+
},
78+
"required": ["/**"]
79+
}

system/topic_state_monitor/src/topic_state_monitor_core.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -42,10 +42,10 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op
4242
using std::placeholders::_1;
4343

4444
// Parameter
45-
node_param_.update_rate = declare_parameter("update_rate", 10.0);
45+
node_param_.update_rate = declare_parameter<double>("update_rate", 10.0);
4646
node_param_.topic = declare_parameter<std::string>("topic");
47-
node_param_.transient_local = declare_parameter("transient_local", false);
48-
node_param_.best_effort = declare_parameter("best_effort", false);
47+
node_param_.transient_local = declare_parameter<bool>("transient_local", false);
48+
node_param_.best_effort = declare_parameter<bool>("best_effort", false);
4949
node_param_.diag_name = declare_parameter<std::string>("diag_name");
5050
node_param_.is_transform = (node_param_.topic == "/tf" || node_param_.topic == "/tf_static");
5151

@@ -56,10 +56,10 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op
5656
node_param_.topic_type = declare_parameter<std::string>("topic_type");
5757
}
5858

59-
param_.warn_rate = declare_parameter("warn_rate", 0.5);
60-
param_.error_rate = declare_parameter("error_rate", 0.1);
61-
param_.timeout = declare_parameter("timeout", 1.0);
62-
param_.window_size = declare_parameter("window_size", 10);
59+
param_.warn_rate = declare_parameter<double>("warn_rate");
60+
param_.error_rate = declare_parameter<double>("error_rate");
61+
param_.timeout = declare_parameter<double>("timeout");
62+
param_.window_size = declare_parameter<double>("window_size");
6363

6464
// Parameter Reconfigure
6565
set_param_res_ =

0 commit comments

Comments
 (0)