Skip to content

Commit

Permalink
Merge pull request #27 from berkeleyauv/keyboard_teleop
Browse files Browse the repository at this point in the history
Fixing typo in keyboard teleop launch file and syntax errors in keyboard teleop node
  • Loading branch information
jpliquid authored Jan 22, 2021
2 parents 6a64390 + 6cb4a1a commit 877bd6b
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,10 @@
</node>
</group>

<include file="$(find-pkg_share uuv_teleop)/launch/uuv_keyboard_teleop.launch">
<include file="$(find-pkg-share uuv_teleop)/launch/uuv_keyboard_teleop.launch">
<arg name="uuv_name" value="$(var uuv_name)"/>
<arg name="output_topic" value="cmd_vel"/>
<arg name="message_type" value="twist"/>
</include>

</launch>
25 changes: 13 additions & 12 deletions uuv_teleop/scripts/vehicle_keyboard_teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,16 +37,17 @@ def __init__(self, name, **kwargs):
allow_undeclared_parameters=True,
automatically_declare_parameters_from_overrides=True,
**kwargs)

# Class Variables
self.settings = termios.tcgetattr(sys.stdin)
self.name = name

# Speed setting
self.speed = 1 # 1 = Slow, 2 = Fast
self.l = Vector3(0, 0, 0) # Linear Velocity for Publish
self.a = Vector3(0, 0, 0) # Angular Velocity for publishing
self.l = Vector3(x=0., y=0., z=0.) # Linear Velocity for Publish
self.a = Vector3(x=0., y=0., z=0.) # Angular Velocity for publishing
self.linear_increment = 0.05 # How much to increment linear velocities by, to avoid jerkyness
self.linear_limit = 1 # Linear velocity limit = self.linear_limit * self.speed
self.linear_limit = 1. # Linear velocity limit = self.linear_limit * self.speed
self.angular_increment = 0.05
self.angular_limit = 0.5
# User Interface
Expand Down Expand Up @@ -119,9 +120,9 @@ def _parse_keyboard(self):

# Set Vehicle Speed #
if key_press == "1":
self.speed = 1
self.speed = 1.
if key_press == "2":
self.speed = 2
self.speed = 2.

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

else:
# If no button is pressed reset velocities to 0
self.l = Vector3(x=0, y=0, z=0)
self.a = Vector3(x=0, y=0, z=0)
self.l = Vector3(x=0., y=0., z=0.)
self.a = Vector3(x=0., y=0., z=0.)

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

# Set twists to 0
cmd.angular = Vector3(x=0, y=0, z=0)
cmd.linear = Vector3(x=0, y=0, z=0)
cmd.angular = Vector3(x=0., y=0., z=0.)
cmd.linear = Vector3(x=0., y=0., z=0.)
self._output_pub.publish(cmd)

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

termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, teleop.settings)

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

0 comments on commit 877bd6b

Please sign in to comment.