3 from __future__ 
import print_function
 
    9 roslib.load_manifest(
'teleop_legged_robots')
 
   12 from geometry_msgs.msg 
import Twist
 
   13 from geometry_msgs.msg 
import Pose
 
   15 import sys, select, termios, tty
 
   20 Reading from the keyboard and Publishing to Twist and Pose! 
   21 --------------------------- 
   27 For Holonomic mode (strafing), hold down the shift key: 
   28 --------------------------- 
   34 --------------------------- 
   35 1/2 : move the body forward/back (+/-x) 
   36 3/4 : move the body right/left (+/-y) 
   38 5/6 : move the body up/down (+/-z) 
   46 q/z : increase/decrease max speeds by 10% 
   47 w/x : increase/decrease only linear speed by 10% 
   48 e/c : increase/decrease only angular speed by 10% 
   50 r/v : increase/decrease body's pose translation by 10% 
   51 t/b : increase/decrease body's pose angular speed by 10% 
   85     '1': (1, 0, 0, 0, 0, 0),
 
   86     '2': (-1, 0, 0, 0, 0, 0),
 
   87     '3': (0, 1, 0, 0, 0, 0),
 
   88     '4': (0, -1, 0, 0, 0, 0),
 
   89     '5': (0, 0, 1, 0, 0, 0),
 
   90     '6': (0, 0, -1, 0, 0, 0),
 
   91     'a': (0, 0, 0, 1, 0, 0),
 
   92     's': (0, 0, 0, -1, 0, 0),
 
   93     'd': (0, 0, 0, 0, 1, 0),
 
   94     'f': (0, 0, 0, 0, -1, 0),
 
   95     'g': (0, 0, 0, 0, 0, 1),
 
   96     'h': (0, 0, 0, 0, 0, -1),
 
  109         super(PublishThread, self).
__init__()
 
  110         robot_name = rospy.get_param(
"~/robot_name", 
"/")
 
  111         twist_publisher_name = rospy.get_param(
"~/twist_publisher_name", robot_name + 
"/cmd_vel")
 
  112         pose_publisher_name = rospy.get_param(
"~/pose_publisher_name", robot_name + 
"/body_pose")
 
  144         while not rospy.is_shutdown() 
