Skip to content

Commit b7effd3

Browse files
committed
fix: clang-tidy draft
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent cdf69b2 commit b7effd3

7 files changed

+45
-76
lines changed

tools/reaction_analyzer/include/reaction_analyzer_node.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,7 @@ struct NodeParams
6666
class ReactionAnalyzerNode : public rclcpp::Node
6767
{
6868
public:
69-
explicit ReactionAnalyzerNode(rclcpp::NodeOptions options);
70-
~ReactionAnalyzerNode() = default;
69+
explicit ReactionAnalyzerNode(rclcpp::NodeOptions node_options);
7170

7271
Odometry::ConstSharedPtr odometry_ptr_;
7372

tools/reaction_analyzer/include/subscriber.hpp

+2-8
Original file line numberDiff line numberDiff line change
@@ -141,13 +141,7 @@ class SubscriberBase
141141
rclcpp::Node * node, Odometry::ConstSharedPtr & odometry, std::atomic<bool> & spawn_object_cmd,
142142
const EntityParams & entity_params);
143143

144-
// Instances of SubscriberBase cannot be copied
145-
SubscriberBase(const SubscriberBase &) = delete;
146-
SubscriberBase & operator=(const SubscriberBase &) = delete;
147-
148-
~SubscriberBase() = default;
149-
150-
std::optional<std::unordered_map<std::string, MessageBufferVariant>> getMessageBuffersMap();
144+
std::optional<std::unordered_map<std::string, MessageBufferVariant>> get_message_buffers_map();
151145
void reset();
152146

153147
private:
@@ -179,7 +173,7 @@ class SubscriberBase
179173
std::optional<size_t> find_first_brake_idx(
180174
const std::vector<AckermannControlCommand> & cmd_array);
181175
void set_control_command_to_buffer(
182-
std::vector<AckermannControlCommand> & buffer, const AckermannControlCommand & cmd);
176+
std::vector<AckermannControlCommand> & buffer, const AckermannControlCommand & cmd) const;
183177

