@@ -42,10 +42,10 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op
42
42
using std::placeholders::_1;
43
43
44
44
// Parameter
45
- node_param_.update_rate = declare_parameter (" update_rate" , 10.0 );
45
+ node_param_.update_rate = declare_parameter< double > (" update_rate" , 10.0 );
46
46
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 );
49
49
node_param_.diag_name = declare_parameter<std::string>(" diag_name" );
50
50
node_param_.is_transform = (node_param_.topic == " /tf" || node_param_.topic == " /tf_static" );
51
51
@@ -56,10 +56,10 @@ TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_op
56
56
node_param_.topic_type = declare_parameter<std::string>(" topic_type" );
57
57
}
58
58
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" );
63
63
64
64
// Parameter Reconfigure
65
65
set_param_res_ =
0 commit comments