and (self.
twist_publisher.get_num_connections() == 0 
or 
  148                     rospy.loginfo(
"Waiting for subscriber to connect to {}".format(self.
twist_publisher.name))
 
  150                     rospy.loginfo(
"Waiting for subscriber to connect to {}".format(self.
pose_publisher.name))
 
  154         if rospy.is_shutdown():
 
  155             raise Exception(
"Got shutdown request before subscribers connected")
 
  157     def update(self, x, y, z, th, speed, turn, pose_x, pose_y, pose_z, pose_roll, pose_pitch, pose_yaw, pose_speed,
 
  180         self.
update(0, 0, 0, 0, 0, 0, self.
pose_x, self.
pose_y, self.
pose_z, self.
pose_roll, self.
pose_pitch,
 
  193             twist.linear.x = self.
x * self.
speed 
  194             twist.linear.y = self.
y * self.
speed 
  195             twist.linear.z = self.
z * self.
speed 
  198             twist.angular.z = self.
th * self.
turn 
  201             pose.position.x = self.
pose_x 
  202             pose.position.y = self.
pose_y 
  203             pose.position.z = self.
pose_z 
  208             quaternion = tf_conversions.transformations.quaternion_from_euler(pose_roll_euler, pose_pitch_euler, pose_yaw_euler)
 
  209             pose.orientation.x = quaternion[0]
 
  210             pose.orientation.y = quaternion[1]
 
  211             pose.orientation.z = quaternion[2]
 
  212             pose.orientation.w = quaternion[3]
 
  227         pose.position.x = self.
pose_x 
  228         pose.position.y = self.
pose_y 
  229         pose.position.z = self.
pose_z 
  234         quaternion = tf_conversions.transformations.quaternion_from_euler(pose_roll_euler, pose_pitch_euler, pose_yaw_euler)
 
  235         pose.orientation.x = quaternion[0]
 
  236         pose.orientation.y = quaternion[1]
 
  237         pose.orientation.z = quaternion[2]
 
  238         pose.orientation.w = quaternion[3]
 
  244     tty.setraw(sys.stdin.fileno())
 
  245     rlist, _, _ = select.select([sys.stdin], [], [], key_timeout)
 
  247         key = sys.stdin.read(1)
 
  250     termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
 
  255     return "currently:\tspeed %s\tturn %s " % (speed, turn)
 
  259     return "currently:\tpose_speed %s\tpose_turn %s " % (pose_speed, pose_turn)
 
  262 def pose_print(pose_x, pose_y, pose_z, pose_roll, pose_pitch, pose_yaw):
 
  263     return "currently:\tx %s\ty %s\tz %s\troll %s\tpitch %s\tyaw %s " % (
 
  264         pose_x, pose_y, pose_z, pose_roll, pose_pitch, pose_yaw)
 
  268     if status_msg == msg_max:
 
  270     return (status_msg + 1) % (msg_max + 1)
 
  273 if __name__ == 
"__main__":
 
  274     settings = termios.tcgetattr(sys.stdin)
 
  276     rospy.init_node(
"teleop_legged")
 
  278     speed = rospy.get_param(
"~/speed", 0.5)
 
  279     turn = rospy.get_param(
"~/turn", 1.0)
 
  280     pose_speed = rospy.get_param(
"~/pose_speed", 0.01)
 
  281     pose_turn = rospy.get_param(
"~/pose_turn", 0.1)
 
  282     repeat = rospy.get_param(
"~/repeat_rate", 0.0)
 
  283     key_timeout = rospy.get_param(
"~/key_timeout", 0.0)
 
  284     msg_max = rospy.get_param(
"~/msg_max", 14)
 
  285     if key_timeout == 0.0:
 
  303         pub_thread.wait_for_subscribers()
 
  304         pub_thread.update(x, y, z, th, speed, turn, pose_x, pose_y, pose_z, pose_roll, pose_pitch, pose_yaw, pose_speed,
 
  308         rospy.loginfo(
vels(speed, turn))
 
  311             if key 
in moveBindings.keys():
 
  312                 x = moveBindings[key][0]
 
  313                 y = moveBindings[key][1]
 
  314                 z = moveBindings[key][2]
 
  315                 th = moveBindings[key][3]
 
  316             elif key 
in speedBindings.keys():
 
  317                 speed = speed * speedBindings[key][0]
 
  318                 turn = turn * speedBindings[key][1]
 
  323                 rospy.loginfo(
vels(speed, turn))
 
  326             elif key 
in poseBindings.keys():
 
  327                 pose_x += pose_speed * poseBindings[key][0]
 
  328                 pose_y += pose_speed * poseBindings[key][1]
 
  329                 pose_z += pose_speed * poseBindings[key][2]
 
  330                 pose_roll += pose_turn * poseBindings[key][3]
 
  331                 pose_pitch += pose_turn * poseBindings[key][4]
 
  332                 pose_yaw += pose_turn * poseBindings[key][5]
 
  338                 rospy.loginfo(
pose_print(pose_x, pose_y, pose_z, pose_roll, pose_pitch, pose_yaw))
 
  341             elif key 
in speedPoseBindings.keys():
 
  342                 pose_speed = pose_speed * speedPoseBindings[key][0]
 
  343                 pose_turn = pose_turn * speedPoseBindings[key][1]
 
  349                 rospy.loginfo(
pose_vel(pose_speed, pose_turn))
 
  355                 if key == 
'' and x == 0 
and y == 0 
and z == 0 
and th == 0:
 
  364             pub_thread.update(x, y, z, th, speed, turn, pose_x, pose_y, pose_z, pose_roll, pose_pitch, pose_yaw,
 
  365                               pose_speed, pose_turn)
 
  367     except Exception 
as e:
 
  373         termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)