Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 5bb640d

Browse files
authoredJul 2, 2024··
Merge branch 'feat/add-mrm-v0.6-launch-based-on-v3.0.0' into feat/add-control-cmd-switcher
2 parents 55021ea + 974b4a6 commit 5bb640d

File tree

17 files changed

+85
-74
lines changed

17 files changed

+85
-74
lines changed
 

‎dummy/dummy_operation_mode_publisher/src/dummy_operation_mode_publisher.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -34,12 +34,12 @@ DummyOperationModePublisher::DummyOperationModePublisher(const rclcpp::NodeOptio
3434

3535
// Timer
3636
using namespace std::literals::chrono_literals;
37-
timer_ = rclcpp::create_timer(this, get_clock(), 1s, std::bind(&DummyOperationModePublisher::onTimer, this));
37+
timer_ = rclcpp::create_timer(
38+
this, get_clock(), 1s, std::bind(&DummyOperationModePublisher::onTimer, this));
3839

3940
// State
4041

4142
// Diagnostics
42-
4343
}
4444

4545
void DummyOperationModePublisher::onTimer()

‎dummy/dummy_operation_mode_publisher/src/dummy_operation_mode_publisher.hpp

+5-6
Original file line numberDiff line numberDiff line change
@@ -12,15 +12,14 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef DUMMY_OPERATION_MODE_PUBLISHER__DUMMY_OPERATION_MODE_PUBLISHER_HPP_
16-
#define DUMMY_OPERATION_MODE_PUBLISHER__DUMMY_OPERATION_MODE_PUBLISHER_HPP_
15+
#ifndef DUMMY_OPERATION_MODE_PUBLISHER_HPP_
16+
#define DUMMY_OPERATION_MODE_PUBLISHER_HPP_
1717

1818
// include
1919
#include <rclcpp/rclcpp.hpp>
2020

2121
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
2222

23-
2423
namespace dummy_operation_mode_publisher
2524
{
2625

@@ -36,7 +35,8 @@ class DummyOperationModePublisher : public rclcpp::Node
3635
// Subscriber
3736

3837
// Publisher
39-
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::OperationModeState>::SharedPtr pub_operation_mode_state_;
38+
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::OperationModeState>::SharedPtr
39+
pub_operation_mode_state_;
4040

4141
// Service
4242

@@ -50,8 +50,7 @@ class DummyOperationModePublisher : public rclcpp::Node
5050
// State
5151

5252
// Diagnostics
53-
5453
};
5554
} // namespace dummy_operation_mode_publisher
5655

57-
#endif // DUMMY_OPERATION_MODE_PUBLISHER__DUMMY_OPERATION_MODE_PUBLISHER_HPP_
56+
#endif // DUMMY_OPERATION_MODE_PUBLISHER_HPP_

‎launch/tier4_system_launch/launch/system.main.mrm-v0.6.tmp.launch.xml

+4-4
Original file line numberDiff line numberDiff line change
@@ -116,6 +116,7 @@
116116
<group if="$(var use_diagnostic_graph)">
117117
<include file="$(find-pkg-share mrm_handler)/launch/mrm_handler.launch.xml">
118118
<arg name="config_file" value="$(var mrm_handler_param_path)"/>
119+
<arg name="output_mrm_state" value="/system/fail_safe/mrm_state/tmp"/>
119120
</include>
120121
</group>
121122

@@ -163,12 +164,13 @@
163164
<!-- Leader Election Converter-->
164165
<group>
165166
<include file="$(find-pkg-share leader_election_converter)/launch/leader_election_converter.launch.xml"/>
167+
<arg name="input_mrm_state" value="/system/fail_safe/mrm_state/tmp"/>
166168
</group>
167169

168-
<!-- topic state montor for MRMv0.6 one host test-->
170+
<!-- topic state monitor for MRMv0.6 one host test-->
169171
<group>
170172
<include file="$(find-pkg-share topic_state_monitor)/launch/topic_state_monitor.launch.xml">
171-
<arg name="node_name_suffix" value="scenario_planning_trajectry"/>
173+
<arg name="node_name_suffix" value="scenario_planning_trajectory"/>
172174
<arg name="topic" value="/planning/scenario_planning/trajectory"/>
173175
<arg name="topic_type" value="autoware_auto_planning_msgs/msg/Trajectory"/>
174176
<arg name="diag_name" value="publish_to_sub_status"/>
@@ -187,6 +189,4 @@
187189
<arg name="timeout" value=""/>
188190
</include> -->
189191
</group>
190-
191-
192192
</launch>

