From 2bf7cf993118208da538465bffc0bc4e38a8369c Mon Sep 17 00:00:00 2001 From: karishma Date: Thu, 30 Nov 2023 15:27:17 +0530 Subject: [PATCH] system/topic_state_monitor Signed-off-by: karishma --- .../schema/topic_state_monitor.json | 79 +++++++++++++++++++ .../src/topic_state_monitor_core.cpp | 14 ++-- 2 files changed, 86 insertions(+), 7 deletions(-) create mode 100644 system/topic_state_monitor/schema/topic_state_monitor.json diff --git a/system/topic_state_monitor/schema/topic_state_monitor.json b/system/topic_state_monitor/schema/topic_state_monitor.json new file mode 100644 index 0000000000000..5eea6643788ad --- /dev/null +++ b/system/topic_state_monitor/schema/topic_state_monitor.json @@ -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": ["/**"] +} diff --git a/system/topic_state_monitor/src/topic_state_monitor_core.cpp b/system/topic_state_monitor/src/topic_state_monitor_core.cpp index 68fa3764d8ecd..b270873bbfd74 100644 --- a/system/topic_state_monitor/src/topic_state_monitor_core.cpp +++ b/system/topic_state_monitor/src/topic_state_monitor_core.cpp @@ -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("update_rate", 10.0); node_param_.topic = declare_parameter("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("transient_local", false); + node_param_.best_effort = declare_parameter("best_effort", false); node_param_.diag_name = declare_parameter("diag_name"); node_param_.is_transform = (node_param_.topic == "/tf" || node_param_.topic == "/tf_static"); @@ -56,10 +56,10 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op node_param_.topic_type = declare_parameter("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("warn_rate"); + param_.error_rate = declare_parameter("error_rate"); + param_.timeout = declare_parameter("timeout"); + param_.window_size = declare_parameter("window_size"); // Parameter Reconfigure set_param_res_ =