Go to the documentation of this file.00001
00002
00003 from jsk_teleop_joy.plugin.rviz_view_controller_singleton import RVizViewControllerManagerSingleton
00004 from jsk_teleop_joy.joy_plugin import JSKJoyPlugin
00005
00006 import rospy
00007
00008 class RVizViewController(JSKJoyPlugin):
00009 '''
00010 Usage:
00011 Right Analog x/y: yaw/pitch of camera position
00012
00013 R3(Right Analog button): while holding down L3 button, buttons/sticks listed below work for RVizViewController
00014 L3: reset camera pose
00015 L1: set focus point to target pose of Pose6D
00016 Up/Down/Left/Right : move focus point x/y
00017 Left Analog y: move camera for eye direction (near/far)
00018 Left Analog x: move focus point for eye direction (near/far)
00019 R3 + L2 + R2: enable follow view mode
00020
00021 Args:
00022 control_view [Boolean, default: True]: Use or not control rviz camera (this is for child class)
00023
00024 Note: code of joyCB is implemented in rviz_view_controller_singleton.py
00025 Use TabletViewController(jsk_rviz_plugin) in rviz (selected at 'Views' Panel)
00026 '''
00027 def __init__(self, name, args):
00028 JSKJoyPlugin.__init__(self, name, args)
00029 self.control_view = self.getArg('control_view', True)
00030 if not self.control_view:
00031 rospy.loginfo("Not using rviz view control")
00032 RVizViewControllerManagerSingleton.camera_pub.unregister()
00033 RVizViewControllerManagerSingleton.camera_sub.unregister()
00034 def joyCB(self, status, history):
00035 RVizViewControllerManagerSingleton.joyCB(status, history, self.pre_pose)
00036 def supportFollowView(self, val):
00037 RVizViewControllerManagerSingleton.support_follow_view = val
00038 def followView(self, val=None):
00039 if val != None:
00040 RVizViewControllerManagerSingleton.follow_view = val
00041 return RVizViewControllerManagerSingleton.follow_view