Skip to content

Commit

Permalink
refactor(topic_state_monitor): move the parameter group to match impl…
Browse files Browse the repository at this point in the history
…ementation (autowarefoundation#1909)

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>
  • Loading branch information
isamu-takagi authored and boyali committed Oct 3, 2022
1 parent 88a5ae7 commit 80d5535
Show file tree
Hide file tree
Showing 4 changed files with 31 additions and 29 deletions.
28 changes: 14 additions & 14 deletions system/topic_state_monitor/Readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,23 +35,23 @@ The types of topic status and corresponding diagnostic status are following.

### Node Parameters

| Name | Type | Default Value | Description |
| ------------- | ------ | ------------- | ----------------------------------------------------- |
| `update_rate` | double | 10.0 | Timer callback period [Hz] |
| `window_size` | int | 10 | Window size of target topic for calculating frequency |
| Name | Type | Default Value | Description |
| ----------------- | ------ | ------------- | ----------------------------------------------------------- |
| `topic` | string | - | Name of target topic |
| `topic_type` | string | - | Type of target topic |
| `transient_local` | bool | false | QoS policy of topic subscription (Transient Local/Volatile) |
| `best_effort` | bool | false | QoS policy of topic subscription (Best Effort/Reliable) |
| `diag_name` | string | - | Name used for the diagnostics to publish |
| `update_rate` | double | 10.0 | Timer callback period [Hz] |

### Core Parameters

| Name | Type | Default Value | Description |
| ----------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------- |
| `topic` | string | - | Name of target topic |
| `topic_type` | string | - | Type of target topic |
| `transient_local` | bool | false | QoS policy of topic subscription (Transient Local/Volatile) |
| `best_effort` | bool | false | QoS policy of topic subscription (Best Effort/Reliable) |
| `diag_name` | string | - | Name used for the diagnostics to publish |
| `warn_rate` | double | 0.5 | If the topic rate is lower than this value, the topic status becomes `WarnRate` |
| `error_rate` | double | 0.1 | If the topic rate is lower than this value, the topic status becomes `ErrorRate` |
| `timeout` | double | 1.0 | If the topic subscription is stopped for more than this time [s], the topic status becomes `Timeout` |
| Name | Type | Default Value | Description |
| ------------- | ------ | ------------- | ---------------------------------------------------------------------------------------------------- |
| `warn_rate` | double | 0.5 | If the topic rate is lower than this value, the topic status becomes `WarnRate` |
| `error_rate` | double | 0.1 | If the topic rate is lower than this value, the topic status becomes `ErrorRate` |
| `timeout` | double | 1.0 | If the topic subscription is stopped for more than this time [s], the topic status becomes `Timeout` |
| `window_size` | int | 10 | Window size of target topic for calculating frequency |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,6 @@ namespace topic_state_monitor
{
struct Param
{
std::string topic;
std::string topic_type;
bool transient_local;
bool best_effort;
std::string diag_name;
double warn_rate;
double error_rate;
double timeout;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,11 @@ namespace topic_state_monitor
struct NodeParam
{
double update_rate;
std::string diag_name;
std::string topic;
std::string topic_type;
bool transient_local;
bool best_effort;
};

class TopicStateMonitorNode : public rclcpp::Node
Expand Down
22 changes: 12 additions & 10 deletions system/topic_state_monitor/src/topic_state_monitor_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,14 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op
: Node("topic_state_monitor", node_options), updater_(this)
{
using std::placeholders::_1;

// Parameter
node_param_.update_rate = declare_parameter("update_rate", 10.0);
param_.topic = declare_parameter<std::string>("topic");
param_.topic_type = declare_parameter<std::string>("topic_type");
param_.transient_local = declare_parameter("transient_local", false);
param_.best_effort = declare_parameter("best_effort", false);
param_.diag_name = declare_parameter<std::string>("diag_name");
node_param_.topic = declare_parameter<std::string>("topic");
node_param_.topic_type = declare_parameter<std::string>("topic_type");
node_param_.transient_local = declare_parameter("transient_local", false);
node_param_.best_effort = declare_parameter("best_effort", false);
node_param_.diag_name = declare_parameter<std::string>("diag_name");
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);
Expand All @@ -62,21 +63,21 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op

// Subscriber
rclcpp::QoS qos = rclcpp::QoS{1};
if (param_.transient_local) {
if (node_param_.transient_local) {
qos.transient_local();
}
if (param_.best_effort) {
if (node_param_.best_effort) {
qos.best_effort();
}
sub_topic_ = this->create_generic_subscription(
param_.topic, param_.topic_type, qos,
node_param_.topic, node_param_.topic_type, qos,
[this]([[maybe_unused]] std::shared_ptr<rclcpp::SerializedMessage> msg) {
topic_state_monitor_->update();
});

// Diagnostic Updater
updater_.setHardwareID("topic_state_monitor");
updater_.add(param_.diag_name, this, &TopicStateMonitorNode::checkTopicStatus);
updater_.add(node_param_.diag_name, this, &TopicStateMonitorNode::checkTopicStatus);

// Timer
const auto period_ns = rclcpp::Rate(node_param_.update_rate).period();
Expand All @@ -96,6 +97,7 @@ rcl_interfaces::msg::SetParametersResult TopicStateMonitorNode::onParameter(
update_param(parameters, "error_rate", param_.error_rate);
update_param(parameters, "timeout", param_.timeout);
update_param(parameters, "window_size", param_.window_size);
topic_state_monitor_->setParam(param_);
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
result.successful = false;
result.reason = e.what();
Expand All @@ -120,7 +122,7 @@ void TopicStateMonitorNode::checkTopicStatus(diagnostic_updater::DiagnosticStatu
const auto topic_rate = topic_state_monitor_->getTopicRate();

// Add topic name
stat.addf("topic", "%s", param_.topic.c_str());
stat.addf("topic", "%s", node_param_.topic.c_str());

// Judge level
int8_t level = DiagnosticStatus::OK;
Expand Down

0 comments on commit 80d5535

Please sign in to comment.