Skip to content

Commit

Permalink
fix tuple syntax error
Browse files Browse the repository at this point in the history
  • Loading branch information
CullenSUN committed Nov 6, 2023
1 parent d9645b1 commit 463e85a
Showing 1 changed file with 26 additions and 21 deletions.
47 changes: 26 additions & 21 deletions mini_pupper_dance/mini_pupper_dance/dance_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -62,50 +62,55 @@ def _dance_callback(self, request, response):
time.sleep(self.interval) # Make sure the robot moved

elif (request.data == 'look_up'):
pose_cmd.orientation.x,
pose_cmd.orientation.y,
pose_cmd.orientation.z,
pose_cmd.orientation.w = quaternion_from_euler(0.0, -0.3, 0.0)

x, y, z, w = quaternion_from_euler(0.0, -0.3, 0.0)
pose_cmd.orientation.x = x
pose_cmd.orientation.y = y
pose_cmd.orientation.z = z
pose_cmd.orientation.w = w

Check warning on line 70 in mini_pupper_dance/mini_pupper_dance/dance_server.py

View workflow job for this annotation

GitHub Actions / flake8

[flake8] reported by reviewdog 🐶 blank line contains whitespace Raw Output: ./mini_pupper_dance/mini_pupper_dance/dance_server.py:70:1: W293 blank line contains whitespace
self.pose_publisher_.publish(pose_cmd)
self.get_logger().info('Publishing: "%s"' % request.data)
time.sleep(self.interval) # Make sure the robot moved

elif (request.data == 'look_down'):
pose_cmd.orientation.x,
pose_cmd.orientation.y,
pose_cmd.orientation.z,
pose_cmd.orientation.w = quaternion_from_euler(0.0, 0.3, 0.0)
x, y, z, w = quaternion_from_euler(0.0, 0.3, 0.0)
pose_cmd.orientation.x = x
pose_cmd.orientation.y = y
pose_cmd.orientation.z = z
pose_cmd.orientation.w = w

self.pose_publisher_.publish(pose_cmd)
self.get_logger().info('Publishing: "%s"' % request.data)
time.sleep(self.interval) # Make sure the robot moved

elif (request.data == 'look_left'):
pose_cmd.orientation.x,
pose_cmd.orientation.y,
pose_cmd.orientation.z,
pose_cmd.orientation.w = quaternion_from_euler(0.0, 0.0, 0.3)
x, y, z, w = quaternion_from_euler(0.0, 0.0, 0.3)
pose_cmd.orientation.x = x
pose_cmd.orientation.y = y
pose_cmd.orientation.z = z
pose_cmd.orientation.w = w

self.pose_publisher_.publish(pose_cmd)
self.get_logger().info('Publishing: "%s"' % request.data)
time.sleep(self.interval) # Make sure the robot moved

elif (request.data == 'look_right'):
pose_cmd.orientation.x,
pose_cmd.orientation.y,
pose_cmd.orientation.z,
pose_cmd.orientation.w = quaternion_from_euler(0.0, 0.0, -0.3)
x, y, z, w = quaternion_from_euler(0.0, 0.0, -0.3)
pose_cmd.orientation.x = x
pose_cmd.orientation.y = y
pose_cmd.orientation.z = z
pose_cmd.orientation.w = w

self.pose_publisher_.publish(pose_cmd)
self.get_logger().info('Publishing: "%s"' % request.data)
time.sleep(self.interval) # Make sure the robot moved

elif (request.data == 'look_middle'):
pose_cmd.orientation.x,
pose_cmd.orientation.y,
pose_cmd.orientation.z,
pose_cmd.orientation.w = quaternion_from_euler(0.0, 0.0, 0.0)
x, y, z, w = quaternion_from_euler(0.0, 0.0, 0.0)
pose_cmd.orientation.x = x
pose_cmd.orientation.y = y
pose_cmd.orientation.z = z
pose_cmd.orientation.w = w

self.pose_publisher_.publish(pose_cmd)
self.get_logger().info('Publishing: "%s"' % request.data)
Expand Down

0 comments on commit 463e85a

Please sign in to comment.