File tree 6 files changed +17
-35
lines changed
localization/pose_initializer
6 files changed +17
-35
lines changed Original file line number Diff line number Diff line change @@ -4,8 +4,7 @@ project(pose_initializer)
4
4
find_package (autoware_cmake REQUIRED)
5
5
autoware_package()
6
6
7
- ament_auto_add_executable(pose_initializer_node
8
- src/pose_initializer/pose_initializer_node.cpp
7
+ ament_auto_add_library(${PROJECT_NAME} SHARED
9
8
src/pose_initializer/pose_initializer_core.cpp
10
9
src/pose_initializer/gnss_module.cpp
11
10
src/pose_initializer/ndt_module.cpp
@@ -15,6 +14,12 @@ ament_auto_add_executable(pose_initializer_node
15
14
src/pose_initializer/ndt_localization_trigger_module.cpp
16
15
)
17
16
17
+ rclcpp_components_register_node(${PROJECT_NAME}
18
+ PLUGIN "PoseInitializer"
19
+ EXECUTABLE ${PROJECT_NAME} _node
20
+ EXECUTOR MultiThreadedExecutor
21
+ )
22
+
18
23
if (BUILD_TESTING)
19
24
function (add_testcase filepath )
20
25
get_filename_component (filename ${filepath} NAME )
@@ -30,7 +35,8 @@ if(BUILD_TESTING)
30
35
add_testcase(test /test_copy_vector_to_array.cpp)
31
36
endif ()
32
37
33
- ament_auto_package(INSTALL_TO_SHARE
38
+ ament_auto_package(
39
+ INSTALL_TO_SHARE
34
40
launch
35
41
config
36
42
)
Original file line number Diff line number Diff line change 9
9
<arg name =" sub_gnss_pose_cov" default =" sub_gnss_pose_cov" />
10
10
<arg name =" gnss_initial_pose_auto_fix_target" default =" pointcloud_map" />
11
11
12
- <node pkg =" pose_initializer" exec =" pose_initializer_node" name = " pose_initializer_node " >
12
+ <node pkg =" pose_initializer" exec =" pose_initializer_node" output = " both " >
13
13
<param from =" $(var config_file)" allow_substs =" true" />
14
14
<remap from =" yabloc_align" to =" /localization/pose_estimator/yabloc/initializer/yabloc_align_srv" />
15
15
<remap from =" ndt_align" to =" /localization/pose_estimator/ndt_align_srv" />
Original file line number Diff line number Diff line change 25
25
<depend >map_height_fitter</depend >
26
26
<depend >motion_utils</depend >
27
27
<depend >rclcpp</depend >
28
+ <depend >rclcpp_components</depend >
28
29
<depend >std_srvs</depend >
29
30
<depend >tier4_autoware_utils</depend >
30
31
<depend >tier4_localization_msgs</depend >
Original file line number Diff line number Diff line change 26
26
#include < sstream>
27
27
#include < vector>
28
28
29
- PoseInitializer::PoseInitializer () : Node(" pose_initializer" )
29
+ PoseInitializer::PoseInitializer (const rclcpp::NodeOptions & options)
30
+ : rclcpp::Node(" pose_initializer" , options)
30
31
{
31
32
const auto node = component_interface_utils::NodeAdaptor (this );
32
33
group_srv_ = create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -209,3 +210,6 @@ geometry_msgs::msg::PoseWithCovarianceStamped PoseInitializer::get_gnss_pose()
209
210
throw ServiceException (
210
211
Initialize::Service::Response::ERROR_GNSS_SUPPORT, " GNSS is not supported." );
211
212
}
213
+
214
+ #include < rclcpp_components/register_node_macro.hpp>
215
+ RCLCPP_COMPONENTS_REGISTER_NODE (PoseInitializer)
Original file line number Diff line number Diff line change @@ -34,7 +34,7 @@ class NdtLocalizationTriggerModule;
34
34
class PoseInitializer : public rclcpp ::Node
35
35
{
36
36
public:
37
- PoseInitializer ();
37
+ explicit PoseInitializer (const rclcpp::NodeOptions & options );
38
38
~PoseInitializer ();
39
39
40
40
private:
Load Diff This file was deleted.
You can’t perform that action at this time.
0 commit comments