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

Replace print() in python demos with logger calls #190

Merged
merged 7 commits into from
Nov 22, 2017
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ def main(args=None):
req.b = 3
cli.call(req)
cli.wait_for_future()
print('Result of add_two_ints: %d' % cli.response.sum)
node.get_logger().info('Result of add_two_ints: %d' % cli.response.sum)

node.destroy_node()
rclpy.shutdown()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ def main(args=None):
while rclpy.ok():
rclpy.spin_once(node)
if cli.response is not None:
print('Result of add_two_ints: %d' % cli.response.sum)
node.get_logger().info('Result of add_two_ints: %d' % cli.response.sum)
break

node.destroy_node()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,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
2 changes: 1 addition & 1 deletion demo_nodes_py/demo_nodes_py/topics/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,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
9 changes: 6 additions & 3 deletions demo_nodes_py/demo_nodes_py/topics/listener_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

import rclpy
from rclpy.qos import qos_profile_default, qos_profile_sensor_data
from rclpy.qos import QoSReliabilityPolicy

from std_msgs.msg import String

Expand All @@ -25,11 +26,15 @@ class ListenerQos(rclpy.Node):

def __init__(self, qos_profile):
super().__init__('listener_qos')
if qos_profile.reliability is QoSReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_RELIABLE:
self.get_logger().info('Reliable listener')
Copy link
Member

Choose a reason for hiding this comment

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

It's not obvious to me that this is actually performing a logging action compared to the API suggested originally in ros2/rclpy#103, maybe just calling the function loginfo or a log function taking a severity keyword would be clearer.
I know the recent discussion was focused on the c++ API but how do we expect the API to look like for the users in python?

Copy link
Member Author

Choose a reason for hiding this comment

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

the .log(,INFO) option is also available on this logger, following ros2/rclpy#103 (comment) (which came from a team discussion), .info() is offered for convenience. Both options mirror what is offered by python logging, we seem to prefer the .info(): https://github.com/ros2/ros2cli/blob/9fce6a08381bb67cf17e7160b0b2c6556ffec1e6/ros2cli/ros2cli/entry_points.py#L87

Copy link
Member

Choose a reason for hiding this comment

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

Ok so the goal is to use an API as close as python native logging as possible rather than something closer to ROS 1. We do provide both but will use this one in our examples. Fair enough.
With ros2/rclpy#148 (comment) it now make sense why we don't something like self.mylogger.loginfo()

Copy link
Member Author

Choose a reason for hiding this comment

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

