Skip to content

Commit df61be3

Browse files
committed
modify: {} mistake
Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com>
1 parent d3bed58 commit df61be3

File tree

1 file changed

+12
-12
lines changed

1 file changed

+12
-12
lines changed

system/mrm_stop_operator/src/mrm_stop_operator.cpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -107,19 +107,19 @@ void MrmStopOperator::onTimer()
107107
current_mrm_state_.stamp = this->now();
108108
pub_mrm_state_->publish(current_mrm_state_);
109109
}
110+
}
110111

111-
bool MrmStopOperator::isStopped()
112-
{
113-
constexpr auto th_stopped_velocity = 0.001;
114-
auto current_velocity = std::make_shared<autoware_vehicle_msgs::msg::VelocityReport>();
115-
rclcpp::MessageInfo message_info;
116-
117-
const bool success = sub_velocity_->take(*current_velocity, message_info);
118-
if (success) {
119-
return current_velocity->longitudinal_velocity < th_stopped_velocity;
120-
} else {
121-
return false;
122-
}
112+
bool MrmStopOperator::isStopped()
113+
{
114+
constexpr auto th_stopped_velocity = 0.001;
115+
auto current_velocity = std::make_shared<autoware_vehicle_msgs::msg::VelocityReport>();
116+
rclcpp::MessageInfo message_info;
117+
118+
const bool success = sub_velocity_->take(*current_velocity, message_info);
119+
if (success) {
120+
return current_velocity->longitudinal_velocity < th_stopped_velocity;
121+
} else {
122+
return false;
123123
}
124124
}
125125
} // namespace mrm_stop_operator

0 commit comments

Comments
 (0)