File tree 6 files changed +14
-37
lines changed
6 files changed +14
-37
lines changed Original file line number Diff line number Diff line change @@ -4,11 +4,16 @@ project(mrm_handler)
4
4
find_package (autoware_cmake REQUIRED)
5
5
autoware_package()
6
6
7
- ament_auto_add_executable(mrm_handler
8
- src/mrm_handler/mrm_handler_node.cpp
7
+ ament_auto_add_library(${PROJECT_NAME} SHARED
9
8
src/mrm_handler/mrm_handler_core.cpp
10
9
)
11
10
11
+ rclcpp_components_register_node(${PROJECT_NAME}
12
+ PLUGIN "MrmHandler"
13
+ EXECUTABLE ${PROJECT_NAME} _node
14
+ EXECUTOR MultiThreadedExecutor
15
+ )
16
+
12
17
ament_auto_package(INSTALL_TO_SHARE
13
18
launch
14
19
config
Original file line number Diff line number Diff line change @@ -60,7 +60,7 @@ struct Param
60
60
class MrmHandler : public rclcpp ::Node
61
61
{
62
62
public:
63
- MrmHandler ();
63
+ explicit MrmHandler (const rclcpp::NodeOptions & options );
64
64
65
65
private:
66
66
// type
Original file line number Diff line number Diff line change 18
18
<arg name =" config_file" default =" $(find-pkg-share mrm_handler)/config/mrm_handler.param.yaml" />
19
19
20
20
<!-- mrm_handler -->
21
- <node pkg =" mrm_handler" exec =" mrm_handler " name =" mrm_handler" output =" screen" >
21
+ <node pkg =" mrm_handler" exec =" mrm_handler_node " name =" mrm_handler" output =" screen" >
22
22
<remap from =" ~/input/operation_mode_availability" to =" $(var input_operation_mode_availability)" />
23
23
<remap from =" ~/input/odometry" to =" $(var input_odometry)" />
24
24
<remap from =" ~/input/control_mode" to =" $(var input_control_mode)" />
Original file line number Diff line number Diff line change 18
18
<depend >autoware_auto_vehicle_msgs</depend >
19
19
<depend >nav_msgs</depend >
20
20
<depend >rclcpp</depend >
21
+ <depend >rclcpp_components</depend >
21
22
<depend >std_msgs</depend >
22
23
<depend >std_srvs</depend >
23
24
<depend >tier4_system_msgs</depend >
Original file line number Diff line number Diff line change 18
18
#include < string>
19
19
#include < utility>
20
20
21
- MrmHandler::MrmHandler () : Node(" mrm_handler" )
21
+ MrmHandler::MrmHandler (const rclcpp::NodeOptions & options ) : Node(" mrm_handler" , options )
22
22
{
23
23
// Parameter
24
24
param_.update_rate = declare_parameter<int >(" update_rate" , 10 );
@@ -597,3 +597,6 @@ bool MrmHandler::isArrivedAtGoal()
597
597
598
598
return operation_mode_state_->mode == OperationModeState::STOP;
599
599
}
600
+
601
+ #include < rclcpp_components/register_node_macro.hpp>
602
+ RCLCPP_COMPONENTS_REGISTER_NODE (MrmHandler)
Load Diff This file was deleted.
You can’t perform that action at this time.
0 commit comments