2 from jsk_teleop_joy.joy_pose_6d
import JoyPose6D
6 imp.find_module(
"actionlib")
8 import roslib; roslib.load_manifest(
'jsk_teleop_joy')
11 from std_msgs.msg
import String, Empty
12 import xml.etree.ElementTree
as ET
16 JoyPose6D.__init__(self, name, args)
17 self.supportFollowView(
True)
18 self.
frame_id = self.getArg(
'frame_id',
'/map')
20 self.
plan_group_pub = rospy.Publisher(
'/rviz/moveit/select_planning_group', String)
21 self.
plan_pub = rospy.Publisher(
"/rviz/moveit/plan", Empty)
22 self.
execute_pub = rospy.Publisher(
"/rviz/moveit/execute", Empty)
28 def joyCB(self, status, history):
29 JoyPose6D.joyCB(self, status, history)
30 latest = history.latest()
33 if status.triangle
and not latest.triangle:
39 elif status.cross
and not latest.cross:
45 elif status.square
and not latest.square:
47 elif status.circle
and not latest.circle:
def joyCB(self, status, history)
def __init__(self, name, args)