Skip to content

Commit

Permalink
feat: devide the fnction into two ones for refactoring
Browse files Browse the repository at this point in the history
  • Loading branch information
TetsuKawa committed Feb 1, 2024
1 parent 1155ca5 commit f201927
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,8 @@ class EmergencyHandler : public rclcpp::Node

autoware_auto_vehicle_msgs::msg::HazardLightsCommand createHazardCmdMsg();
autoware_auto_vehicle_msgs::msg::GearCommand createGearCmdMsg();
void publishControlCommands();
void publishHazardCommand();
void publishGearCommand();

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -188,27 +188,25 @@ autoware_auto_vehicle_msgs::msg::HazardLightsCommand EmergencyHandler::createHaz
return msg;
}

void EmergencyHandler::publishControlCommands()
void EmergencyHandler::publishHazardCommand()
{
using autoware_auto_vehicle_msgs::msg::GearCommand;

// Create timestamp
const auto stamp = this->now();

// Publish hazard command
pub_hazard_cmd_->publish(createHazardCmdMsg());
}

// Publish gear
{
GearCommand msg;
msg.stamp = stamp;
if (param_.use_parking_after_stopped && isStopped()) {
msg.command = GearCommand::PARK;
} else {
msg.command = GearCommand::DRIVE;
}
pub_gear_cmd_->publish(msg);
void EmergencyHandler::publishGearCommand()
{
// Publish gear command
using autoware_auto_vehicle_msgs::msg::GearCommand;\

GearCommand msg;
msg.stamp = this->now();
if (param_.use_parking_after_stopped && isStopped()) {
msg.command = GearCommand::PARK;
} else {
msg.command = GearCommand::DRIVE;
}
pub_gear_cmd_->publish(msg);
}

void EmergencyHandler::publishMrmState()
Expand Down Expand Up @@ -386,15 +384,18 @@ void EmergencyHandler::onTimer()
this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
"heartbeat operation_mode_availability is timeout");
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING;
publishControlCommands();
publishHazardCommand();
publishGearCommand()
return;
}

// Update Emergency State
updateMrmState();

// Publish control commands
publishControlCommands();
// Publish hazard and gear commands
publishHazardCommand();
publishGearCommand()

operateMrm();
publishMrmState();
}
Expand Down

0 comments on commit f201927

Please sign in to comment.