Skip to content

Commit

Permalink
Add semicolons to all RCLCPP and RCUTILS macros. (#214)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Oct 5, 2018
1 parent f6027ed commit 3b60ee1
Show file tree
Hide file tree
Showing 12 changed files with 15 additions and 15 deletions.
8 changes: 4 additions & 4 deletions rclcpp/minimal_client/main.cpp
Expand Up @@ -27,10 +27,10 @@ int main(int argc, char * argv[])
auto client = node->create_client<AddTwoInts>("add_two_ints");
while (!client->wait_for_service(std::chrono::seconds(1))) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(node->get_logger(), "client interrupted while waiting for service to appear.")
RCLCPP_ERROR(node->get_logger(), "client interrupted while waiting for service to appear.");
return 1;
}
RCLCPP_INFO(node->get_logger(), "waiting for service to appear...")
RCLCPP_INFO(node->get_logger(), "waiting for service to appear...");
}
auto request = std::make_shared<AddTwoInts::Request>();
request->a = 41;
Expand All @@ -39,12 +39,12 @@ int main(int argc, char * argv[])
if (rclcpp::spin_until_future_complete(node, result_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "service call failed :(")
RCLCPP_ERROR(node->get_logger(), "service call failed :(");
return 1;
}
auto result = result_future.get();
RCLCPP_INFO(node->get_logger(), "result of %" PRId64 " + %" PRId64 " = %" PRId64,
request->a, request->b, result->sum)
request->a, request->b, result->sum);
rclcpp::shutdown();
return 0;
}
2 changes: 1 addition & 1 deletion rclcpp/minimal_composition/src/publisher_node.cpp
Expand Up @@ -32,7 +32,7 @@ void PublisherNode::on_timer()
{
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publisher: '%s'", message.data.c_str())
RCLCPP_INFO(this->get_logger(), "Publisher: '%s'", message.data.c_str());
publisher_->publish(message);
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_composition/src/subscriber_node.cpp
Expand Up @@ -22,7 +22,7 @@ SubscriberNode::SubscriberNode()
subscription_ = create_subscription<std_msgs::msg::String>(
"topic",
[this](std_msgs::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "Subscriber: '%s'", msg->data.c_str())
RCLCPP_INFO(this->get_logger(), "Subscriber: '%s'", msg->data.c_str());
});
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_publisher/lambda.cpp
Expand Up @@ -33,7 +33,7 @@ class MinimalPublisher : public rclcpp::Node
[this]() -> void {
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(this->count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str())
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
this->publisher_->publish(message);
};
timer_ = this->create_wall_timer(500ms, timer_callback);
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_publisher/member_function.cpp
Expand Up @@ -37,7 +37,7 @@ class MinimalPublisher : public rclcpp::Node
{
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str())
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_publisher/not_composable.cpp
Expand Up @@ -35,7 +35,7 @@ int main(int argc, char * argv[])

while (rclcpp::ok()) {
message->data = "Hello, world! " + std::to_string(publish_count++);
RCLCPP_INFO(node->get_logger(), "Publishing: '%s'", message->data.c_str())
RCLCPP_INFO(node->get_logger(), "Publishing: '%s'", message->data.c_str());
publisher->publish(message);
rclcpp::spin_some(node);
loop_rate.sleep();
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_service/main.cpp
Expand Up @@ -28,7 +28,7 @@ void handle_service(
(void)request_header;
RCLCPP_INFO(
g_node->get_logger(),
"request: %" PRId64 " + %" PRId64, request->a, request->b)
"request: %" PRId64 " + %" PRId64, request->a, request->b);
response->sum = request->a + request->b;
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_subscriber/lambda.cpp
Expand Up @@ -25,7 +25,7 @@ class MinimalSubscriber : public rclcpp::Node
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic",
[this](std_msgs::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str())
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
});
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_subscriber/member_function.cpp
Expand Up @@ -29,7 +29,7 @@ class MinimalSubscriber : public rclcpp::Node
private:
void topic_callback(const std_msgs::msg::String::SharedPtr msg)
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str())
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_subscriber/not_composable.cpp
Expand Up @@ -24,7 +24,7 @@ rclcpp::Node::SharedPtr g_node = nullptr;

void topic_callback(const std_msgs::msg::String::SharedPtr msg)
{
RCLCPP_INFO(g_node->get_logger(), "I heard: '%s'", msg->data.c_str())
RCLCPP_INFO(g_node->get_logger(), "I heard: '%s'", msg->data.c_str());
}

int main(int argc, char * argv[])
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_timer/lambda.cpp
Expand Up @@ -28,7 +28,7 @@ class MinimalTimer : public rclcpp::Node
MinimalTimer()
: Node("minimal_timer")
{
auto timer_callback = [this]() -> void { RCLCPP_INFO(this->get_logger(), "Hello, world!") };
auto timer_callback = [this]() -> void { RCLCPP_INFO(this->get_logger(), "Hello, world!"); };
timer_ = create_wall_timer(500ms, timer_callback);
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_timer/member_function.cpp
Expand Up @@ -33,7 +33,7 @@ class MinimalTimer : public rclcpp::Node
private:
void timer_callback()
{
RCLCPP_INFO(this->get_logger(), "Hello, world!")
RCLCPP_INFO(this->get_logger(), "Hello, world!");
}
rclcpp::TimerBase::SharedPtr timer_;
};
Expand Down

0 comments on commit 3b60ee1

Please sign in to comment.