Skip to content

Commit

Permalink
fix clang-tidy warnings
Browse files Browse the repository at this point in the history
Signed-off-by: Alexey Panferov <[email protected]>
  • Loading branch information
lexavtanke committed Apr 17, 2024
1 parent d834855 commit 1d9eddf
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ TEST_F(AutowareControlCenterTest, RegisterNode)
auto client = autoware_control_center_
->create_client<autoware_control_center_msgs::srv::AutowareNodeRegister>(
"/autoware_control_center/srv/autoware_node_register");
if (!client->wait_for_service(20s)) {
if (!client->wait_for_service(std::chrono::seconds(20))) {
ASSERT_TRUE(false) << "Node register service not available after waiting";
}

Expand All @@ -58,7 +58,7 @@ TEST_F(AutowareControlCenterTest, RegisterNode)

auto result = client->async_send_request(request);
auto ret = rclcpp::spin_until_future_complete(
autoware_control_center_, result, 5s); // Wait for the result.
autoware_control_center_, result, std::chrono::seconds(5)); // Wait for the result.

ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);

Expand All @@ -72,7 +72,7 @@ TEST_F(AutowareControlCenterTest, DeregisterNode)
->create_client<autoware_control_center_msgs::srv::AutowareNodeRegister>(
"/autoware_control_center/srv/autoware_node_register");

if (!client_reg->wait_for_service(20s)) {
if (!client_reg->wait_for_service(std::chrono::seconds(20))) {
ASSERT_TRUE(false) << "Node register service not available after waiting";
}
// Register node first
Expand All @@ -82,7 +82,7 @@ TEST_F(AutowareControlCenterTest, DeregisterNode)

auto result_reg = client_reg->async_send_request(request_reg);
auto ret = rclcpp::spin_until_future_complete(
autoware_control_center_, result_reg, 5s); // Wait for the result.
autoware_control_center_, result_reg, std::chrono::seconds(5)); // Wait for the result.

ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
auto result_reg_payload = result_reg.get();
Expand All @@ -94,7 +94,7 @@ TEST_F(AutowareControlCenterTest, DeregisterNode)
auto client_dereg = autoware_control_center_
->create_client<autoware_control_center_msgs::srv::AutowareNodeDeregister>(
"/autoware_control_center/srv/autoware_node_deregister");
if (!client_dereg->wait_for_service(20s)) {
if (!client_dereg->wait_for_service(std::chrono::seconds(20))) {
ASSERT_TRUE(false) << "Node deregister service not available after waiting";
}

Expand All @@ -118,7 +118,7 @@ TEST_F(AutowareControlCenterTest, NodeErrorServiceNotRegistered)
autoware_control_center_->create_client<autoware_control_center_msgs::srv::AutowareNodeError>(
"/autoware_control_center/srv/autoware_node_error");

if (!client->wait_for_service(20s)) {
if (!client->wait_for_service(std::chrono::seconds(20))) {
ASSERT_TRUE(false) << "Node error service not available after waiting";
}

Expand All @@ -131,7 +131,7 @@ TEST_F(AutowareControlCenterTest, NodeErrorServiceNotRegistered)
error_request->message = "test message";

auto result_error = client->async_send_request(error_request);
auto ret = rclcpp::spin_until_future_complete(autoware_control_center_, result_error, 5s);
auto ret = rclcpp::spin_until_future_complete(autoware_control_center_, result_error, std::chrono::seconds(5));

ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
auto result_error_payload = result_error.get();
Expand All @@ -149,7 +149,7 @@ TEST_F(AutowareControlCenterTest, NodeErrorService)
->create_client<autoware_control_center_msgs::srv::AutowareNodeRegister>(
"/autoware_control_center/srv/autoware_node_register");

if (!client_reg->wait_for_service(20s)) {
if (!client_reg->wait_for_service(std::chrono::seconds(20))) {
ASSERT_TRUE(false) << "Node register service not available after waiting";
}
// Register node first
Expand All @@ -159,7 +159,7 @@ TEST_F(AutowareControlCenterTest, NodeErrorService)

auto result_reg = client_reg->async_send_request(request_reg);
auto ret_reg = rclcpp::spin_until_future_complete(
autoware_control_center_, result_reg, 5s); // Wait for the result.
autoware_control_center_, result_reg, std::chrono::seconds(5)); // Wait for the result.

ASSERT_EQ(ret_reg, rclcpp::FutureReturnCode::SUCCESS);
auto result_reg_payload = result_reg.get();
Expand All @@ -170,7 +170,7 @@ TEST_F(AutowareControlCenterTest, NodeErrorService)
autoware_control_center_->create_client<autoware_control_center_msgs::srv::AutowareNodeError>(
"/autoware_control_center/srv/autoware_node_error");

if (!error_client->wait_for_service(20s)) {
if (!error_client->wait_for_service(std::chrono::seconds(20))) {
ASSERT_TRUE(false) << "Node error service not available after waiting";
}

Expand All @@ -183,7 +183,7 @@ TEST_F(AutowareControlCenterTest, NodeErrorService)
error_request->message = "test message";

auto result_error = error_client->async_send_request(error_request);
auto ret_err = rclcpp::spin_until_future_complete(autoware_control_center_, result_error, 5s);
auto ret_err = rclcpp::spin_until_future_complete(autoware_control_center_, result_error, std::chrono::seconds(5));

ASSERT_EQ(ret_err, rclcpp::FutureReturnCode::SUCCESS);
auto result_error_payload = result_error.get();
Expand Down
5 changes: 1 addition & 4 deletions common/autoware_node/src/autoware_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,7 @@

#include <chrono>

using std::chrono::operator""ms;

constexpr std::chrono::milliseconds lease_delta =
20ms; ///< Buffer added to heartbeat to define lease.
constexpr std::chrono::milliseconds lease_delta(20); ///< Buffer added to heartbeat to define lease.

namespace autoware_node
{
Expand Down
8 changes: 4 additions & 4 deletions common/test_node/src/test_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,11 @@
class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher() : Node("minimal_publisher"), count_{0}
MinimalPublisher() : Node("minimal_publisher")
{
rclcpp::QoS qos_profile(10);
declare_parameter<int>("hz", 10);
const auto hz = get_parameter("hz").as_int();
declare_parameter<double>("hz", 10.0);
const double hz = get_parameter("hz").as_double();
std::chrono::milliseconds timer_period{static_cast<int>(1.0 / hz * 1000)};
std::chrono::milliseconds lease_duration{static_cast<int>(1.0 / hz * 1000 * 1.1)};
qos_profile.liveliness(RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC)
Expand All @@ -52,7 +52,7 @@ class MinimalPublisher : public rclcpp::Node
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
size_t count_;
size_t count_ = 0;
};

int main(int argc, char * argv[])
Expand Down

0 comments on commit 1d9eddf

Please sign in to comment.