vehicle.py
Go to the documentation of this file.
1 from __future__ import print_function
2 
3 import rospy
4 
5 import actionlib
6 from jsk_teleop_joy.joy_plugin import JSKJoyPlugin
7 from drc_task_common.srv import StringRequest, StringRequestResponse
8 
9 try:
10  imp.find_module("std_msgs")
11 except:
12  import roslib; roslib.load_manifest('jsk_teleop_joy')
13 
14 
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
20 
22  def __init__(self, name, args):
23  JSKJoyPlugin.__init__(self, name, args)
24  self.command_states = {
25  "handle": HandleCommandState("handle", Float64, Float32, "drive/controller/goal_handle_angle"),
26  "accel": VehicleCommandState("accel", Float64, Float32, "drive/controller/step"),
27  "brake": VehicleCommandState("brake", Float64, None, None), # do not support brake synchronize
28  "neck_y": VehicleCommandState("neck_y", Float64, Float32, "drive/controller/neck_y_angle"),
29  "neck_p": VehicleCommandState("neck_p", Float64, Float32, "drive/controller/neck_p_angle")
30  }
32  self.execute_flag = False
33  print("Joystick initialization is finished", file=sys.stderr)
34  self.initialize_service = rospy.Service('drive/operation/initialize', Empty, self.initializeServiceCallback)
35  self.synchronize_service = rospy.Service('drive/operation/synchronize', StringRequest, self.synchronizeServiceCallback)
36  self.subscriber = rospy.Subscriber('drive/execute_flag', Bool, self.executeFlagCallback)
37 
38  def joyCB(self, status, history):
39  latest = history.latest()
40  handle_resolution = 0.025 # rad
41  neck_y_resolution = 0.1 # deg
42  neck_y_angle_max = 35.0
43  neck_y_angle_min = -35.0
44  neck_p_resolution = 0.1 # deg
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
49 
50  if not self.execute_flag or not latest:
51  return
52 
53  # handle command
54  if status.left_analog_x:
55  self.command_states["handle"].command = self.command_states["handle"].command + handle_resolution * status.left_analog_x
56  # neck_y command
57  if status.left:
58  self.command_states["neck_y"].command = self.commandJointAngle(self.command_states["neck_y"].command, neck_y_resolution, neck_y_angle_max, neck_y_angle_min)
59  elif status.right:
60  self.command_states["neck_y"].command = self.commandJointAngle(self.command_states["neck_y"].command, -neck_y_resolution, neck_y_angle_max, neck_y_angle_min)
61  # neck_p command (head goes down when neck_p incleases)
62  if status.up:
63  self.command_states["neck_p"].command = self.commandJointAngle(self.command_states["neck_p"].command, -neck_p_resolution, neck_p_angle_max, neck_p_angle_min)
64  elif status.down:
65  self.command_states["neck_p"].command = self.commandJointAngle(self.command_states["neck_p"].command, neck_p_resolution, neck_p_angle_max, neck_p_angle_min)
66  # accel command
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:
70  self.command_states["brake"].command = 1.0
71  else:
72  self.command_states["brake"].command = 0.0
73  else:
74  self.command_states["accel"].command = 0.0
75  self.command_states["brake"].command = 0.0
76 
77  for command in self.command_states.values():
78  command.publishCommand()
79 
80  def commandJointAngle(self, current_value, resolution, max_value, min_value): # max_value assumed to be positive
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
86  return next_value
87 
89  for command in self.command_states.values():
90  command.initialize()
91 
92  def synchronizeCommand(self, key):
93  print("Sync " + key, file=sys.stderr)
94  self.command_states[key].synchronize()
95 
97  for key in self.command_states.keys():
98  self.synchronizeCommand(key)
99 
100  def executeFlagCallback(self, msg):
101  self.execute_flag = msg.data
102  print("set execute_flag as " + str(self.execute_flag), file=sys.stderr)
103 
105  print("initialize vehicle joy", file=sys.stderr)
106  self.initializeAllCommand()
107  return EmptyResponse()
108 
110  key = req.data.lower()
111  if key in self.command_states:
112  self.synchronizeCommand(key)
113  elif key == "neck":
114  self.synchronizeCommand("neck_p")
115  self.synchronizeCommand("neck_y")
116  elif key == "all":
117  self.synchronizeAllCommand()
118  else:
119  print("Invalid key", file=sys.stderr)
120  return StringRequestResponse()
121 
123  def __init__(self, command_name, pub_type, sub_type, robot_topic):
124  self.command_name = command_name
125  self.pub_type = pub_type
126  self.sub_type = sub_type
128  self.robot_topic = robot_topic
129  self.publisher = rospy.Publisher("drive/operation/" + self.command_name + "_cmd_fast", self.pub_type)
130  if robot_topic and self.sub_type:
131  self.subscriber = rospy.Subscriber(robot_topic, self.sub_type, self.callback)
132  else:
133  self.subscriber = None
134  self.initialize()
135  def callback(self, msg):
136  self.robot_value = msg.data
137  def initialize(self):
138  self.command = 0.0
139  self.robot_value = 0.0
140  def synchronize(self, timeout = 1.0):
141  if self.robot_topic != None and self.sub_type != None:
142  try:
143  if self.wait_for_message_flag:
144  rospy.wait_for_message(self.robot_topic, self.sub_type, timeout)
145  self.wait_for_message_flag = False
146  print("Sync with " + self.robot_topic, file=sys.stderr)
147  print("%s -> %s" % (str(self.command), str(self.robot_value)))
148  self.command = self.robot_value
149  except rospy.ROSException as e:
150  print("Cannot subscribe " + self.robot_topic, file=sys.stderr)
151  def publishCommand(self):
152  pub_msg = self.pub_type(data = self.command)
153  self.publisher.publish(pub_msg)
154 
156  def callback(self, msg):
157  self.robot_value = msg.data * numpy.pi / 180.0 # goal_handle_angle[deg] -> command[rad]
158  # def synchronize(self):
159  # self.command = self.robot_value * numpy.pi / 180.0 # robot_value[deg] -> command[rad]
160 
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.__init__
def __init__(self, command_name, pub_type, sub_type, robot_topic)
Definition: vehicle.py:123
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.callback
def callback(self, msg)
Definition: vehicle.py:135
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.command
command
Definition: vehicle.py:138
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.initialize
def initialize(self)
Definition: vehicle.py:137
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.subscriber
subscriber
Definition: vehicle.py:131
jsk_teleop_joy.plugin.vehicle.VehicleCommandState
Definition: vehicle.py:122
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.execute_flag
execute_flag
Definition: vehicle.py:32
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.executeFlagCallback
def executeFlagCallback(self, msg)
Definition: vehicle.py:100
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.publishCommand
def publishCommand(self)
Definition: vehicle.py:151
jsk_teleop_joy.plugin.vehicle.HandleCommandState.callback
def callback(self, msg)
Definition: vehicle.py:156
jsk_teleop_joy.joy_plugin
Definition: joy_plugin.py:1
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.wait_for_message_flag
wait_for_message_flag
Definition: vehicle.py:127
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.synchronizeCommand
def synchronizeCommand(self, key)
Definition: vehicle.py:92
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.initializeServiceCallback
def initializeServiceCallback(self, req)
Definition: vehicle.py:104
jsk_teleop_joy.joy_plugin.JSKJoyPlugin
Definition: joy_plugin.py:5
jsk_teleop_joy.plugin.vehicle.HandleCommandState
Definition: vehicle.py:155
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.synchronize_service
synchronize_service
Definition: vehicle.py:35
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.commandJointAngle
def commandJointAngle(self, current_value, resolution, max_value, min_value)
Definition: vehicle.py:80
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.pub_type
pub_type
Definition: vehicle.py:125
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.synchronizeAllCommand
def synchronizeAllCommand(self)
Definition: vehicle.py:96
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.publisher
publisher
Definition: vehicle.py:129
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.subscriber
subscriber
Definition: vehicle.py:36
jsk_teleop_joy.plugin.vehicle.VehicleJoyController
Definition: vehicle.py:21
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.command_name
command_name
Definition: vehicle.py:124
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.synchronizeServiceCallback
def synchronizeServiceCallback(self, req)
Definition: vehicle.py:109
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.robot_value
robot_value
Definition: vehicle.py:136
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.synchronize
def synchronize(self, timeout=1.0)
Definition: vehicle.py:140
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.robot_topic
robot_topic
Definition: vehicle.py:128
jsk_teleop_joy.plugin.vehicle.VehicleCommandState.sub_type
sub_type
Definition: vehicle.py:126
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.joyCB
def joyCB(self, status, history)
Definition: vehicle.py:38
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.__init__
def __init__(self, name, args)
Definition: vehicle.py:22
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.initializeAllCommand
def initializeAllCommand(self)
Definition: vehicle.py:88
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.initialize_service
initialize_service
Definition: vehicle.py:34
jsk_teleop_joy.plugin.vehicle.VehicleJoyController.command_states
command_states
Definition: vehicle.py:24


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Wed Jan 24 2024 04:05:49