Skip to content

Commit ab6b7e3

Browse files
authored
Merge branch 'main' into chore/update_maintainer_yoshiri
2 parents f04fca4 + d3886e4 commit ab6b7e3

File tree

2 files changed

+23
-29
lines changed

2 files changed

+23
-29
lines changed

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -104,9 +104,8 @@ class MrmHandler : public rclcpp::Node
104104
pub_hazard_cmd_;
105105
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::GearCommand>::SharedPtr pub_gear_cmd_;
106106

107-
autoware_auto_vehicle_msgs::msg::HazardLightsCommand createHazardCmdMsg();
108-
autoware_auto_vehicle_msgs::msg::GearCommand createGearCmdMsg();
109-
void publishControlCommands();
107+
void publishHazardCmd();
108+
void publishGearCmd();
110109

111110
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
112111

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+21-26
Original file line numberDiff line numberDiff line change
@@ -161,48 +161,39 @@ void MrmHandler::onOperationModeState(
161161
operation_mode_state_ = msg;
162162
}
163163

164-
autoware_auto_vehicle_msgs::msg::HazardLightsCommand MrmHandler::createHazardCmdMsg()
164+
void MrmHandler::publishHazardCmd()
165165
{
166166
using autoware_auto_vehicle_msgs::msg::HazardLightsCommand;
167167
HazardLightsCommand msg;
168168

169-
// Check emergency
170-
const bool is_emergency = isEmergency();
171-
169+
msg.stamp = this->now();
172170
if (is_emergency_holding_) {
173171
// turn hazard on during emergency holding
174172
msg.command = HazardLightsCommand::ENABLE;
175-
} else if (is_emergency && param_.turning_hazard_on.emergency) {
173+
} else if (isEmergency() && param_.turning_hazard_on.emergency) {
176174
// turn hazard on if vehicle is in emergency state and
177175
// turning hazard on if emergency flag is true
178176
msg.command = HazardLightsCommand::ENABLE;
179177
} else {
180178
msg.command = HazardLightsCommand::NO_COMMAND;
181179
}
182-
return msg;
180+
181+
pub_hazard_cmd_->publish(msg);
183182
}
184183

185-
void MrmHandler::publishControlCommands()
184+
void MrmHandler::publishGearCmd()
186185
{
187186
using autoware_auto_vehicle_msgs::msg::GearCommand;
187+
GearCommand msg;
188188

189-
// Create timestamp
190-
const auto stamp = this->now();
191-
192-
// Publish hazard command
193-
pub_hazard_cmd_->publish(createHazardCmdMsg());
194-
195-
// Publish gear
196-
{
197-
GearCommand msg;
198-
msg.stamp = stamp;
199-
if (param_.use_parking_after_stopped && isStopped()) {
200-
msg.command = GearCommand::PARK;
201-
} else {
202-
msg.command = GearCommand::DRIVE;
203-
}
204-
pub_gear_cmd_->publish(msg);
189+
msg.stamp = this->now();
190+
if (param_.use_parking_after_stopped && isStopped()) {
191+
msg.command = GearCommand::PARK;
192+
} else {
193+
msg.command = GearCommand::DRIVE;
205194
}
195+
196+
pub_gear_cmd_->publish(msg);
206197
}
207198

208199
void MrmHandler::publishMrmState()
@@ -380,17 +371,21 @@ void MrmHandler::onTimer()
380371
this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
381372
"heartbeat operation_mode_availability is timeout");
382373
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING;
383-
publishControlCommands();
374+
publishHazardCmd();
375+
publishGearCmd();
384376
return;
385377
}
386378

387379
// Update Emergency State
388380
updateMrmState();
389381

390-
// Publish control commands
391-
publishControlCommands();
382+
// Operate MRM
392383
operateMrm();
384+
385+
// Publish
393386
publishMrmState();
387+
publishHazardCmd();
388+
publishGearCmd();
394389
}
395390

396391
void MrmHandler::transitionTo(const int new_state)

0 commit comments

Comments
 (0)