Skip to content

Commit 02dec01

Browse files
committed
feat(ad_api_adaptors): componentize nodes
Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>
1 parent ea009b8 commit 02dec01

File tree

7 files changed

+25
-29
lines changed

7 files changed

+25
-29
lines changed

system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt

+12-3
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,21 @@ project(ad_api_adaptors)
44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
66

7-
ament_auto_add_executable(initial_pose_adaptor
7+
ament_auto_add_library(${PROJECT_NAME} SHARED
88
src/initial_pose_adaptor.cpp
9+
src/routing_adaptor.cpp
910
)
1011

11-
ament_auto_add_executable(routing_adaptor
12-
src/routing_adaptor.cpp
12+
rclcpp_components_register_node(${PROJECT_NAME}
13+
PLUGIN "ad_api_adaptors::InitialPoseAdaptor"
14+
EXECUTABLE initial_pose_adaptor_node
15+
EXECUTOR MultiThreadedExecutor
16+
)
17+
18+
rclcpp_components_register_node(${PROJECT_NAME}
19+
PLUGIN "ad_api_adaptors::RoutingAdaptor"
20+
EXECUTABLE routing_adaptor_node
21+
EXECUTOR SingleThreadedExecutor
1322
)
1423

1524
ament_auto_package(INSTALL_TO_SHARE config launch)

system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33

44
<group>
55
<push-ros-namespace namespace="default_ad_api/helpers"/>
6-
<node pkg="ad_api_adaptors" exec="initial_pose_adaptor" name="initial_pose_adaptor">
6+
<node pkg="ad_api_adaptors" exec="initial_pose_adaptor_node">
77
<param from="$(find-pkg-share ad_api_adaptors)/config/initial_pose.param.yaml"/>
88
<param name="map_height_fitter.map_loader_name" value="/map/pointcloud_map_loader"/>
99
<param name="map_height_fitter.target" value="$(var rviz_initial_pose_auto_fix_target)"/>
@@ -12,7 +12,7 @@
1212
<remap from="~/partial_map_load" to="/map/get_partial_pointcloud_map"/>
1313
<remap from="~/vector_map" to="/map/vector_map"/>
1414
</node>
15-
<node pkg="ad_api_adaptors" exec="routing_adaptor" name="routing_adaptor">
15+
<node pkg="ad_api_adaptors" exec="routing_adaptor_node">
1616
<remap from="~/input/fixed_goal" to="/planning/mission_planning/goal"/>
1717
<remap from="~/input/rough_goal" to="/rviz/routing/rough_goal"/>
1818
<remap from="~/input/reroute" to="/rviz/routing/reroute"/>

system/default_ad_api_helpers/ad_api_adaptors/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
<depend>component_interface_utils</depend>
1818
<depend>map_height_fitter</depend>
1919
<depend>rclcpp</depend>
20+
<depend>rclcpp_components</depend>
2021

2122
<test_depend>ament_lint_auto</test_depend>
2223
<test_depend>autoware_lint_common</test_depend>

system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp

+4-11
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,8 @@ std::array<double, 36> get_covariance_parameter(rclcpp::Node * node, const std::
3434
return array;
3535
}
3636

37-
InitialPoseAdaptor::InitialPoseAdaptor() : Node("initial_pose_adaptor"), fitter_(this)
37+
InitialPoseAdaptor::InitialPoseAdaptor(const rclcpp::NodeOptions & options)
38+
: Node("initial_pose_adaptor", options), fitter_(this)
3839
{
3940
rviz_particle_covariance_ = get_covariance_parameter(this, "initial_pose_particle_covariance");
4041
sub_initial_pose_ = create_subscription<PoseWithCovarianceStamped>(
@@ -61,13 +62,5 @@ void InitialPoseAdaptor::on_initial_pose(const PoseWithCovarianceStamped::ConstS
6162

6263
} // namespace ad_api_adaptors
6364

64-
int main(int argc, char ** argv)
65-
{
66-
rclcpp::init(argc, argv);
67-
rclcpp::executors::MultiThreadedExecutor executor;
68-
auto node = std::make_shared<ad_api_adaptors::InitialPoseAdaptor>();
69-
executor.add_node(node);
70-
executor.spin();
71-
executor.remove_node(node);
72-
rclcpp::shutdown();
73-
}
65+
#include <rclcpp_components/register_node_macro.hpp>
66+
RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::InitialPoseAdaptor)

system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ namespace ad_api_adaptors
2828
class InitialPoseAdaptor : public rclcpp::Node
2929
{
3030
public:
31-
InitialPoseAdaptor();
31+
explicit InitialPoseAdaptor(const rclcpp::NodeOptions & options);
3232

3333
private:
3434
using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped;

system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp

+4-11
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,8 @@
1919
namespace ad_api_adaptors
2020
{
2121

22-
RoutingAdaptor::RoutingAdaptor() : Node("routing_adaptor")
22+
RoutingAdaptor::RoutingAdaptor(const rclcpp::NodeOptions & options)
23+
: Node("routing_adaptor", options)
2324
{
2425
using std::placeholders::_1;
2526

@@ -110,13 +111,5 @@ void RoutingAdaptor::on_reroute(const PoseStamped::ConstSharedPtr pose)
110111

111112
} // namespace ad_api_adaptors
112113

113-
int main(int argc, char ** argv)
114-
{
115-
rclcpp::init(argc, argv);
116-
rclcpp::executors::SingleThreadedExecutor executor;
117-
auto node = std::make_shared<ad_api_adaptors::RoutingAdaptor>();
118-
executor.add_node(node);
119-
executor.spin();
120-
executor.remove_node(node);
121-
rclcpp::shutdown();
122-
}
114+
#include <rclcpp_components/register_node_macro.hpp>
115+
RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::RoutingAdaptor)

system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ namespace ad_api_adaptors
2929
class RoutingAdaptor : public rclcpp::Node
3030
{
3131
public:
32-
RoutingAdaptor();
32+
explicit RoutingAdaptor(const rclcpp::NodeOptions & options);
3333

3434
private:
3535
using PoseStamped = geometry_msgs::msg::PoseStamped;

0 commit comments

Comments
 (0)