Skip to content

Commit

Permalink
fix(autoware_node, test_node): 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 fea1486 commit a2a1508
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ class AutowareNode : public rclcpp_lifecycle::LifecycleNode
/*!
The sequential number of the Heartbeat message.
*/
uint16_t sequence_number;
uint16_t sequence_number_;
};

} // namespace autoware_node
Expand Down
16 changes: 8 additions & 8 deletions common/autoware_node/src/autoware_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

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

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

namespace autoware_node
Expand All @@ -47,15 +47,15 @@ AutowareNode::AutowareNode(
} else {
self_name = name;
}
sequence_number = 0;
sequence_number_ = 0;
registered = false;

// The granted lease is essentially infinite here, i.e., only reader/watchdog will notify
// violations. XXX causes segfault for cyclone dds, hence pass explicit lease life > heartbeat.
rclcpp::QoS qos_profile(1);
qos_profile.liveliness(RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC)
.liveliness_lease_duration(heartbeat_period + LEASE_DELTA)
.deadline(heartbeat_period + LEASE_DELTA);
.liveliness_lease_duration(heartbeat_period + lease_delta)
.deadline(heartbeat_period + lease_delta);

// assert liveliness on the 'heartbeat' topic
heartbeat_pub_ = this->create_publisher<autoware_control_center_msgs::msg::Heartbeat>(
Expand Down Expand Up @@ -115,7 +115,7 @@ void AutowareNode::heartbeat_callback()
{
auto message = autoware_control_center_msgs::msg::Heartbeat();
message.stamp = this->get_clock()->now();
message.sequence_number = sequence_number++;
message.sequence_number = sequence_number_++;
RCLCPP_INFO(this->get_logger(), "Publishing heartbeat, sent at [%i]", message.stamp.sec);
heartbeat_pub_->publish(message);
}
Expand Down Expand Up @@ -158,7 +158,7 @@ void AutowareNode::send_state(

req->name_node = self_name;
req->state = node_state;
req->message = message;
req->message = std::move(message);

cli_node_error_->async_send_request(
req, std::bind(&AutowareNode::node_error_future_callback, this, std::placeholders::_1));
Expand All @@ -167,7 +167,7 @@ void AutowareNode::send_state(

void AutowareNode::node_register_future_callback(AutowareNodeRegisterServiceResponseFuture future)
{
const auto response = future.get();
const auto & response = future.get();
std::string str_uuid = autoware_utils::to_hex_string(response->uuid_node);
RCLCPP_INFO(get_logger(), "response: %d, %s", response->status.status, str_uuid.c_str());

Expand All @@ -184,7 +184,7 @@ void AutowareNode::node_register_future_callback(AutowareNodeRegisterServiceResp

void AutowareNode::node_error_future_callback(AutowareNodeErrorServiceResponseFuture future)
{
auto response = future.get();
const auto & response = future.get();
std::string str_uuid = autoware_utils::to_hex_string(response->uuid_node);
RCLCPP_INFO(
get_logger(), "response: %d, %s, %s", response->status.status, str_uuid.c_str(),
Expand Down
5 changes: 2 additions & 3 deletions common/test_node/src/test_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,19 +21,18 @@
#include <memory>
#include <string>

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

/* This example creates a subclass of Node and uses std::bind() to register a
* member function as a callback from the timer. */

class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher() : Node("minimal_publisher"), count_(0)
MinimalPublisher() : Node("minimal_publisher"), count_{0}
{
rclcpp::QoS qos_profile(10);
declare_parameter<int>("hz", 10);
int hz = get_parameter("hz").as_int();
const auto hz = get_parameter("hz").as_int();
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 Down

0 comments on commit a2a1508

Please sign in to comment.