Skip to content

Commit 087eaf1

Browse files
clalancettebmagyar
authored andcommitted
Fix some warnings from tests.
In here are some flake8 fixes and fixes to the joy_teleop tests now that some of the error messages have changed. Signed-off-by: Chris Lalancette <[email protected]>
1 parent e83a52f commit 087eaf1

File tree

3 files changed

+7
-6
lines changed

3 files changed

+7
-6
lines changed

joy_teleop/joy_teleop/joy_teleop.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -155,8 +155,8 @@ def __init__(self, name: str, config: typing.Dict[str, typing.Any], node: Node)
155155
# Now check that the mappings have all of the required configuration.
156156
for mapping, values in self.axis_mappings.items():
157157
if 'axis' not in values and 'button' not in values and 'value' not in values:
158-
raise JoyTeleopException("Axis mapping for '{}' must have an axis, button, or value"
159-
.format(name))
158+
raise JoyTeleopException("Axis mapping for '{}' must have an axis, button, "
159+
'or value'.format(name))
160160

161161
if 'axis' in values:
162162
if 'offset' not in values:

joy_teleop/test/test_parameter_failures.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -150,7 +150,7 @@ def test_teleop_axis_mappings_missing_axis_or_button(self):
150150
self.assertTrue(joy_teleop_process.wait_for_shutdown(timeout=10))
151151

152152
self.assertEqual(joy_teleop_process.exit_code, 1)
153-
self.assertTrue('must have an axis or button' in joy_teleop_process.output)
153+
self.assertTrue('must have an axis, button, or value' in joy_teleop_process.output)
154154

155155
def test_teleop_axis_mappings_missing_offset(self):
156156
parameters = {}

key_teleop/key_teleop/key_teleop.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -45,12 +45,12 @@
4545
import signal
4646
import time
4747

48-
from std_msgs.msg import Header
4948
from geometry_msgs.msg import Twist, TwistStamped
5049
import rclpy
5150
from rclpy.duration import Duration
5251
from rclpy.node import Node
5352
from rclpy.qos import qos_profile_system_default
53+
from std_msgs.msg import Header
5454

5555

5656
class Velocity(object):
@@ -130,7 +130,8 @@ def __init__(self, interface):
130130
self._publish_stamped_twist = self.declare_parameter('twist_stamped_enabled', False).value
131131

132132
if self._publish_stamped_twist:
133-
self._pub_cmd = self.create_publisher(TwistStamped, 'key_vel', qos_profile_system_default)
133+
self._pub_cmd = self.create_publisher(TwistStamped, 'key_vel',
134+
qos_profile_system_default)
134135
else:
135136
self._pub_cmd = self.create_publisher(Twist, 'key_vel', qos_profile_system_default)
136137

@@ -173,7 +174,7 @@ def _make_twist_stamped(self, linear, angular):
173174
twist_stamped = TwistStamped()
174175
header = Header()
175176
header.stamp = rclpy.clock.Clock().now().to_msg()
176-
header.frame_id = "key_teleop"
177+
header.frame_id = 'key_teleop'
177178

178179
twist_stamped.header = header
179180
twist_stamped.twist.linear.x = linear

0 commit comments

Comments
 (0)