Skip to content

Commit eae2aaa

Browse files
committed
build: revert clang-tidy related changes
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent eedd133 commit eae2aaa

File tree

5 files changed

+15
-15
lines changed

5 files changed

+15
-15
lines changed

planning/autoware_behavior_velocity_planner/src/node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -154,7 +154,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
154154
// Initialize PlannerManager
155155
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
156156
// workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
157-
if (name.empty()) {
157+
if (name == "") {
158158
break;
159159
}
160160
planner_manager_.launchScenePlugin(*this, name);
@@ -182,7 +182,7 @@ void BehaviorVelocityPlannerNode::onUnloadPlugin(
182182

183183
// NOTE: argument planner_data must not be referenced for multithreading
184184
bool BehaviorVelocityPlannerNode::isDataReady(
185-
const PlannerData & planner_data, rclcpp::Clock clock) const
185+
const PlannerData planner_data, rclcpp::Clock clock) const
186186
{
187187
const auto & d = planner_data;
188188

@@ -463,7 +463,7 @@ void BehaviorVelocityPlannerNode::publishDebugMarker(
463463
for (size_t i = 0; i < path.points.size(); ++i) {
464464
visualization_msgs::msg::Marker marker;
465465
marker.header = path.header;
466-
marker.id = static_cast<int32_t>(i);
466+
marker.id = i;
467467
marker.type = visualization_msgs::msg::Marker::ARROW;
468468
marker.pose = path.points.at(i).pose;
469469
marker.scale.y = marker.scale.z = 0.05;

planning/autoware_behavior_velocity_planner/src/node.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
111111
BehaviorVelocityPlannerManager planner_manager_;
112112
bool is_driving_forward_{true};
113113
HADMapBin::ConstSharedPtr map_ptr_{nullptr};
114-
bool has_received_map_{};
114+
bool has_received_map_;
115115

116116
rclcpp::Service<LoadPlugin>::SharedPtr srv_load_plugin_;
117117
rclcpp::Service<UnloadPlugin>::SharedPtr srv_unload_plugin_;
@@ -125,8 +125,8 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
125125
std::mutex mutex_;
126126

127127
// function
128-
geometry_msgs::msg::PoseStamped get_current_pose();
129-
bool isDataReady(const PlannerData & planner_data, rclcpp::Clock clock) const;
128+
geometry_msgs::msg::PoseStamped getCurrentPose();
129+
bool isDataReady(const PlannerData planner_data, rclcpp::Clock clock) const;
130130
autoware_auto_planning_msgs::msg::Path generatePath(
131131
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
132132
const PlannerData & planner_data);

planning/autoware_behavior_velocity_planner/src/planner_manager.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose)
3535
}
3636

3737
diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag(
38-
const std::string & stop_reason, const geometry_msgs::msg::Pose & stop_pose)
38+
const std::string stop_reason, const geometry_msgs::msg::Pose & stop_pose)
3939
{
4040
diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag;
4141
diagnostic_msgs::msg::KeyValue stop_reason_diag_kv;
@@ -83,7 +83,7 @@ void BehaviorVelocityPlannerManager::removeScenePlugin(
8383
{
8484
auto it = std::remove_if(
8585
scene_manager_plugins_.begin(), scene_manager_plugins_.end(),
86-
[&](const std::shared_ptr<behavior_velocity_planner::PluginInterface> & plugin) {
86+
[&](const std::shared_ptr<behavior_velocity_planner::PluginInterface> plugin) {
8787
return plugin->getModuleName() == name;
8888
});
8989

@@ -109,11 +109,11 @@ autoware_auto_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager:
109109
for (const auto & plugin : scene_manager_plugins_) {
110110
plugin->updateSceneModuleInstances(planner_data, input_path_msg);
111111
plugin->plan(&output_path_msg);
112-
const auto first_stop_path_point_index_from_plugin = plugin->getFirstStopPathPointIndex();
112+
const auto firstStopPathPointIndex = plugin->getFirstStopPathPointIndex();
113113

114-
if (first_stop_path_point_index_from_plugin) {
115-
if (first_stop_path_point_index_from_plugin.value() < first_stop_path_point_index) {
116-
first_stop_path_point_index = first_stop_path_point_index_from_plugin.value();
114+
if (firstStopPathPointIndex) {
115+
if (firstStopPathPointIndex.value() < first_stop_path_point_index) {
116+
first_stop_path_point_index = firstStopPathPointIndex.value();
117117
stop_reason_msg = plugin->getModuleName();
118118
}
119119
}

planning/autoware_behavior_velocity_planner/src/planner_manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class BehaviorVelocityPlannerManager
5252
const std::shared_ptr<const PlannerData> & planner_data,
5353
const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path_msg);
5454

55-
[[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const;
55+
diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const;
5656

5757
private:
5858
diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag_;

planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -115,8 +115,8 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
115115
}
116116

117117
void publishMandatoryTopics(
118-
const std::shared_ptr<PlanningInterfaceTestManager> & test_manager,
119-
const std::shared_ptr<BehaviorVelocityPlannerNode> & test_target_node)
118+
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
119+
std::shared_ptr<BehaviorVelocityPlannerNode> test_target_node)
120120
{
121121
// publish necessary topics from test_manager
122122
test_manager->publishTF(test_target_node, "/tf");

0 commit comments

Comments
 (0)