Skip to content

Commit 38542d6

Browse files
committed
lint errors
1 parent aeffb9a commit 38542d6

File tree

3 files changed

+27
-17
lines changed

3 files changed

+27
-17
lines changed

greenwave_monitor/include/minimal_publisher_node.hpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,14 +17,18 @@
1717

1818
#pragma once
1919

20+
#include <memory>
21+
#include <string>
22+
#include <vector>
23+
2024
#include "rclcpp/rclcpp.hpp"
2125
#include "sensor_msgs/msg/image.hpp"
2226
#include "sensor_msgs/msg/imu.hpp"
2327
#include "std_msgs/msg/string.hpp"
2428
#include "message_diagnostics.hpp"
2529
#include "rclcpp/subscription_options.hpp"
2630

27-
using namespace std::chrono_literals;
31+
using std::chrono_literals::operator""ms;
2832

2933
class MinimalPublisher : public rclcpp::Node
3034
{

greenwave_monitor/src/greenwave_monitor.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,11 +18,12 @@
1818
#include "greenwave_monitor.hpp"
1919

2020
#include <algorithm>
21-
#include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"
2221
#include <cstring>
2322
#include <mutex>
2423
#include <unordered_map>
2524

25+
#include "rosidl_typesupport_introspection_cpp/message_introspection.hpp"
26+
2627
using namespace std::chrono_literals;
2728

2829
GreenwaveMonitor::GreenwaveMonitor(const rclcpp::NodeOptions & options)
@@ -227,7 +228,7 @@ bool GreenwaveMonitor::has_header_from_type(const std::string & type_name)
227228
{"std_msgs/msg/Float64", false},
228229
{"std_msgs/msg/Bool", false},
229230
{"std_msgs/msg/Empty", false},
230-
{"std_msgs/msg/Header", false}, // Header itself doesn't have a header
231+
{"std_msgs/msg/Header", false}, // Header itself doesn't have a header
231232

232233
// Common message types without headers
233234
{"geometry_msgs/msg/Twist", false},
@@ -326,7 +327,7 @@ GreenwaveMonitor::GetTimestampFromSerializedMessage(
326327
const std::string & type)
327328
{
328329
if (!has_header_from_type(type)) {
329-
return std::chrono::time_point<std::chrono::system_clock>(); // timestamp 0 as fallback
330+
return std::chrono::time_point<std::chrono::system_clock>(); // timestamp 0 as fallback
330331
}
331332

332333
int32_t timestamp_sec;

greenwave_monitor/test/test_message_diagnostics.cpp

Lines changed: 18 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -68,12 +68,12 @@ TEST_F(MessageDiagnosticsTest, FrameRateMsgTest)
6868
message_diagnostics::MessageDiagnostics message_diagnostics(
6969
*node_, "test_topic", message_diagnostics::MessageDiagnosticsConfig());
7070

71-
uint64_t timestamp = test_constants::kStartTimestampNs; // in nanoseconds
71+
uint64_t timestamp = test_constants::kStartTimestampNs; // in nanoseconds
7272
for (int i = 0; i < 1000; i++) {
7373
message_diagnostics.updateDiagnostics(timestamp);
74-
timestamp += 10000000; // 10 ms in nanoseconds
74+
timestamp += 10000000; // 10 ms in nanoseconds
7575
}
76-
EXPECT_EQ(message_diagnostics.getFrameRateMsg(), 100); // 100 Hz
76+
EXPECT_EQ(message_diagnostics.getFrameRateMsg(), 100); // 100 Hz
7777
}
7878

7979
TEST_F(MessageDiagnosticsTest, FrameRateNodeTest)
@@ -82,11 +82,12 @@ TEST_F(MessageDiagnosticsTest, FrameRateNodeTest)
8282
message_diagnostics::MessageDiagnostics message_diagnostics(
8383
*node_, "test_topic", message_diagnostics::MessageDiagnosticsConfig());
8484

85-
constexpr auto timestamp = test_constants::kStartTimestampNs; // dummy timestamp, not used for node time calculation
85+
// dummy timestamp, not used for node time calculation
86+
constexpr auto timestamp = test_constants::kStartTimestampNs;
8687
const auto start_time = std::chrono::high_resolution_clock::now();
8788

8889
constexpr int num_messages = 1000;
89-
constexpr int interarrival_time_ms = 10; // 100 hz
90+
constexpr int interarrival_time_ms = 10; // 100 hz
9091

9192
for (int i = 0; i < num_messages; i++) {
9293
message_diagnostics.updateDiagnostics(timestamp);
@@ -98,7 +99,7 @@ TEST_F(MessageDiagnosticsTest, FrameRateNodeTest)
9899

99100
const double expected_frame_rate = static_cast<double>(num_messages) / total_duration.count();
100101

101-
EXPECT_NEAR(message_diagnostics.getFrameRateNode(), expected_frame_rate, 2.0); // allow 2.0 Hz error
102+
EXPECT_NEAR(message_diagnostics.getFrameRateNode(), expected_frame_rate, 2.0); // allow 2.0 Hz error
102103
}
103104

104105
TEST_F(MessageDiagnosticsTest, MessageLatencyTest)
@@ -116,22 +117,24 @@ TEST_F(MessageDiagnosticsTest, MessageLatencyTest)
116117

117118
message_diagnostics.updateDiagnostics(msg_timestamp.nanoseconds());
118119

119-
EXPECT_NEAR(message_diagnostics.getLatency(), expected_latency_ms, 1.0); // allow 1 ms tolerance
120+
EXPECT_NEAR(message_diagnostics.getLatency(), expected_latency_ms, 1.0); // allow 1 ms tolerance
120121
}
121122

