Skip to content

Commit 877bd6b

Browse files
authored
Merge pull request Liquid-ai#27 from berkeleyauv/keyboard_teleop
Fixing typo in keyboard teleop launch file and syntax errors in keyboard teleop node
2 parents 6a64390 + 6cb4a1a commit 877bd6b

File tree

2 files changed

+15
-13
lines changed

2 files changed

+15
-13
lines changed

uuv_control/uuv_control_cascaded_pids/launch/key_board_velocity.launch

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,10 @@
2424
</node>
2525
</group>
2626

27-
<include file="$(find-pkg_share uuv_teleop)/launch/uuv_keyboard_teleop.launch">
27+
<include file="$(find-pkg-share uuv_teleop)/launch/uuv_keyboard_teleop.launch">
2828
<arg name="uuv_name" value="$(var uuv_name)"/>
2929
<arg name="output_topic" value="cmd_vel"/>
3030
<arg name="message_type" value="twist"/>
3131
</include>
32+
3233
</launch>

uuv_teleop/scripts/vehicle_keyboard_teleop.py

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -37,16 +37,17 @@ def __init__(self, name, **kwargs):
3737
allow_undeclared_parameters=True,
3838
automatically_declare_parameters_from_overrides=True,
3939
**kwargs)
40-
40+
4141
# Class Variables
4242
self.settings = termios.tcgetattr(sys.stdin)
43+
self.name = name
4344

4445
# Speed setting
4546
self.speed = 1 # 1 = Slow, 2 = Fast
46-
self.l = Vector3(0, 0, 0) # Linear Velocity for Publish
47-
self.a = Vector3(0, 0, 0) # Angular Velocity for publishing
47+
self.l = Vector3(x=0., y=0., z=0.) # Linear Velocity for Publish
48+
self.a = Vector3(x=0., y=0., z=0.) # Angular Velocity for publishing
4849
self.linear_increment = 0.05 # How much to increment linear velocities by, to avoid jerkyness
49-
self.linear_limit = 1 # Linear velocity limit = self.linear_limit * self.speed
50+
self.linear_limit = 1. # Linear velocity limit = self.linear_limit * self.speed
5051
self.angular_increment = 0.05
5152
self.angular_limit = 0.5
5253
# User Interface
@@ -119,9 +120,9 @@ def _parse_keyboard(self):
119120

120121
# Set Vehicle Speed #
121122
if key_press == "1":
122-
self.speed = 1
123+
self.speed = 1.
123124
if key_press == "2":
124-
self.speed = 2
125+
self.speed = 2.
125126

126127
# Choose ros message accordingly
127128
if self._msg_type == 'twist':
@@ -173,8 +174,8 @@ def _parse_keyboard(self):
173174

174175
else:
175176
# If no button is pressed reset velocities to 0
176-
self.l = Vector3(x=0, y=0, z=0)
177-
self.a = Vector3(x=0, y=0, z=0)
177+
self.l = Vector3(x=0., y=0., z=0.)
178+
self.a = Vector3(x=0., y=0., z=0.)
178179

179180
# Store velocity message into Twist format
180181
cmd.angular = self.a
@@ -183,11 +184,11 @@ def _parse_keyboard(self):
183184
# If ctrl+c kill node
184185
if (key_press == '\x03'):
185186
self.get_logger().info('Keyboard Interrupt Pressed')
186-
self.get_logger().info('Shutting down [%s] node' % name)
187+
self.get_logger().info('Shutting down [%s] node' % self.name)
187188

188189
# Set twists to 0
189-
cmd.angular = Vector3(x=0, y=0, z=0)
190-
cmd.linear = Vector3(x=0, y=0, z=0)
190+
cmd.angular = Vector3(x=0., y=0., z=0.)
191+
cmd.linear = Vector3(x=0., y=0., z=0.)
191192
self._output_pub.publish(cmd)
192193

193194
exit(-1)
@@ -207,7 +208,7 @@ def main(args=None):
207208
teleop = KeyBoardVehicleTeleop(name, parameter_overrides=[sim_time_param])
208209
teleop.get_logger().info('Starting [%s] node' % name)
209210

210-
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
211+
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, teleop.settings)
211212

212213
rclpy.spin(teleop)
213214
teleop.get_logger().info('Shutting down [%s] node' % name)

0 commit comments

Comments
 (0)