‎launch/tier4_system_launch/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,9 @@
1212
<buildtool_depend>autoware_cmake</buildtool_depend>
1313

1414
<exec_depend>component_state_monitor</exec_depend>
15+
<exec_depend>control_cmd_switcher</exec_depend>
1516
<exec_depend>emergency_handler</exec_depend>
17+
<exec_depend>leader_election_converter</exec_depend>
1618
<exec_depend>system_error_monitor</exec_depend>
1719
<exec_depend>system_monitor</exec_depend>
1820
<exec_depend>control_cmd_switcher</exec_depend>

‎system/control_cmd_switcher/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
# control_cmd_switcher
1+
# control_cmd_switcher

‎system/control_cmd_switcher/config/control_cmd_switcher.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -2,4 +2,3 @@
22
---
33
/**:
44
ros__parameters:
5-

‎system/control_cmd_switcher/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313

1414
<depend>autoware_auto_control_msgs</depend>
1515
<depend>rclcpp</depend>
16+
<depend>rclcpp_components</depend>
1617
<depend>tier4_system_msgs</depend>
17-
<depend>rclcpp_components</depend>
1818

1919
<test_depend>ament_lint_auto</test_depend>
2020
<test_depend>autoware_lint_common</test_depend>

‎system/control_cmd_switcher/src/control_cmd_switcher/control_cmd_switcher.cpp

+18-10
Original file line numberDiff line numberDiff line change
@@ -18,17 +18,23 @@
1818
#include <string>
1919
#include <utility>
2020

21-
ControlCmdSwitcher::ControlCmdSwitcher(const rclcpp::NodeOptions & node_options) : Node("control_cmd_switcher", node_options)
21+
ControlCmdSwitcher::ControlCmdSwitcher(const rclcpp::NodeOptions & node_options)
22+
: Node("control_cmd_switcher", node_options)
2223
{
2324
// Subscriber
24-
sub_main_control_cmd_ = create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>(
25-
"~/input/main/control_cmd", rclcpp::QoS{10}, std::bind(&ControlCmdSwitcher::onMainControlCmd, this, std::placeholders::_1));
25+
sub_main_control_cmd_ =
26+
create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>(
27+
"~/input/main/control_cmd", rclcpp::QoS{10},
28+
std::bind(&ControlCmdSwitcher::onMainControlCmd, this, std::placeholders::_1));
2629

27-
sub_sub_control_cmd_ = create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>(
28-
"~/input/sub/control_cmd", rclcpp::QoS{10}, std::bind(&ControlCmdSwitcher::onSubControlCmd, this, std::placeholders::_1));
30+
sub_sub_control_cmd_ =
31+
create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>(
32+
"~/input/sub/control_cmd", rclcpp::QoS{10},
33+
std::bind(&ControlCmdSwitcher::onSubControlCmd, this, std::placeholders::_1));
2934

3035
sub_election_status = create_subscription<tier4_system_msgs::msg::ElectionStatus>(
31-
"~/input/election/status", rclcpp::QoS{10}, std::bind(&ControlCmdSwitcher::onElectionStatus, this, std::placeholders::_1));
36+
"~/input/election/status", rclcpp::QoS{10},
37+
std::bind(&ControlCmdSwitcher::onElectionStatus, this, std::placeholders::_1));
3238
// Publisher
3339
pub_control_cmd_ = create_publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>(
3440
"~/output/control_cmd", rclcpp::QoS{1});
@@ -37,21 +43,24 @@ ControlCmdSwitcher::ControlCmdSwitcher(const rclcpp::NodeOptions & node_options)
3743
use_main_control_cmd_ = true;
3844
}
3945

40-
void ControlCmdSwitcher::onMainControlCmd(const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg)
46+
void ControlCmdSwitcher::onMainControlCmd(
47+
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg)
4148
{
4249
if (use_main_control_cmd_) {
4350
pub_control_cmd_->publish(*msg);
4451
}
4552
}
4653

47-
void ControlCmdSwitcher::onSubControlCmd(const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg)
54+
void ControlCmdSwitcher::onSubControlCmd(
55+
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg)
4856
{
4957
if (!use_main_control_cmd_) {
5058
pub_control_cmd_->publish(*msg);
5159
}
5260
}
5361

54-
void ControlCmdSwitcher::onElectionStatus(const tier4_system_msgs::msg::ElectionStatus::ConstSharedPtr msg)
62+
void ControlCmdSwitcher::onElectionStatus(
63+
const tier4_system_msgs::msg::ElectionStatus::ConstSharedPtr msg)
5564
{
5665
if (((msg->path_info >> 3) & 0x01) == 1) {
5766
use_main_control_cmd_ = true;
@@ -62,4 +71,3 @@ void ControlCmdSwitcher::onElectionStatus(const tier4_system_msgs::msg::Election
6271

6372
#include <rclcpp_components/register_node_macro.hpp>
6473
RCLCPP_COMPONENTS_REGISTER_NODE(ControlCmdSwitcher)
65-

‎system/control_cmd_switcher/src/control_cmd_switcher/control_cmd_switcher.hpp

+14-14
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef CONTROL_SWITCHER__CONTROL_CMD_SWITCHER_HPP_
16-
#define CONTROL_SWITCHER__CONTROL_CMD_SWITCHER_HPP_
15+
#ifndef CONTROL_CMD_SWITCHER__CONTROL_CMD_SWITCHER_HPP_
16+
#define CONTROL_CMD_SWITCHER__CONTROL_CMD_SWITCHER_HPP_
1717

1818
// Core
19+
#include <atomic>
1920
#include <memory>
2021
#include <string>
21-
#include <atomic>
22-
2322

2423
// Autoware
2524
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
@@ -28,28 +27,29 @@
2827
// ROS 2 core
2928
#include <rclcpp/rclcpp.hpp>
3029

31-
3230
class ControlCmdSwitcher : public rclcpp::Node
3331
{
3432
public:
3533
explicit ControlCmdSwitcher(const rclcpp::NodeOptions & node_options);
3634

3735
private:
38-
3936
// Subscribers
40-
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr sub_main_control_cmd_;
41-
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr sub_sub_control_cmd_;
37+
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
38+
sub_main_control_cmd_;
39+
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
40+
sub_sub_control_cmd_;
4241
rclcpp::Subscription<tier4_system_msgs::msg::ElectionStatus>::SharedPtr sub_election_status;
43-
void onMainControlCmd(const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
44-
void onSubControlCmd(const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
42+
void onMainControlCmd(
43+
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
44+
void onSubControlCmd(
45+
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
4546
void onElectionStatus(const tier4_system_msgs::msg::ElectionStatus::ConstSharedPtr msg);
4647

47-
4848
// Publisher
49-
rclcpp::Publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr pub_control_cmd_;
50-
49+
rclcpp::Publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
50+
pub_control_cmd_;
5151

5252
std::atomic<bool> use_main_control_cmd_;
5353
};
5454

55-
#endif // CONTROL_SWITCHER__CONTROL_SWITCHER_HPP_
55+
#endif // CONTROL_CMD_SWITCHER__CONTROL_CMD_SWITCHER_HPP_

‎system/control_cmd_switcher/tool/rely_trajectory.py

+13-11
Original file line numberDiff line numberDiff line change
@@ -1,20 +1,21 @@
11
#!/usr/bin/env python3
22

3+
import threading
4+
5+
from autoware_auto_planning_msgs.msg import Trajectory
36
import rclpy
47
from rclpy.node import Node
5-
from autoware_auto_planning_msgs.msg import Trajectory
6-
import threading
78

8-
class RelayTrajectoryNode(Node):
99

10+
class RelayTrajectoryNode(Node):
1011
def __init__(self):
11-
super().__init__('relay_trajectory')
12+
super().__init__("relay_trajectory")
1213
self.subscription = self.create_subscription(
13-
Trajectory,
14-
'/tmp/planning/scenario_planning/trajectory',
15-
self.listener_callback,
16-
10)
17-
self.publisher = self.create_publisher(Trajectory, '/planning/scenario_planning/trajectory', 10)
14+
Trajectory, "/tmp/planning/scenario_planning/trajectory", self.listener_callback, 10
15+
)
16+
self.publisher = self.create_publisher(
17+
Trajectory, "/planning/scenario_planning/trajectory", 10
18+
)
1819
self.running = True
1920

2021
def listener_callback(self, msg):
@@ -29,7 +30,7 @@ def input_thread():
2930
nonlocal node
3031
while True:
3132
user_input = input("Enter 'y' to stop publishing: ")
32-
if user_input.lower() == 'y':
33+
if user_input.lower() == "y":
3334
node.running = False
3435
print("Publishing stopped.")
3536
break
@@ -43,5 +44,6 @@ def input_thread():
4344
node.destroy_node()
4445
rclpy.shutdown()
4546

46-
if __name__ == '__main__':
47+
48+
if __name__ == "__main__":
4749
main()

‎system/leader_election_converter/src/common/converter/availability_converter.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ void AvailabilityConverter::setUdpSender(const std::string & dest_ip, const std:
3333

3434
void AvailabilityConverter::setSubscriber()
3535
{
36-
const auto qos = rclcpp::QoS(1).transient_local();
36+
const auto qos = rclcpp::QoS(1);
3737
availability_callback_group_ =
3838
node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
3939
rclcpp::SubscriptionOptions availability_options = rclcpp::SubscriptionOptions();
@@ -75,7 +75,8 @@ void AvailabilityConverter::convertToUdp(
7575
availability.pull_over = availability_msg->pull_over;
7676
udp_availability_sender_->send(availability);
7777
} else {
78-
RCLCPP_ERROR(node_->get_logger(), "Failed to take control mode report");
78+
RCLCPP_ERROR_THROTTLE(
79+
node_->get_logger(), *node_->get_clock(), 5000, "Failed to take control mode report");
7980
}
8081
}
8182

‎system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -25,13 +25,13 @@
2525
// Autoware
2626
#include <tier4_autoware_utils/ros/update_param.hpp>
2727

28-
#include <tier4_system_msgs/msg/mrm_state.hpp>
29-
#include <tier4_system_msgs/msg/mrm_behavior.hpp>
3028
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
3129
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
3230
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
3331
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
32+
#include <tier4_system_msgs/msg/mrm_behavior.hpp>
3433
#include <tier4_system_msgs/msg/mrm_behavior_status.hpp>
34+
#include <tier4_system_msgs/msg/mrm_state.hpp>
3535
#include <tier4_system_msgs/msg/operation_mode_availability.hpp>
3636
#include <tier4_system_msgs/srv/operate_mrm.hpp>
3737

‎system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -227,8 +227,8 @@ void MrmHandler::publishMrmState()
227227

228228
void MrmHandler::operateMrm()
229229
{
230-
using tier4_system_msgs::msg::MrmState;
231230
using tier4_system_msgs::msg::MrmBehavior;
231+
using tier4_system_msgs::msg::MrmState;
232232

233233
if (mrm_state_.state == MrmState::NORMAL) {
234234
// Cancel MRM behavior when returning to NORMAL state
@@ -271,8 +271,8 @@ void MrmHandler::operateMrm()
271271

272272
void MrmHandler::handleFailedRequest()
273273
{
274-
using tier4_system_msgs::msg::MrmState;
275274
using tier4_system_msgs::msg::MrmBehavior;
275+
using tier4_system_msgs::msg::MrmState;
276276

277277
if (requestMrmBehavior(MrmBehavior::EMERGENCY_STOP, CALL)) {
278278
if (mrm_state_.state != MrmState::MRM_OPERATING) transitionTo(MrmState::MRM_OPERATING);
@@ -286,8 +286,8 @@ bool MrmHandler::requestMrmBehavior(
286286
const tier4_system_msgs::msg::MrmBehavior::_type_type & mrm_behavior,
287287
RequestType request_type) const
288288
{
289-
using tier4_system_msgs::msg::MrmState;
290289
using tier4_system_msgs::msg::MrmBehavior;
290+
using tier4_system_msgs::msg::MrmState;
291291

292292
auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>();
293293
if (request_type == RequestType::CALL) {
@@ -465,9 +465,9 @@ void MrmHandler::transitionTo(const int new_state)
465465

466466
void MrmHandler::updateMrmState()
467467
{
468-
using tier4_system_msgs::msg::MrmState;
469-
using tier4_system_msgs::msg::MrmBehavior;
470468
using autoware_auto_vehicle_msgs::msg::ControlModeReport;
469+
using tier4_system_msgs::msg::MrmBehavior;
470+
using tier4_system_msgs::msg::MrmState;
471471

472472
// Check emergency
473473
const bool is_emergency = isEmergency();
@@ -522,8 +522,8 @@ void MrmHandler::updateMrmState()
522522

523523
tier4_system_msgs::msg::MrmBehavior::_type_type MrmHandler::getCurrentMrmBehavior()
524524
{
525-
using tier4_system_msgs::msg::MrmState;
526525
using tier4_system_msgs::msg::MrmBehavior;
526+
using tier4_system_msgs::msg::MrmState;
527527
using tier4_system_msgs::msg::OperationModeAvailability;
528528

529529
// State machine

‎system/mrm_stop_operator/config/mrm_stop_operator.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -3,4 +3,3 @@
33
min_acceleration: -4.0 # min acceleration for sub ecu mrm stop [m/s^2]
44
max_jerk: 5.0 # max jerk for sub ecu mrm stop [m/s^3]
55
min_jerk: -5.0 # min jerk for sub ecu mrm stop [m/s^3]
6-

‎system/mrm_stop_operator/launch/mrm_stop_operator.launch.xml

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

44
<node pkg="mrm_stop_operator" exec="mrm_stop_operator_node" name="mrm_stop_operator" output="screen">
55
<param from="$(var mrm_stop_operator_param_path)"/>
6-
6+
77
<remap from="~/input/mrm_request" to="/system/mrm_request"/>
88
<remap from="~/output/velocity_limit" to="/planning/scenario_planning/max_velocity_candidates"/>
99
<remap from="~/output/velocity_limit_clear_command" to="/planning/scenario_planning/clear_velocity_limit"/>

‎system/mrm_stop_operator/src/mrm_stop_operator.cpp

+7-6
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,9 @@ MrmStopOperator::MrmStopOperator(const rclcpp::NodeOptions & node_options)
3333
// Publisher
3434
pub_velocity_limit_ = create_publisher<tier4_planning_msgs::msg::VelocityLimit>(
3535
"~/output/velocity_limit", rclcpp::QoS{10}.transient_local());
36-
pub_velocity_limit_clear_command_ = create_publisher<tier4_planning_msgs::msg::VelocityLimitClearCommand>(
37-
"~/output/velocity_limit_clear_command", rclcpp::QoS{10}.transient_local());
36+
pub_velocity_limit_clear_command_ =
37+
create_publisher<tier4_planning_msgs::msg::VelocityLimitClearCommand>(
38+
"~/output/velocity_limit_clear_command", rclcpp::QoS{10}.transient_local());
3839

3940
// Timer
4041

@@ -48,13 +49,13 @@ MrmStopOperator::MrmStopOperator(const rclcpp::NodeOptions & node_options)
4849
initState();
4950

5051
// Diagnostics
51-
5252
}
5353

5454
void MrmStopOperator::onMrmRequest(const tier4_system_msgs::msg::MrmBehavior::ConstSharedPtr msg)
5555
{
56-
if (msg->type == tier4_system_msgs::msg::MrmBehavior::COMFORTABLE_STOP &&
57-
last_mrm_request_.type != tier4_system_msgs::msg::MrmBehavior::COMFORTABLE_STOP) {
56+
if (
57+
msg->type == tier4_system_msgs::msg::MrmBehavior::COMFORTABLE_STOP &&
58+
last_mrm_request_.type != tier4_system_msgs::msg::MrmBehavior::COMFORTABLE_STOP) {
5859
tier4_planning_msgs::msg::VelocityLimit velocity_limit;
5960
velocity_limit.stamp = this->now();
6061
velocity_limit.max_velocity = 0.0;
@@ -64,7 +65,7 @@ void MrmStopOperator::onMrmRequest(const tier4_system_msgs::msg::MrmBehavior::Co
6465
velocity_limit.constraints.min_jerk = params_.min_jerk;
6566
velocity_limit.sender = "mrm_stop_operator";
6667
pub_velocity_limit_->publish(velocity_limit);
67-
68+
6869
last_mrm_request_ = *msg;
6970
}
7071
}

‎system/mrm_stop_operator/src/mrm_stop_operator.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef MRM_STOP_OPERATOR__MRM_STOP_OPERATOR_HPP_
16-
#define MRM_STOP_OPERATOR__MRM_STOP_OPERATOR_HPP_
15+
#ifndef MRM_STOP_OPERATOR_HPP_
16+
#define MRM_STOP_OPERATOR_HPP_
1717

1818
// include
1919
#include <rclcpp/rclcpp.hpp>
@@ -51,7 +51,8 @@ class MrmStopOperator : public rclcpp::Node
5151

5252
// Publisher
5353
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr pub_velocity_limit_;
54-
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimitClearCommand>::SharedPtr pub_velocity_limit_clear_command_;
54+
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimitClearCommand>::SharedPtr
55+
pub_velocity_limit_clear_command_;
5556

5657
// Service
5758

@@ -61,12 +62,11 @@ class MrmStopOperator : public rclcpp::Node
6162

6263
// State
6364
tier4_system_msgs::msg::MrmBehavior last_mrm_request_;
64-
65+
6566
void initState();
6667

6768
// Diagnostics
68-
6969
};
7070
} // namespace mrm_stop_operator
7171

72-
#endif // MRM_STOP_OPERATOR__MRM_STOP_OPERATOR_HPP_
72+
#endif // MRM_STOP_OPERATOR_HPP_

0 commit comments

Comments
 (0)
Please sign in to comment.