Skip to content

Commit 6e97b7e

Browse files
mitukou1109esteve
authored andcommitted
feat(remaining_distance_time_calculator): integrate generate_parameter_library (autowarefoundation#8826)
* add parameter description Signed-off-by: mitukou1109 <[email protected]> * use parameter listener Signed-off-by: mitukou1109 <[email protected]> * supress deprecated error Signed-off-by: mitukou1109 <[email protected]> * change scope of compile option to private Signed-off-by: mitukou1109 <[email protected]> --------- Signed-off-by: mitukou1109 <[email protected]>
1 parent 9ff93ff commit 6e97b7e

File tree

5 files changed

+23
-8
lines changed

5 files changed

+23
-8
lines changed

planning/autoware_remaining_distance_time_calculator/CMakeLists.txt

+12
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,22 @@ project(autoware_remaining_distance_time_calculator)
44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
66

7+
generate_parameter_library(remaining_distance_time_calculator_parameters
8+
param/remaining_distance_time_calculator_parameters.yaml
9+
)
10+
711
ament_auto_add_library(${PROJECT_NAME} SHARED
812
src/remaining_distance_time_calculator_node.cpp
913
)
1014

15+
target_link_libraries(${PROJECT_NAME}
16+
remaining_distance_time_calculator_parameters
17+
)
18+
19+
target_compile_options(${PROJECT_NAME} PRIVATE
20+
-Wno-error=deprecated-declarations
21+
)
22+
1123
rclcpp_components_register_node(${PROJECT_NAME}
1224
PLUGIN "autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode"
1325
EXECUTABLE ${PROJECT_NAME}_node

planning/autoware_remaining_distance_time_calculator/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
<depend>autoware_route_handler</depend>
1919
<depend>autoware_test_utils</depend>
2020
<depend>autoware_universe_utils</depend>
21+
<depend>generate_parameter_library</depend>
2122
<depend>geometry_msgs</depend>
2223
<depend>nav_msgs</depend>
2324
<depend>rclcpp</depend>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
remaining_distance_time_calculator:
2+
update_rate:
3+
type: double
4+
description: Timer callback period. [Hz]

planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -65,9 +65,11 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode(
6565
"~/output/mission_remaining_distance_time",
6666
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable());
6767

68-
node_param_.update_rate = declare_parameter<double>("update_rate");
68+
param_listener_ = std::make_shared<::remaining_distance_time_calculator::ParamListener>(
69+
this->get_node_parameters_interface());
70+
const auto param = param_listener_->get_params();
6971

70-
const auto period_ns = rclcpp::Rate(node_param_.update_rate).period();
72+
const auto period_ns = rclcpp::Rate(param.update_rate).period();
7173
timer_ = rclcpp::create_timer(
7274
this, get_clock(), period_ns, std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this));
7375
}

planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp

+2-6
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <autoware/route_handler/route_handler.hpp>
1919
#include <rclcpp/rclcpp.hpp>
20+
#include <remaining_distance_time_calculator_parameters.hpp>
2021

2122
#include <autoware_internal_msgs/msg/mission_remaining_distance_time.hpp>
2223
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
@@ -39,11 +40,6 @@
3940
namespace autoware::remaining_distance_time_calculator
4041
{
4142

42-
struct NodeParam
43-
{
44-
double update_rate{0.0};
45-
};
46-
4743
class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
4844
{
4945
public:
@@ -86,7 +82,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
8682
double remaining_time_;
8783

8884
// Parameter
89-
NodeParam node_param_;
85+
std::shared_ptr<::remaining_distance_time_calculator::ParamListener> param_listener_;
9086

9187
// Callbacks
9288
void on_timer();

0 commit comments

Comments
 (0)