5 import geometry_msgs.msg
 
   16     fd = sys.stdin.fileno()
 
   17     old_settings = termios.tcgetattr(fd)
 
   19         tty.setraw(sys.stdin.fileno())
 
   20         ch = sys.stdin.read(1)
 
   23         termios.tcsetattr(fd, termios.TCSADRAIN, old_settings)
 
   32     sys.stdout.write(
'%-8s%-8s%-8s%-40s\r' % (status[
'mode'], status[status[
'mode']][
'value'], status[status[
'mode']][
'step'], status[
'message']))
 
   36     static_transformStamped = geometry_msgs.msg.TransformStamped()
 
   37     static_transformStamped.header.stamp = rospy.Time.now()
 
   38     static_transformStamped.header.frame_id = from_cam
 
   40     static_transformStamped.child_frame_id = to_cam
 
   41     static_transformStamped.transform.translation.x = status[
'x'][
'value']
 
   42     static_transformStamped.transform.translation.y = status[
'y'][
'value']
 
   43     static_transformStamped.transform.translation.z = status[
'z'][
'value']
 
   45     quat = tf.transformations.quaternion_from_euler(math.radians(status[
'roll'][
'value']),
 
   46                                                     math.radians(status[
'pitch'][
'value']),
 
   47                                                     math.radians(status[
'azimuth'][
'value']))
 
   48     static_transformStamped.transform.rotation.x = quat[0]
 
   49     static_transformStamped.transform.rotation.y = quat[1]
 
   50     static_transformStamped.transform.rotation.z = quat[2]
 
   51     static_transformStamped.transform.rotation.w = quat[3]
 
   52     broadcaster.sendTransform(static_transformStamped)
 
   55 if __name__ == 
'__main__':
 
   58         print (
'set_cams_transforms.py from_cam to_cam x y z azimuth pitch roll')
 
   59         print (
'x, y, z: in meters')
 
   60         print (
'azimuth, pitch, roll: in degrees')
 
   62         print (
'If parameters are not given read last used parameters.')
 
   65         print (
'--file <file name> : if given, default values are loaded from file')
 
   68     from_cam, to_cam = sys.argv[1:3]
 
   70         filename = sys.argv[sys.argv.index(
'--file')+1]
 
   71         print (
'Using file %s' % os.path.abspath(filename))
 
   73         filename = os.path.join(os.path.dirname(__file__), 
'_set_cams_info_file.txt')
 
   74         print (
'Using default file %s' % os.path.abspath(filename))
 
   76     if len(sys.argv) >= 9:
 
   77         x, y, z, yaw, pitch, roll = [float(arg) 
for arg 
in sys.argv[3:10]]
 
   78         status = {
'mode': 
'pitch',
 
   79                   'x': {
'value': x, 
'step': 0.1},
 
   80                   'y': {
'value': y, 
'step': 0.1},
 
   81                   'z': {
'value': z, 
'step': 0.1},
 
   82                   'azimuth': {
'value': yaw, 
'step': 1},
 
   83                   'pitch': {
'value': pitch, 
'step': 1},
 
   84                   'roll': {
'value': roll, 
'step': 1},
 
   86         print (
'Use given initial values.')
 
   89             status = json.load(open(filename, 
'r'))
 
   90             print (
'Read initial values from file.')
 
   92             print (
'Failed reading initial parameters from file %s' % filename)
 
   93             print (
'Initial parameters must be given for initial run or if an un-initialized file has been given.')
 
   96     rospy.init_node(
'my_static_tf2_broadcaster')
 
  100     print (
'Press the following keys to change mode: x, y, z, (a)zimuth, (p)itch, (r)oll')
 
  101     print (
'For each mode, press 6 to increase by step and 4 to decrease')
 
  102     print (
'Press + to multiply step by 2 or - to divide')
 
  104     print (
'Press Q to quit')
 
  107     status_keys = [key[0] 
for key 
in status.keys()]
 
  108     print (
'%-8s%-8s%-8s%s' % (
'Mode', 
'value', 
'step', 
'message'))
 
  113         status[
'message'] = 
'' 
  115             key_idx = status_keys.index(kk)
 
  116             status[
'mode'] = status.keys()[key_idx]
 
  117         except ValueError 
as e:
 
  118             if kk.upper() == 
'Q':
 
  119                 sys.stdout.write(
'\n')
 
  122                 status[status[
'mode']][
'value'] -= status[status[
'mode']][
'step']
 
  124                 status[status[
'mode']][
'value'] += status[status[
'mode']][
'step']
 
  126                 status[status[
'mode']][
'step'] /= 2.0
 
  128                 status[status[
'mode']][
'step'] *= 2.0
 
  130                 status[
'message'] = 
'Invalid key:' + kk
 
  134         json.dump(status, open(filename, 
'w'), indent=4)