122123
TEST_F(MessageDiagnosticsTest, DiagnosticPublishSubscribeTest)
123124
{
124-
constexpr int input_frequency = 50; // 50 Hz
125+
constexpr int input_frequency = 50; // 50 Hz
126+
// 20 ms in nanoseconds
125127
const int64_t interarrival_time_ns = static_cast<int64_t>(
126-
::message_diagnostics::constants::kSecondsToNanoseconds / input_frequency); // 20 ms in nanoseconds
128+
::message_diagnostics::constants::kSecondsToNanoseconds / input_frequency);
127129

128130
// Initialize MessageDiagnostics with diagnostics enabled
129131
message_diagnostics::MessageDiagnosticsConfig config;
130132
config.enable_msg_time_diagnostics = true;
131133
config.enable_node_time_diagnostics = true;
132134
config.enable_increasing_msg_time_diagnostics = true;
135+
// in us
133136
config.expected_dt_us = interarrival_time_ns /
134-
::message_diagnostics::constants::kMicrosecondsToNanoseconds; // in us
137+
::message_diagnostics::constants::kMicrosecondsToNanoseconds;
135138

136139
message_diagnostics::MessageDiagnostics message_diagnostics(*node_, "test_topic", config);
137140

@@ -144,10 +147,12 @@ TEST_F(MessageDiagnosticsTest, DiagnosticPublishSubscribeTest)
144147
received_diagnostics.push_back(msg);
145148
});
146149

150+
// 50 ms delay
147151
constexpr int64_t delay_time_ns = 50 *
148152
static_cast<int64_t>(::message_diagnostics::constants::kMillisecondsToMicroseconds) *
149-
static_cast<int64_t>(::message_diagnostics::constants::kMicrosecondsToNanoseconds); // 50 ms delay
150-
auto msg_timestamp = test_constants::kStartTimestampNs; // Starting message timestamp in nanoseconds
153+
static_cast<int64_t>(::message_diagnostics::constants::kMicrosecondsToNanoseconds);
154+
// Starting message timestamp in nanoseconds
155+
auto msg_timestamp = test_constants::kStartTimestampNs;
151156

152157
int sent_count = 0;
153158
const auto start_time = std::chrono::high_resolution_clock::now();
@@ -170,7 +175,7 @@ TEST_F(MessageDiagnosticsTest, DiagnosticPublishSubscribeTest)
170175
}
171176
// Add a jitter by delaying at count 10
172177
if (sent_count == 10) {
173-
std::this_thread::sleep_for(std::chrono::nanoseconds(delay_time_ns)); // 50 ms delay
178+
std::this_thread::sleep_for(std::chrono::nanoseconds(delay_time_ns)); // 50 ms delay
174179
msg_timestamp += delay_time_ns;
175180
}
176181

0 commit comments

Comments
 (0)