rviz_mouse_point_to_tablet.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import numpy
00005 from math import pi
00006 from view_controller_msgs.msg import CameraPlacement
00007 from geometry_msgs.msg import PointStamped
00008 from jsk_gui_msgs.msg import Tablet
00009 from threading import Lock
00010 
00011 lock = Lock()
00012 latest_mouse_point = None
00013 
00014 def pointCallback(msg):
00015     global latest_mouse_point
00016     with lock:
00017         latest_mouse_point = msg
00018     
00019 def timerCallback(event):
00020     global latest_mouse_point
00021     # print (latest_mouse_point and latest_mouse_point.point, 
00022     #        prev_mouse_point and prev_mouse_point.point)
00023     with lock:
00024         if not latest_mouse_point:
00025             return
00026         next_x = latest_mouse_point.point.x * 640
00027         next_y = latest_mouse_point.point.y * 480
00028         msg = Tablet()
00029         msg.header.stamp = rospy.Time.now()
00030         msg.action.task_name = "MoveCameraCenter"
00031         # chop
00032         msg.action.touch_x = next_x
00033         msg.action.touch_y = next_y
00034         rospy.loginfo("neck actino to (%f, %f)" % (msg.action.touch_x, msg.action.touch_y))
00035         pub.publish(msg)
00036         latest_mouse_point = None
00037 
00038         
00039 if __name__ == "__main__":
00040     rospy.init_node("rviz_mouse_point_to_tablet")
00041     pub = rospy.Publisher("/Tablet/Command", Tablet)
00042     sub = rospy.Subscriber("/rviz/current_mouse_point", 
00043                            PointStamped, pointCallback)
00044     rospy.Timer(rospy.Duration(0.3), timerCallback)
00045     rospy.spin()


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Wed May 1 2019 02:40:22