Following up on this, if I understand correctly your initial concern was referring to how we would use the generic logging functions (e.g. rclpy.logging.loginfo()) as opposed to log calls being made on specific logger objects (which weren't around in ROS 1).

On the use of mylogger.info() as opposed to mylogger.log(, severity=INFO), as you noted I've chosen to mirror the typical usage of native python logging. https://docs.python.org/3/howto/logging-cookbook.html, for example, uses mylogger.info() in all cases except where the severity is chosen programatically, for which case the mylogger.log(, severity=INFO) form is available

else:
self.get_logger().info('Best effort listener')
self.sub = self.create_subscription(
String, 'chatter', self.chatter_callback, qos_profile=qos_profile)

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


def main(argv=sys.argv[1:]):
Expand All @@ -46,10 +51,8 @@ def main(argv=sys.argv[1:]):

if args.reliable:
custom_qos_profile = qos_profile_default
print('Reliable listener')
else:
custom_qos_profile = qos_profile_sensor_data
print('Best effort listener')

node = ListenerQos(custom_qos_profile)

Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_py/demo_nodes_py/topics/talker.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,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
10 changes: 7 additions & 3 deletions demo_nodes_py/demo_nodes_py/topics/talker_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

import rclpy
from rclpy.qos import qos_profile_default, qos_profile_sensor_data
from rclpy.qos import QoSReliabilityPolicy

from std_msgs.msg import String

Expand All @@ -26,15 +27,20 @@ class TalkerQos(rclpy.Node):
def __init__(self, qos_profile):
super().__init__('talker_qos')
self.i = 0
if qos_profile.reliability is QoSReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_RELIABLE:
self.get_logger().info('Reliable talker')
else:
self.get_logger().info('Best effort talker')
self.pub = self.create_publisher(String, 'chatter', qos_profile=qos_profile)

timer_period = 1.0
self.tmr = self.create_timer(timer_period, self.timer_callback)

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 All @@ -52,10 +58,8 @@ def main(argv=sys.argv[1:]):

if args.reliable:
custom_qos_profile = qos_profile_default
print('Reliable publisher')
else:
custom_qos_profile = qos_profile_sensor_data
print('Best effort publisher')

node = TalkerQos(custom_qos_profile)

Expand Down
40 changes: 22 additions & 18 deletions lifecycle/src/lifecycle_service_client_py.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,11 @@ def change_state(lifecycle_node, change_state_args=''):
cli.call(req)
cli.wait_for_future()
if cli.response.success:
print('%s successfully triggered transition %s' % (lifecycle_node, change_state_args))
node.get_logger().info(
'%s successfully triggered transition %s' % (lifecycle_node, change_state_args))
else:
print('%s failed to triggered transition %s' % (lifecycle_node, change_state_args))
node.get_logger().info(
'%s failed to triggered transition %s' % (lifecycle_node, change_state_args))


def get_state(lifecycle_node):
Expand All @@ -51,8 +53,9 @@ def get_state(lifecycle_node):
req = GetState.Request()
cli.call(req)
cli.wait_for_future()
print('%s is in state %s(%u)'
% (lifecycle_node, cli.response.current_state.label, cli.response.current_state.id))
node.get_logger().info(
'%s is in state %s(%u)'
% (lifecycle_node, cli.response.current_state.label, cli.response.current_state.id))


def get_available_states(lifecycle_node):
Expand All @@ -62,9 +65,10 @@ def get_available_states(lifecycle_node):
req = GetAvailableStates.Request()
cli.call(req)
cli.wait_for_future()
print('%s has %u available states' % (lifecycle_node, len(cli.response.available_states)))
node.get_logger().info(
'%s has %u available states' % (lifecycle_node, len(cli.response.available_states)))
for state in cli.response.available_states:
print('id: %u\tlabel: %s' % (state.id, state.label))
node.get_logger().info('id: %u\tlabel: %s' % (state.id, state.label))


def get_available_transitions(lifecycle_node):
Expand All @@ -75,24 +79,24 @@ def get_available_transitions(lifecycle_node):
req = GetAvailableTransitions.Request()
cli.call(req)
cli.wait_for_future()
print('%s has %u available transitions'
% (lifecycle_node, len(cli.response.available_transitions)))
node.get_logger().info(
'%s has %u available transitions'
% (lifecycle_node, len(cli.response.available_transitions)))
for transition in cli.response.available_transitions:
print('Transition id: %u\tlabel: %s'
% (transition.transition.id, transition.transition.label))
print('\tStart id: %u\tlabel: %s'
% (transition.start_state.id, transition.start_state.label))
print('\tGoal id: %u\tlabel: %s'
% (transition.goal_state.id, transition.goal_state.label))
node.get_logger().info(
'Transition id: %u\tlabel: %s'
% (transition.transition.id, transition.transition.label))
node.get_logger().info(
'\tStart id: %u\tlabel: %s'
% (transition.start_state.id, transition.start_state.label))
node.get_logger().info(
'\tGoal id: %u\tlabel: %s'
% (transition.goal_state.id, transition.goal_state.label))


def main(service_type, lifecycle_node, change_state_args='', args=None):
rclpy.init(args=args)

if not rclpy.ok():
Copy link
Member

Choose a reason for hiding this comment

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

This is not necessary anymore because init would raise on failure ?

Copy link
Member Author

Choose a reason for hiding this comment

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

yep, thanks for making it explicit 😄

print('Something is wrong with rclpy init')
return

if service_type == 'change_state':
change_state(lifecycle_node, change_state_args)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os
import sys

from launch import LaunchDescriptor
Expand All @@ -25,6 +26,10 @@ def main():
package = 'topic_monitor'
executable = get_executable_path(package_name=package, executable_name='data_publisher')

# Strip the logger name from the message format in favor of the shorter executable name
os.environ['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '[{severity}] {message}'
Copy link
Member

Choose a reason for hiding this comment

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

Does this modified environment need to be passed to the launched processes ? (maybe it's not necessary as the same environment is used for the launchfile and each launched process). Otherwise there's an example of custom environment passed to launched processes here:
https://github.com/ros2/system_tests/blob/a4e81e348f7d2b25076f2b11dfde0f073e3850de/test_communication/test/test_publisher_subscriber.py.in#L28-L32

Copy link
Member Author

Choose a reason for hiding this comment

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

yeah any children processes will inherit this environment automatically

Copy link
Member

Choose a reason for hiding this comment

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

👍

os.environ['PYTHONUNBUFFERED'] = '1' # force unbuffered output to get prints to sync correctly

launch_descriptor.add_process(
cmd=[executable, 'sensor', '--best-effort'],
name='sensor',
Expand Down
40 changes: 19 additions & 21 deletions topic_monitor/topic_monitor/scripts/data_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
# limitations under the License.

import argparse
import sys
from time import sleep

import rclpy
Expand All @@ -22,7 +21,6 @@

from std_msgs.msg import Header


default_depth = 10


Expand Down Expand Up @@ -58,53 +56,53 @@ def main():

args = parser.parse_args()

reliability_suffix = '_best_effort' if args.best_effort else ''
topic_name = '{0}_data{1}'.format(args.data_name, reliability_suffix)

rclpy.init()
node = rclpy.create_node('%s_pub' % topic_name)
node_logger = node.get_logger()

qos_profile = QoSProfile()

if args.best_effort:
print('Reliability: best effort')
node_logger.info('Reliability: best effort')
qos_profile.reliability = QoSReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
else:
print('Reliability: reliable')
node_logger.info('Reliability: reliable')
qos_profile.reliability = QoSReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_RELIABLE

if args.keep_all:
print('History: keep all')
node_logger.info('History: keep all')
qos_profile.history = QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_ALL
else:
print('History: keep last')
node_logger.info('History: keep last')
qos_profile.history = QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST

print('Depth: {0}'.format(args.depth))
node_logger.info('Depth: {0}'.format(args.depth))
qos_profile.depth = args.depth

if args.transient_local:
print('Durability: transient local')
node_logger.info('Durability: transient local')
qos_profile.durability = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
else:
print('Durability: volatile')
node_logger.info('Durability: volatile')
qos_profile.durability = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_VOLATILE

print('Payload size: {0}'.format(args.payload_size))
data = 'a' * args.payload_size

reliability_suffix = '_best_effort' if args.best_effort else ''
topic_name = '{0}_data{1}'.format(args.data_name, reliability_suffix)
print('Publishing on topic: {0}'.format(topic_name))
sys.stdout.flush()

rclpy.init()
node = rclpy.create_node('%s_pub' % topic_name)
data_pub = node.create_publisher(
Header, topic_name, qos_profile=qos_profile)
node_logger.info('Publishing on topic: {0}'.format(topic_name))

node_logger.info('Payload size: {0}'.format(args.payload_size))
data = 'a' * args.payload_size

msg = Header()
cycle_count = 0

def publish_msg(val):
msg.frame_id = '{0}_{1}'.format(val, data)
data_pub.publish(msg)
print('Publishing: "{0}"'.format(val))
sys.stdout.flush() # this is to get the output to show immediately when using Launch
node_logger.info('Publishing: "{0}"'.format(val))

while rclpy.ok():
if args.end_after is not None and cycle_count >= args.end_after:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ def main():
def publish_msg(val):
msg.frame_id = str(val)
data_pub.publish(msg)
print('Publishing: "{0}"'.format(val))
rospy.loginfo('Publishing: "{0}"'.format(val))
sys.stdout.flush() # this is to get the output to show immediately when using Launch

while not rospy.is_shutdown():
Expand Down
Loading