Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use logging #190

Merged
merged 8 commits into from
Dec 5, 2017
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions rclcpp/minimal_client/main.cpp
Original file line number Diff line number Diff line change
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()) {
printf("client interrupted while waiting for service to appear.\n");
RCLCPP_ERROR(node->get_logger(), "client interrupted while waiting for service to appear.")
return 1;
}
printf("waiting for service to appear...\n");
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)
{
printf("service call failed :(\n");
RCLCPP_ERROR(node->get_logger(), "service call failed :(")
return 1;
}
auto result = result_future.get();
printf("result of %" PRId64 " + %" PRId64 " = %" PRId64 "\n",
request->a, request->b, result->sum);
RCLCPP_INFO(node->get_logger(), "result of %" PRId64 " + %" PRId64 " = %" PRId64,
request->a, request->b, result->sum)
rclcpp::shutdown();
return 0;
}
2 changes: 1 addition & 1 deletion rclcpp/minimal_composition/src/publisher_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ void PublisherNode::on_timer()
{
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
printf("Publisher: [%s]\n", message.data.c_str());
RCLCPP_INFO(this->get_logger(), "Publisher: '%s'", message.data.c_str())
publisher_->publish(message);
}

Expand Down
4 changes: 2 additions & 2 deletions rclcpp/minimal_composition/src/subscriber_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ SubscriberNode::SubscriberNode()
{
subscription_ = create_subscription<std_msgs::msg::String>(
"topic",
[](std_msgs::msg::String::UniquePtr msg) {
printf("Subscriber: [%s]\n", msg->data.c_str());
[this](std_msgs::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "Subscriber: '%s'", msg->data.c_str())
});
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/minimal_publisher/lambda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class MinimalPublisher : public rclcpp::Node
[this]() -> void {
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(this->count_++);
printf("Publishing: [%s]\n", 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
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class MinimalPublisher : public rclcpp::Node
{
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
printf("Publishing: [%s]\n", 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
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ int main(int argc, char * argv[])

while (rclcpp::ok()) {
message->data = "Hello, world! " + std::to_string(publish_count++);
printf("Publishing: [%s]\n", 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
11 changes: 7 additions & 4 deletions rclcpp/minimal_service/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,23 +18,26 @@
#include "rclcpp/rclcpp.hpp"

using AddTwoInts = example_interfaces::srv::AddTwoInts;
rclcpp::Node::SharedPtr g_node = nullptr;

void handle_service(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<AddTwoInts::Request> request,
const std::shared_ptr<AddTwoInts::Response> response)
{
(void)request_header;
printf("request: %" PRId64 " + %" PRId64 "\n", request->a, request->b);
RCLCPP_INFO(
g_node->get_logger(),
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Segfaults since the global variable is never set.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually this example works fine. I think you're referring to the not composable subscriber. See #195 for a fix

"request: %" PRId64 " + %" PRId64, request->a, request->b)
response->sum = request->a + request->b;
}

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("minimal_service");
auto server = node->create_service<AddTwoInts>("add_two_ints", handle_service);
rclcpp::spin(node);
g_node = rclcpp::Node::make_shared("minimal_service");
auto server = g_node->create_service<AddTwoInts>("add_two_ints", handle_service);
rclcpp::spin(g_node);
rclcpp::shutdown();
return 0;
}
4 changes: 2 additions & 2 deletions rclcpp/minimal_subscriber/lambda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ class MinimalSubscriber : public rclcpp::Node
{
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic",
[](std_msgs::msg::String::UniquePtr msg) {
printf("I heard: [%s]\n", msg->data.c_str());
[this](std_msgs::msg::String::UniquePtr msg) {
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
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class MinimalSubscriber : public rclcpp::Node
private:
void topic_callback(const std_msgs::msg::String::SharedPtr msg)
{
printf("I heard: [%s]\n", 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
10 changes: 6 additions & 4 deletions rclcpp/minimal_subscriber/not_composable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,23 +15,25 @@
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

rclcpp::Node::SharedPtr g_node = nullptr;

/* We do not recommend this style anymore, because composition of multiple
* nodes in the same executable is not possible. Please see one of the subclass
* examples for the "new" recommended styles. This example is only included
* for completeness because it is similar to "classic" standalone ROS nodes. */

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

int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = rclcpp::node::Node::make_shared("minimal_subscriber");
auto subscription = node->create_subscription<std_msgs::msg::String>
auto g_node = rclcpp::node::Node::make_shared("minimal_subscriber");
auto subscription = g_node->create_subscription<std_msgs::msg::String>
("topic", topic_callback);
rclcpp::spin(node);
rclcpp::spin(g_node);
rclcpp::shutdown();
return 0;
}
2 changes: 1 addition & 1 deletion rclcpp/minimal_timer/lambda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class MinimalTimer : public rclcpp::Node
MinimalTimer()
: Node("minimal_timer")
{
auto timer_callback = []() -> void { printf("Hello, world!\n"); };
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
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class MinimalTimer : public rclcpp::Node
private:
void timer_callback()
{
printf("Hello, world!\n");
RCLCPP_INFO(this->get_logger(), "Hello, world!")
}
rclcpp::TimerBase::SharedPtr timer_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ def timer_callback(self):
msg = String()
msg.data = 'Hello World: {0}'.format(self.i)
self.i += 1
print('Publishing: "{0}"'.format(msg.data))
self.get_logger().info('Publishing: "{0}"'.format(msg.data))
self.pub.publish(msg)


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ def timer_callback(self):
msg = String()
msg.data = 'Hello World: {0}'.format(self.i)
self.i += 1
print('Publishing: "{0}"'.format(msg.data))
self.get_logger().info('Publishing: "{0}"'.format(msg.data))
self.pub.publish(msg)


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def __init__(self):
self.sub = self.create_subscription(String, 'estop', self.estop_callback)

def estop_callback(self, msg):
print('I heard: [%s]' % msg.data)
self.get_logger().info('I heard: "%s"' % msg.data)


class PriorityExecutor(Executor):
Expand Down
2 changes: 1 addition & 1 deletion rclpy/executors/examples_rclpy_executors/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ def __init__(self):
self.sub = self.create_subscription(String, 'chatter', self.chatter_callback)

def chatter_callback(self, msg):
print('I heard: [%s]' % msg.data)
self.get_logger().info('I heard: "%s"' % msg.data)


def main(args=None):
Expand Down
2 changes: 1 addition & 1 deletion rclpy/executors/examples_rclpy_executors/talker.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ def timer_callback(self):
msg = String()
msg.data = 'Hello World: {0}'.format(self.i)
self.i += 1
print('Publishing: "{0}"'.format(msg.data))
self.get_logger().info('Publishing: "{0}"'.format(msg.data))
self.pub.publish(msg)


Expand Down
4 changes: 2 additions & 2 deletions rclpy/services/minimal_client/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ def main(args=None):
req.a = 41
req.b = 1
while not cli.wait_for_service(timeout_sec=1.0):
print('service not available, waiting again...')
node.get_logger().info('service not available, waiting again...')

cli.call(req)
# when calling wait for future
Expand All @@ -35,7 +35,7 @@ def main(args=None):
# TODO(mikaelarguedas) This is not the final API, and this does not scale
# for multiple pending requests. This will change once an executor model is implemented
# In the future the response will not be stored in cli.response
print(
node.get_logger().info(
'Result of add_two_ints: for %d + %d = %d' %
(req.a, req.b, cli.response.sum))

Expand Down
4 changes: 2 additions & 2 deletions rclpy/services/minimal_client/client_async.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,15 +28,15 @@ def main(args=None):
req.a = 41
req.b = 1
while not cli.wait_for_service(timeout_sec=1.0):
print('service not available, waiting again...')
node.get_logger().info('service not available, waiting again...')

cli.call(req)
while rclpy.ok():
# TODO(mikaelarguedas) This is not the final API, and this does not scale
# for multiple pending requests. This will change once an executor model is implemented
# In the future the response will not be stored in cli.response
if cli.response is not None:
print(
node.get_logger().info(
'Result of add_two_ints: for %d + %d = %d' %
(req.a, req.b, cli.response.sum))
break
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ def __init__(self):
super().__init__('minimal_client_async')
self.cli = self.create_client(AddTwoInts, 'add_two_ints')
while not self.cli.wait_for_service(timeout_sec=1.0):
print('service not available, waiting again...')
self.get_logger().info('service not available, waiting again...')
self.req = AddTwoInts.Request()

def send_request(self):
Expand All @@ -44,7 +44,7 @@ def main(args=None):
# for multiple pending requests. This will change once an executor model is implemented
# In the future the response will not be stored in cli.response
if minimal_client.cli.response is not None:
print(
minimal_client.get_logger().info(
'Result of add_two_ints: for %d + %d = %d' %
(minimal_client.req.a, minimal_client.req.b, minimal_client.cli.response.sum))
break
Expand Down
15 changes: 10 additions & 5 deletions rclpy/services/minimal_service/service.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,27 +16,32 @@

import rclpy

g_node = None


def add_two_ints_callback(request, response):
global g_node
response.sum = request.a + request.b
print('Incoming request\na: %d b: %d' % (request.a, request.b))
g_node.get_logger().info(
'Incoming request\na: %d b: %d' % (request.a, request.b))

return response


def main(args=None):
global g_node
rclpy.init(args=args)

node = rclpy.create_node('minimal_service')
g_node = rclpy.create_node('minimal_service')

srv = node.create_service(AddTwoInts, 'add_two_ints', add_two_ints_callback)
srv = g_node.create_service(AddTwoInts, 'add_two_ints', add_two_ints_callback)
while rclpy.ok():
rclpy.spin_once(node)
rclpy.spin_once(g_node)

# Destroy the service attached to the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
node.destroy_service(srv)
g_node.destroy_service(srv)
rclpy.shutdown()


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ def __init__(self):

def add_two_ints_callback(self, request, response):
response.sum = request.a + request.b
print('Incoming request\na: %d b: %d' % (request.a, request.b))
self.get_logger().info('Incoming request\na: %d b: %d' % (request.a, request.b))

return response

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def timer_callback():
nonlocal i
msg.data = 'Hello World: %d' % i
i += 1
print('Publishing: "%s"' % msg.data)
node.get_logger().info('Publishing: "%s"' % msg.data)
publisher.publish(msg)

timer_period = 0.5 # seconds
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ def timer_callback(self):
msg = String()
msg.data = 'Hello World: %d' % self.i
self.publisher_.publish(msg)
print('Publishing: "%s"' % msg.data)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.i += 1


Expand Down
2 changes: 1 addition & 1 deletion rclpy/topics/minimal_publisher/publisher_old_school.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ def main(args=None):
while rclpy.ok():
msg.data = 'Hello World: %d' % i
i += 1
print('Publishing: "%s"' % msg.data)
node.get_logger().info('Publishing: "%s"' % msg.data)
publisher.publish(msg)
sleep(0.5) # seconds

Expand Down
2 changes: 1 addition & 1 deletion rclpy/topics/minimal_subscriber/subscriber_lambda.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ def main(args=None):
node = rclpy.create_node('minimal_subscriber')

subscription = node.create_subscription(
String, 'topic', lambda msg: print('I heard: [%s]' % msg.data))
String, 'topic', lambda msg: node.get_logger().info('I heard: "%s"' % msg.data))
subscription # prevent unused variable warning

rclpy.spin(node)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ def __init__(self):
self.subscription # prevent unused variable warning

def listener_callback(self, msg):
print('I heard: [%s]' % msg.data)
self.get_logger().info('I heard: "%s"' % msg.data)


def main(args=None):
Expand Down
Loading