set_cams_transforms.py
Go to the documentation of this file.
00001 import rospy
00002 import sys
00003 import tf
00004 import tf2_ros
00005 import geometry_msgs.msg
00006 
00007 import termios
00008 import tty
00009 import os
00010 import time
00011 import math
00012 import json
00013 
00014 
00015 def getch():
00016     fd = sys.stdin.fileno()
00017     old_settings = termios.tcgetattr(fd)
00018     try:
00019         tty.setraw(sys.stdin.fileno())
00020         ch = sys.stdin.read(1)
00021 
00022     finally:
00023         termios.tcsetattr(fd, termios.TCSADRAIN, old_settings)
00024     return ch
00025 
00026 
00027 def main():
00028     return
00029 
00030 
00031 def print_status(status):
00032     sys.stdout.write('%-8s%-8s%-8s%-40s\r' % (status['mode'], status[status['mode']]['value'], status[status['mode']]['step'], status['message']))
00033 
00034 
00035 def publish_status(broadcaster, status):
00036     static_transformStamped = geometry_msgs.msg.TransformStamped()
00037     static_transformStamped.header.stamp = rospy.Time.now()
00038     static_transformStamped.header.frame_id = from_cam
00039 
00040     static_transformStamped.child_frame_id = to_cam
00041     static_transformStamped.transform.translation.x = status['x']['value']
00042     static_transformStamped.transform.translation.y = status['y']['value']
00043     static_transformStamped.transform.translation.z = status['z']['value']
00044 
00045     quat = tf.transformations.quaternion_from_euler(math.radians(status['roll']['value']),
00046                                                     math.radians(status['pitch']['value']),
00047                                                     math.radians(status['azimuth']['value']))
00048     static_transformStamped.transform.rotation.x = quat[0]
00049     static_transformStamped.transform.rotation.y = quat[1]
00050     static_transformStamped.transform.rotation.z = quat[2]
00051     static_transformStamped.transform.rotation.w = quat[3]
00052     broadcaster.sendTransform(static_transformStamped)
00053 
00054 
00055 if __name__ == '__main__':
00056     if len(sys.argv) < 3:
00057         print 'USAGE:'
00058         print 'set_cams_transforms.py from_cam to_cam x y z azimuth pitch roll'
00059         print 'x, y, z: in meters'
00060         print 'azimuth, pitch, roll: in degrees'
00061         print
00062         print 'If parameters are not given read last used parameters.'
00063         print
00064         print '[OPTIONS]'
00065         print '--file <file name> : if given, default values are loaded from file'
00066         sys.exit(-1)
00067 
00068     from_cam, to_cam = sys.argv[1:3]
00069     try:
00070         filename = sys.argv[sys.argv.index('--file')+1]
00071         print 'Using file %s' % os.path.abspath(filename)
00072     except:
00073         filename = os.path.join(os.path.dirname(__file__), '_set_cams_info_file.txt')
00074         print 'Using default file %s' % os.path.abspath(filename)
00075 
00076     if len(sys.argv) >= 9:
00077         x, y, z, yaw, pitch, roll = [float(arg) for arg in sys.argv[3:10]]
00078         status = {'mode': 'pitch',
00079                   'x': {'value': x, 'step': 0.1},
00080                   'y': {'value': y, 'step': 0.1},
00081                   'z': {'value': z, 'step': 0.1},
00082                   'azimuth': {'value': yaw, 'step': 1},
00083                   'pitch': {'value': pitch, 'step': 1},
00084                   'roll': {'value': roll, 'step': 1},
00085                   'message': ''}
00086         print 'Use given initial values.'
00087     else:
00088         try:
00089             status = json.load(open(filename, 'r'))
00090             print 'Read initial values from file.'
00091         except IOError as e:
00092             print 'Failed reading initial parameters from file %s' % filename
00093             print 'Initial parameters must be given for initial run or if an un-initialized file has been given.'
00094             sys.exit(-1)
00095 
00096     rospy.init_node('my_static_tf2_broadcaster')
00097     broadcaster = tf2_ros.StaticTransformBroadcaster()
00098 
00099     print
00100     print 'Press the following keys to change mode: x, y, z, (a)zimuth, (p)itch, (r)oll'
00101     print 'For each mode, press 6 to increase by step and 4 to decrease'
00102     print 'Press + to multiply step by 2 or - to divide'
00103     print
00104     print 'Press Q to quit'
00105     print
00106 
00107     status_keys = [key[0] for key in status.keys()]
00108     print '%-8s%-8s%-8s%s' % ('Mode', 'value', 'step', 'message')
00109     print_status(status)
00110     publish_status(broadcaster, status)
00111     while True:
00112         kk = getch()
00113         status['message'] = ''
00114         try:
00115             key_idx = status_keys.index(kk)
00116             status['mode'] = status.keys()[key_idx]
00117         except ValueError as e:
00118             if kk.upper() == 'Q':
00119                 sys.stdout.write('\n')
00120                 exit(0)
00121             elif kk == '4':
00122                 status[status['mode']]['value'] -= status[status['mode']]['step']
00123             elif kk == '6':
00124                 status[status['mode']]['value'] += status[status['mode']]['step']
00125             elif kk == '-':
00126                 status[status['mode']]['step'] /= 2.0
00127             elif kk == '+':
00128                 status[status['mode']]['step'] *= 2.0
00129             else:
00130                 status['message'] = 'Invalid key:' + kk
00131 
00132         print_status(status)
00133         publish_status(broadcaster, status)
00134         json.dump(status, open(filename, 'w'), indent=4)
00135 
00136     #rospy.spin()


realsense2_camera
Author(s): Sergey Dorodnicov , Doron Hirshberg
autogenerated on Sat Jul 6 2019 03:30:09