Skip to content

Commit 19df922

Browse files
authored
Pass keyword arguments by name (#317)
Signed-off-by: Jacob Perron <[email protected]>
1 parent 3ff2adb commit 19df922

File tree

2 files changed

+8
-5
lines changed

2 files changed

+8
-5
lines changed

ros2action/ros2action/verb/send_goal.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ def _goal_status_to_string(status):
7373

7474

7575
def _feedback_callback(feedback):
76-
print('Feedback:\n {}'.format(message_to_yaml(feedback.feedback, None)))
76+
print('Feedback:\n {}'.format(message_to_yaml(feedback.feedback)))
7777

7878

7979
def send_goal(action_name, action_type, goal_values, feedback_callback):
@@ -116,7 +116,7 @@ def send_goal(action_name, action_type, goal_values, feedback_callback):
116116
print('Waiting for an action server to become available...')
117117
action_client.wait_for_server()
118118

119-
print('Sending goal:\n {}'.format(message_to_yaml(goal, None)))
119+
print('Sending goal:\n {}'.format(message_to_yaml(goal)))
120120
goal_future = action_client.send_goal_async(goal, feedback_callback)
121121
rclpy.spin_until_future_complete(node, goal_future)
122122

@@ -146,7 +146,7 @@ def send_goal(action_name, action_type, goal_values, feedback_callback):
146146
# no need to potentially cancel the goal anymore
147147
goal_handle = None
148148

149-
print('Result:\n {}'.format(message_to_yaml(result.result, None)))
149+
print('Result:\n {}'.format(message_to_yaml(result.result)))
150150
print('Goal finished with status: {}'.format(_goal_status_to_string(result.status)))
151151
finally:
152152
# Cancel the goal if it's still active

ros2topic/ros2topic/verb/echo.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -121,12 +121,15 @@ def subscriber(node, topic_name, message_type, callback):
121121
def subscriber_cb(truncate_length, noarr, nostr):
122122
def cb(msg):
123123
nonlocal truncate_length, noarr, nostr
124-
print(message_to_yaml(msg, truncate_length, noarr, nostr), end='---\n')
124+
print(
125+
message_to_yaml(
126+
msg, truncate_length=truncate_length, no_arr=noarr, no_str=nostr),
127+
end='---\n')
125128
return cb
126129

127130

128131
def subscriber_cb_csv(truncate_length, noarr, nostr):
129132
def cb(msg):
130133
nonlocal truncate_length, noarr, nostr
131-
print(message_to_csv(msg, truncate_length, noarr, nostr))
134+
print(message_to_csv(msg, truncate_length=truncate_length, no_arr=noarr, no_str=nostr))
132135
return cb

0 commit comments

Comments
 (0)