184178
// Callbacks for modules are subscribed
185179
void on_control_command(

tools/reaction_analyzer/include/topic_publisher.hpp

+6-7
Original file line numberDiff line numberDiff line change
@@ -110,23 +110,23 @@ struct PublisherVarAccessor
110110
{
111111
// Template struct to check if a type has a header member.
112112
template <typename T, typename = std::void_t<>>
113-
struct has_header : std::false_type
113+
struct HasHeader : std::false_type
114114
{
115115
};
116116

117117
template <typename T>
118-
struct has_header<T, std::void_t<decltype(T::header)>> : std::true_type
118+
struct HasHeader<T, std::void_t<decltype(T::header)>> : std::true_type
119119
{
120120
};
121121

122122
// Template struct to check if a type has a stamp member.
123123
template <typename T, typename = std::void_t<>>
124-
struct has_stamp : std::false_type
124+
struct HasStamp : std::false_type
125125
{
126126
};
127127

128128
template <typename T>
129-
struct has_stamp<T, std::void_t<decltype(T::stamp)>> : std::true_type
129+
struct HasStamp<T, std::void_t<decltype(T::stamp)>> : std::true_type
130130
{
131131
};
132132

@@ -142,9 +142,9 @@ struct PublisherVarAccessor
142142
} else {
143143
*msg_to_be_published = *publisherVar.empty_area_message;
144144
}
145-
if constexpr (has_header<MessageType>::value) {
145+
if constexpr (HasHeader<MessageType>::value) {
146146
msg_to_be_published->header.stamp = current_time;
147-
} else if constexpr (has_stamp<MessageType>::value) {
147+
} else if constexpr (HasStamp<MessageType>::value) {
148148
msg_to_be_published->stamp = current_time;
149149
}
150150
publisherVar.publisher->publish(std::move(msg_to_be_published));
@@ -200,7 +200,6 @@ class TopicPublisher
200200
std::optional<rclcpp::Time> & spawn_cmd_time, const RunningMode & node_running_mode,
201201
const EntityParams & entity_params);
202202

203-
~TopicPublisher() = default;
204203
void reset();
205204

206205
private:

tools/reaction_analyzer/src/reaction_analyzer_node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,8 @@ void ReactionAnalyzerNode::on_ground_truth_pose(PoseStamped::ConstSharedPtr msg_
5151
ground_truth_pose_ptr_ = std::move(msg_ptr);
5252
}
5353

54-
ReactionAnalyzerNode::ReactionAnalyzerNode(rclcpp::NodeOptions options)
55-
: Node("reaction_analyzer_node", options.automatically_declare_parameters_from_overrides(true))
54+
ReactionAnalyzerNode::ReactionAnalyzerNode(rclcpp::NodeOptions node_options)
55+
: Node("reaction_analyzer_node", node_options.automatically_declare_parameters_from_overrides(true))
5656
{
5757
using std::placeholders::_1;
5858

@@ -173,7 +173,7 @@ void ReactionAnalyzerNode::on_timer()
173173
if (!spawn_cmd_time) return;
174174

175175
// Get the reacted messages, if all modules reacted
176-
const auto message_buffers = subscriber_ptr_->getMessageBuffersMap();
176+
const auto message_buffers = subscriber_ptr_->get_message_buffers_map();
177177

178178
if (message_buffers) {
179179
// if reacted, calculate the results

tools/reaction_analyzer/src/subscriber.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ SubscriberBase::SubscriberBase(
4040

4141
void SubscriberBase::init_reaction_chains_and_params()
4242
{
43-
auto stringToMessageType = [](const std::string & input) {
43+
auto string_to_message_type = [](const std::string & input) {
4444
if (input == "autoware_auto_control_msgs/msg/AckermannControlCommand") {
4545
return SubscriberMessageType::ACKERMANN_CONTROL_COMMAND;
4646
} else if (input == "autoware_auto_planning_msgs/msg/Trajectory") {
@@ -58,7 +58,7 @@ void SubscriberBase::init_reaction_chains_and_params()
5858
}
5959
};
6060

61-
auto stringToReactionType = [](const std::string & input) {
61+
auto string_to_reaction_type = [](const std::string & input) {
6262
if (input == "first_brake_params") {
6363
return ReactionType::FIRST_BRAKE;
6464
} else if (input == "search_zero_vel_params") {
@@ -82,7 +82,7 @@ void SubscriberBase::init_reaction_chains_and_params()
8282
tmp.time_debug_topic_address =
8383
node_->get_parameter_or(module_name + ".time_debug_topic_name", std::string(""));
8484
tmp.message_type =
85-
stringToMessageType(node_->get_parameter(module_name + ".message_type").as_string());
85+
string_to_message_type(node_->get_parameter(module_name + ".message_type").as_string());
8686
if (tmp.message_type != SubscriberMessageType::UNKNOWN) {
8787
chain_modules_.emplace_back(tmp);
8888
} else {
@@ -99,7 +99,7 @@ void SubscriberBase::init_reaction_chains_and_params()
9999
const auto module_names = node_->list_parameters({param_key}, 3).prefixes;
100100
for (const auto & module_name : module_names) {
101101
const auto splitted_name = split(module_name, '.');
102-
const auto type = stringToReactionType(splitted_name.back());
102+
const auto type = string_to_reaction_type(splitted_name.back());
103103
switch (type) {
104104
case ReactionType::FIRST_BRAKE: {
105105
reaction_params_.first_brake_params.debug_control_commands =
@@ -460,7 +460,7 @@ bool SubscriberBase::init_subscribers()
460460
}
461461

462462
std::optional<std::unordered_map<std::string, MessageBufferVariant>>
463-
SubscriberBase::getMessageBuffersMap()
463+
SubscriberBase::get_message_buffers_map()
464464
{
465465
std::lock_guard<std::mutex> lock(mutex_);
466466
if (message_buffers_.empty()) {
@@ -997,7 +997,7 @@ std::optional<size_t> SubscriberBase::find_first_brake_idx(
997997
}
998998

999999
void SubscriberBase::set_control_command_to_buffer(
1000-
std::vector<AckermannControlCommand> & buffer, const AckermannControlCommand & cmd)
1000+
std::vector<AckermannControlCommand> & buffer, const AckermannControlCommand & cmd) const
10011001
{
10021002
const auto last_cmd_time = cmd.stamp;
10031003
if (!buffer.empty()) {

tools/reaction_analyzer/src/topic_publisher.cpp

+16-20
Original file line numberDiff line numberDiff line change
@@ -304,9 +304,8 @@ void TopicPublisher::init_rosbag_publishers()
304304
if (it != topics.end()) {
305305
return string_to_publisher_message_type(
306306
it->topic_metadata.type); // Return the message type if found
307-
} else {
308-
return PublisherMessageType::UNKNOWN; //
309307
}
308+
return PublisherMessageType::UNKNOWN;
310309
};
311310

312311
// Collect timestamps for each topic to set the frequency of the publishers
@@ -349,25 +348,24 @@ void TopicPublisher::init_rosbag_publishers()
349348

350349
const auto & topics = reader.get_metadata().topics_with_message_count;
351350

352-
auto getMessageTypeForTopic = [&topics, &string_to_publisher_message_type](
353-
const std::string & topicName) -> PublisherMessageType {
351+
auto get_message_type_for_topic = [&topics, &string_to_publisher_message_type](
352+
const std::string & topicName) -> PublisherMessageType {
354353
auto it = std::find_if(topics.begin(), topics.end(), [&topicName](const auto & topic) {
355354
return topic.topic_metadata.name == topicName;
356355
});
357356

358357
if (it != topics.end()) {
359358
return string_to_publisher_message_type(
360359
it->topic_metadata.type); // Return the message type if found
361-
} else {
362-
return PublisherMessageType::UNKNOWN;
363360
}
361+
return PublisherMessageType::UNKNOWN;
364362
};
365363

366364
while (reader.has_next()) {
367365
auto bag_message = reader.read_next();
368366
const auto current_topic = bag_message->topic_name;
369367

370-
const auto message_type = getMessageTypeForTopic(current_topic);
368+
const auto message_type = get_message_type_for_topic(current_topic);
371369

372370
if (message_type == PublisherMessageType::UNKNOWN) {
373371
continue;
@@ -869,10 +867,10 @@ void TopicPublisher::set_period_to_variable_map(
869867
auto period_ms = std::chrono::duration_cast<std::chrono::milliseconds>(total_duration_ns) /
870868
(timestamps_tmp.size() - 1);
871869

872-
PublisherVariablesVariant & publisherVar = topic_publisher_map_[topic_name];
870+
PublisherVariablesVariant & publisher_variant = topic_publisher_map_[topic_name];
873871
PublisherVarAccessor accessor;
874872

875-
std::visit([&](auto & var) { accessor.set_period(var, period_ms); }, publisherVar);
873+
std::visit([&](auto & var) { accessor.set_period(var, period_ms); }, publisher_variant);
876874
}
877875
}
878876
}
@@ -973,24 +971,21 @@ bool TopicPublisher::set_publishers_and_timers_to_variable_map()
973971
// Create a timer to create phase difference bw timers which will be created for each lidar
974972
// topics
975973
auto one_shot_timer = node_->create_wall_timer(phase_dif, [this, period_pointcloud_ns]() {
976-
for (const auto & [lidar_name, publisher_var_pair] : lidar_pub_variable_pair_map_) {
974+
for (const auto & publisher_var_pair : lidar_pub_variable_pair_map_) {
975+
const auto & lidar_name = publisher_var_pair.first;
976+
const auto & publisher_var = publisher_var_pair.second;
977977
if (
978978
pointcloud_publish_timers_map_.find(lidar_name) == pointcloud_publish_timers_map_.end()) {
979-
// Create the periodic timer
980-
auto periodic_timer =
981-
node_->create_wall_timer(period_pointcloud_ns, [this, publisher_var_pair]() {
982-
this->pointcloud_messages_async_publisher(publisher_var_pair);
983-
});
984-
// Store the periodic timer to keep it alive
979+
auto periodic_timer = node_->create_wall_timer(
980+
period_pointcloud_ns,
981+
[this, publisher_var]() { this->pointcloud_messages_async_publisher(publisher_var); });
985982
pointcloud_publish_timers_map_[lidar_name] = periodic_timer;
986983
return;
987984
}
988985
}
989-
// close the timer
990986
one_shot_timer_shared_ptr_->cancel();
991987
});
992-
993-
one_shot_timer_shared_ptr_ = one_shot_timer; // Store a weak pointer to the timer
988+
one_shot_timer_shared_ptr_ = one_shot_timer;
994989
}
995990
return true;
996991
}
@@ -1010,7 +1005,8 @@ bool TopicPublisher::check_publishers_initialized_correctly()
10101005
node_->get_logger(),
10111006
"Empty area message couldn't found in the topic named: " << topic_name);
10121007
return false;
1013-
} else if (!object_spawned_message) {
1008+
}
1009+
if (!object_spawned_message) {
10141010
RCLCPP_ERROR_STREAM(
10151011
node_->get_logger(),
10161012
"Object spawned message couldn't found in the topic named: " << topic_name);

tools/reaction_analyzer/src/utils.cpp

+11-30
Original file line numberDiff line numberDiff line change
@@ -66,27 +66,27 @@ double calculate_time_diff_ms(const rclcpp::Time & start, const rclcpp::Time & e
6666
TimestampedReactionPairsVector convert_pipeline_map_to_sorted_vector(
6767
const PipelineMap & pipelineMap)
6868
{
69-
std::vector<std::tuple<rclcpp::Time, std::vector<ReactionPair>>> sortedVector;
69+
std::vector<std::tuple<rclcpp::Time, std::vector<ReactionPair>>> sorted_vector;
7070

7171
for (const auto & entry : pipelineMap) {
72-
auto sortedReactions = entry.second;
72+
auto sorted_reactions = entry.second;
7373
// Sort the vector of ReactionPair based on the published stamp
7474
std::sort(
75-
sortedReactions.begin(), sortedReactions.end(),
75+
sorted_reactions.begin(), sorted_reactions.end(),
7676
[](const ReactionPair & a, const ReactionPair & b) {
7777
return rclcpp::Time(a.second.published_stamp) < rclcpp::Time(b.second.published_stamp);
7878
});
7979

8080
// Add to the vector as a tuple
81-
sortedVector.push_back(std::make_tuple(entry.first, sortedReactions));
81+
sorted_vector.emplace_back(std::make_tuple(entry.first, sorted_reactions));
8282
}
8383

8484
// Sort the vector of tuples by rclcpp::Time
85-
std::sort(sortedVector.begin(), sortedVector.end(), [](const auto & a, const auto & b) {
85+
std::sort(sorted_vector.begin(), sorted_vector.end(), [](const auto & a, const auto & b) {
8686
return std::get<0>(a) < std::get<0>(b);
8787
});
8888

89-
return sortedVector;
89+
return sorted_vector;
9090
}
9191

9292
unique_identifier_msgs::msg::UUID generate_uuid_msg(const std::string & input)
@@ -212,70 +212,51 @@ bool search_pointcloud_near_pose(
212212
const pcl::PointCloud<pcl::PointXYZ> & pcl_pointcloud, const geometry_msgs::msg::Pose & pose,
213213
const double search_radius)
214214
{
215-
bool isAnyPointWithinRadius = std::any_of(
215+
return std::any_of(
216216
pcl_pointcloud.points.begin(), pcl_pointcloud.points.end(),
217217
[pose, search_radius](const auto & point) {
218218
return tier4_autoware_utils::calcDistance3d(pose.position, point) <= search_radius;
219219
});
220-
221-
if (isAnyPointWithinRadius) {
222-
return true;
223-
}
224-
return false;
225220
}
226221

227222
bool search_predicted_objects_near_pose(
228223
const PredictedObjects & predicted_objects, const geometry_msgs::msg::Pose & pose,
229224
const double search_radius)
230225
{
231-
bool isAnyObjectWithinRadius = std::any_of(
226+
return std::any_of(
232227
predicted_objects.objects.begin(), predicted_objects.objects.end(),
233228
[pose, search_radius](const PredictedObject & object) {
234229
return tier4_autoware_utils::calcDistance3d(
235230
pose.position, object.kinematics.initial_pose_with_covariance.pose.position) <=
236231
search_radius;
237232
});
238-
239-
if (isAnyObjectWithinRadius) {
240-
return true;
241-
}
242-
return false;
233+
;
243234
}
244235

245236
bool search_detected_objects_near_pose(
246237
const DetectedObjects & detected_objects, const geometry_msgs::msg::Pose & pose,
247238
const double search_radius)
248239
{
249-
bool isAnyObjectWithinRadius = std::any_of(
240+
return std::any_of(
250241
detected_objects.objects.begin(), detected_objects.objects.end(),
251242
[pose, search_radius](const DetectedObject & object) {
252243
return tier4_autoware_utils::calcDistance3d(
253244
pose.position, object.kinematics.pose_with_covariance.pose.position) <=
254245
search_radius;
255246
});
256-
257-
if (isAnyObjectWithinRadius) {
258-
return true;
259-
}
260-
return false;
261247
}
262248

263249
bool search_tracked_objects_near_pose(
264250
const TrackedObjects & tracked_objects, const geometry_msgs::msg::Pose & pose,
265251
const double search_radius)
266252
{
267-
bool isAnyObjectWithinRadius = std::any_of(
253+
return std::any_of(
268254
tracked_objects.objects.begin(), tracked_objects.objects.end(),
269255
[pose, search_radius](const TrackedObject & object) {
270256
return tier4_autoware_utils::calcDistance3d(
271257
pose.position, object.kinematics.pose_with_covariance.pose.position) <=
272258
search_radius;
273259
});
274-
275-
if (isAnyObjectWithinRadius) {
276-
return true;
277-
}
278-
return false;
279260
}
280261

281262
LatencyStats calculate_statistics(const std::vector<double> & latency_vec)

0 commit comments

Comments
 (0)