1 from __future__
import print_function
7 from drc_task_common.srv
import StringRequest, StringRequestResponse
10 imp.find_module(
"std_msgs")
12 import roslib; roslib.load_manifest(
'jsk_teleop_joy')
15 from std_msgs.msg
import String, Float64, Bool, Float32
16 from std_srvs.srv
import Empty, EmptyResponse
17 from geometry_msgs.msg
import PoseStamped
18 import xml.etree.ElementTree
as ET
19 import os, sys, time, numpy
23 JSKJoyPlugin.__init__(self, name, args)
25 "handle":
HandleCommandState(
"handle", Float64, Float32,
"drive/controller/goal_handle_angle"),
33 print(
"Joystick initialization is finished", file=sys.stderr)
38 def joyCB(self, status, history):
39 latest = history.latest()
40 handle_resolution = 0.025
41 neck_y_resolution = 0.1
42 neck_y_angle_max = 35.0
43 neck_y_angle_min = -35.0
44 neck_p_resolution = 0.1
45 neck_p_angle_max = 35.0
46 neck_p_angle_min = -35.0
47 max_accel_resolution = 0.05
48 max_brake_resolution = 1.0
54 if status.left_analog_x:
67 if status.right_analog_y:
68 self.
command_states[
"accel"].command = max(status.right_analog_y, 0.0)
69 if status.right_analog_y < -0.5:
78 command.publishCommand()
81 next_value = current_value + resolution
82 if next_value > max_value:
83 next_value = max_value
84 elif next_value < min_value:
85 next_value = min_value
93 print(
"Sync " + key, file=sys.stderr)
102 print(
"set execute_flag as " + str(self.
execute_flag), file=sys.stderr)
105 print(
"initialize vehicle joy", file=sys.stderr)
107 return EmptyResponse()
110 key = req.data.lower()
119 print(
"Invalid key", file=sys.stderr)
120 return StringRequestResponse()
123 def __init__(self, command_name, pub_type, sub_type, robot_topic):
146 print(
"Sync with " + self.
robot_topic, file=sys.stderr)
149 except rospy.ROSException
as e:
150 print(
"Cannot subscribe " + self.
robot_topic, file=sys.stderr)