Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(topic_state_monitor): rework parameters #5731

Closed
79 changes: 79 additions & 0 deletions system/topic_state_monitor/schema/topic_state_monitor.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for topic_state_monitor",
"type": "object",
"definitions": {
"topic_state_monitor": {
"type": "object",
"properties": {
"warn_rate": {
"type": "number",
"default": 0.5,
"description": "If the topic rate is lower than this value, the topic status becomes warn_rate"
},
"error_rate": {
"type": "number",
"default": 0.1,
"description": "If the topic rate is lower than this value, the topic status becomes."
},
"timeout": {
"type": "number",
"default": 1.0,
"description": "If the topic subscription is stopped for more than this time [s], the topic status becomes timeout."
},
"window_size": {
"type": "number",
"default": 10,
"description": "Window size of target topic for calculating frequency."
},
"update_rate": {
"type": "number",
"default": 10.0,
"description": "Timer callback period."
},
"topic": {
"type": "string",
"description": "Name of target."
},
"transient_local": {
"type": "boolean",
"default": "false",
"description": "QoS policy of topic subscription (Transient Local/Volatile)."
},
"best_effort": {
"type": "boolean",
"default": "false",
"description": "QoS policy of topic subscription (Best Effort/Reliable)."
},
"diag_name": {
"type": "boolean",
"default": "string",
"description": "Name used for the diagnostics to publish."
}
},
"required": [
"warn_rate",
"window_size",
"timeout",
"error_rate",
"update_rate",
"topic",
"transient_local",
"best_effort",
"diag_name"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/topic_state_monitor"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
14 changes: 7 additions & 7 deletions system/topic_state_monitor/src/topic_state_monitor_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,10 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op
using std::placeholders::_1;

// Parameter
node_param_.update_rate = declare_parameter("update_rate", 10.0);
node_param_.update_rate = declare_parameter<double>("update_rate");
node_param_.topic = declare_parameter<std::string>("topic");
node_param_.transient_local = declare_parameter("transient_local", false);
node_param_.best_effort = declare_parameter("best_effort", false);
node_param_.transient_local = declare_parameter<bool>("transient_local");
node_param_.best_effort = declare_parameter<bool>("best_effort");
node_param_.diag_name = declare_parameter<std::string>("diag_name");
node_param_.is_transform = (node_param_.topic == "/tf" || node_param_.topic == "/tf_static");

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

param_.warn_rate = declare_parameter("warn_rate", 0.5);
param_.error_rate = declare_parameter("error_rate", 0.1);
param_.timeout = declare_parameter("timeout", 1.0);
param_.window_size = declare_parameter("window_size", 10);
param_.warn_rate = declare_parameter<double>("warn_rate");
param_.error_rate = declare_parameter<double>("error_rate");
param_.timeout = declare_parameter<double>("timeout");
param_.window_size = declare_parameter<double>("window_size");

// Parameter Reconfigure
set_param_res_ =
Expand Down
Loading