@@ -161,48 +161,39 @@ void MrmHandler::onOperationModeState(
161
161
operation_mode_state_ = msg;
162
162
}
163
163
164
- autoware_auto_vehicle_msgs::msg::HazardLightsCommand MrmHandler::createHazardCmdMsg ()
164
+ void MrmHandler::publishHazardCmd ()
165
165
{
166
166
using autoware_auto_vehicle_msgs::msg::HazardLightsCommand;
167
167
HazardLightsCommand msg;
168
168
169
- // Check emergency
170
- const bool is_emergency = isEmergency ();
171
-
169
+ msg.stamp = this ->now ();
172
170
if (is_emergency_holding_) {
173
171
// turn hazard on during emergency holding
174
172
msg.command = HazardLightsCommand::ENABLE;
175
- } else if (is_emergency && param_.turning_hazard_on .emergency ) {
173
+ } else if (isEmergency () && param_.turning_hazard_on .emergency ) {
176
174
// turn hazard on if vehicle is in emergency state and
177
175
// turning hazard on if emergency flag is true
178
176
msg.command = HazardLightsCommand::ENABLE;
179
177
} else {
180
178
msg.command = HazardLightsCommand::NO_COMMAND;
181
179
}
182
- return msg;
180
+
181
+ pub_hazard_cmd_->publish (msg);
183
182
}
184
183
185
- void MrmHandler::publishControlCommands ()
184
+ void MrmHandler::publishGearCmd ()
186
185
{
187
186
using autoware_auto_vehicle_msgs::msg::GearCommand;
187
+ GearCommand msg;
188
188
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;
205
194
}
195
+
196
+ pub_gear_cmd_->publish (msg);
206
197
}
207
198
208
199
void MrmHandler::publishMrmState ()
@@ -380,17 +371,21 @@ void MrmHandler::onTimer()
380
371
this ->get_logger (), *this ->get_clock (), std::chrono::milliseconds (1000 ).count (),
381
372
" heartbeat operation_mode_availability is timeout" );
382
373
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING;
383
- publishControlCommands ();
374
+ publishHazardCmd ();
375
+ publishGearCmd ();
384
376
return ;
385
377
}
386
378
387
379
// Update Emergency State
388
380
updateMrmState ();
389
381
390
- // Publish control commands
391
- publishControlCommands ();
382
+ // Operate MRM
392
383
operateMrm ();
384
+
385
+ // Publish
393
386
publishMrmState ();
387
+ publishHazardCmd ();
388
+ publishGearCmd ();
394
389
}
395
390
396
391
void MrmHandler::transitionTo (const int new_state)
0 commit comments