You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

490 lines
18 KiB

2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
2 years ago
  1. ## Example 9
  2. This example aims to combine the [ReSpeaker Microphone Array](respeaker_microphone_array.md) and [Follow Joint Trajectory](follow_joint_trajectory.md) tutorials to voice teleoperate the mobile base of the Stretch robot.
  3. Begin by running the following command in a new terminal.
  4. ```{.bash .shell-prompt}
  5. roslaunch stretch_core stretch_driver.launch
  6. ```
  7. Switch the mode to `position` mode using a rosservice call.
  8. ```{.bash .shell-prompt}
  9. rosservice call /switch_to_position_mode
  10. ```
  11. Then run the `respeaker.launch` file. In a new terminal, execute:
  12. ```{.bash .shell-prompt}
  13. roslaunch stretch_core respeaker.launch
  14. ```
  15. Then run the [voice_teleoperation_base.py](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/voice_teleoperation_base.py) node in a new terminal.
  16. ```{.bash .shell-prompt}
  17. cd catkin_ws/src/stretch_tutorials/src/
  18. python3 voice_teleoperation_base.py
  19. ```
  20. In terminal 3, a menu of voice commands is printed. You can reference this menu layout below.
  21. ```{.bash .no-copy}
  22. ------------ VOICE TELEOP MENU ------------
  23. VOICE COMMANDS
  24. "forward": BASE FORWARD
  25. "back" : BASE BACK
  26. "left" : BASE ROTATE LEFT
  27. "right" : BASE ROTATE RIGHT
  28. "stretch": BASE ROTATES TOWARDS SOUND
  29. STEP SIZE
  30. "big" : BIG
  31. "medium" : MEDIUM
  32. "small" : SMALL
  33. "quit" : QUIT AND CLOSE NODE
  34. -------------------------------------------
  35. ```
  36. To stop the node from sending twist messages, type `Ctrl` + `c` or say "**quit**".
  37. ### The Code
  38. ```python
  39. #!/usr/bin/env python3
  40. import math
  41. import rospy
  42. import sys
  43. from sensor_msgs.msg import JointState
  44. from std_msgs.msg import Int32
  45. from control_msgs.msg import FollowJointTrajectoryGoal
  46. from trajectory_msgs.msg import JointTrajectoryPoint
  47. import hello_helpers.hello_misc as hm
  48. from speech_recognition_msgs.msg import SpeechRecognitionCandidates
  49. class GetVoiceCommands:
  50. """
  51. A class that subscribes to the speech to text recognition messages, prints
  52. a voice command menu, and defines step size for translational and rotational
  53. mobile base motion.
  54. """
  55. def __init__(self):
  56. """
  57. A function that initializes subscribers and defines the three different
  58. step sizes.
  59. :param self: The self reference.
  60. """
  61. self.step_size = 'medium'
  62. self.rad_per_deg = math.pi/180.0
  63. self.small_deg = 5.0
  64. self.small_rad = self.rad_per_deg * self.small_deg
  65. self.small_translate = 0.025
  66. self.medium_deg = 10.0
  67. self.medium_rad = self.rad_per_deg * self.medium_deg
  68. self.medium_translate = 0.05
  69. self.big_deg = 20.0
  70. self.big_rad = self.rad_per_deg * self.big_deg
  71. self.big_translate = 0.1
  72. self.voice_command = None
  73. self.sound_direction = 0
  74. self.speech_to_text_sub = rospy.Subscriber("/speech_to_text", SpeechRecognitionCandidates, self.callback_speech)
  75. self.sound_direction_sub = rospy.Subscriber("/sound_direction", Int32, self.callback_direction)
  76. def callback_direction(self, msg):
  77. """
  78. A callback function that converts the incoming message, sound direction,
  79. from degrees to radians.
  80. :param self: The self reference.
  81. :param msg: The Int32 message type that represents the sound direction.
  82. """
  83. self.sound_direction = msg.data * -self.rad_per_deg
  84. def callback_speech(self,msg):
  85. """
  86. A callback function takes the incoming message, a list of the speech to
  87. text, and joins all items in that iterable list into a single string.
  88. :param self: The self reference.
  89. :param msg: The SpeechRecognitionCandidates message type.
  90. """
  91. self.voice_command = ' '.join(map(str,msg.transcript))
  92. def get_inc(self):
  93. """
  94. A function that sets the increment size for translational and rotational
  95. base motion.
  96. :param self:The self reference.
  97. :returns inc: A dictionary type the contains the increment size.
  98. """
  99. if self.step_size == 'small':
  100. inc = {'rad': self.small_rad, 'translate': self.small_translate}
  101. if self.step_size == 'medium':
  102. inc = {'rad': self.medium_rad, 'translate': self.medium_translate}
  103. if self.step_size == 'big':
  104. inc = {'rad': self.big_rad, 'translate': self.big_translate}
  105. return inc
  106. def print_commands(self):
  107. """
  108. A function that prints the voice teleoperation menu.
  109. :param self: The self reference.
  110. """
  111. print(' ')
  112. print('------------ VOICE TELEOP MENU ------------')
  113. print(' ')
  114. print(' VOICE COMMANDS ')
  115. print(' "forward": BASE FORWARD ')
  116. print(' "back" : BASE BACK ')
  117. print(' "left" : BASE ROTATE LEFT ')
  118. print(' "right" : BASE ROTATE RIGHT ')
  119. print(' "stretch": BASE ROTATES TOWARDS SOUND ')
  120. print(' ')
  121. print(' STEP SIZE ')
  122. print(' "big" : BIG ')
  123. print(' "medium" : MEDIUM ')
  124. print(' "small" : SMALL ')
  125. print(' ')
  126. print(' ')
  127. print(' "quit" : QUIT AND CLOSE NODE ')
  128. print(' ')
  129. print('-------------------------------------------')
  130. def get_command(self):
  131. """
  132. A function that defines the teleoperation command based on the voice command.
  133. :param self: The self reference.
  134. :returns command: A dictionary type that contains the type of base motion.
  135. """
  136. command = None
  137. if self.voice_command == 'forward':
  138. command = {'joint': 'translate_mobile_base', 'inc': self.get_inc()['translate']}
  139. if self.voice_command == 'back':
  140. command = {'joint': 'translate_mobile_base', 'inc': -self.get_inc()['translate']}
  141. if self.voice_command == 'left':
  142. command = {'joint': 'rotate_mobile_base', 'inc': self.get_inc()['rad']}
  143. if self.voice_command == 'right':
  144. command = {'joint': 'rotate_mobile_base', 'inc': -self.get_inc()['rad']}
  145. if self.voice_command == 'stretch':
  146. command = {'joint': 'rotate_mobile_base', 'inc': self.sound_direction}
  147. if (self.voice_command == "small") or (self.voice_command == "medium") or (self.voice_command == "big"):
  148. self.step_size = self.voice_command
  149. rospy.loginfo('Step size = {0}'.format(self.step_size))
  150. if self.voice_command == 'quit':
  151. rospy.signal_shutdown("done")
  152. sys.exit(0)
  153. self.voice_command = None
  154. return command
  155. class VoiceTeleopNode(hm.HelloNode):
  156. """
  157. A class that inherits the HelloNode class from hm and sends joint trajectory
  158. commands.
  159. """
  160. def __init__(self):
  161. """
  162. A function that declares object from the GetVoiceCommands class, instantiates
  163. the HelloNode class, and set the publishing rate.
  164. :param self: The self reference.
  165. """
  166. hm.HelloNode.__init__(self)
  167. self.rate = 10.0
  168. self.joint_state = None
  169. self.speech = GetVoiceCommands()
  170. def joint_states_callback(self, msg):
  171. """
  172. A callback function that stores Stretch's joint states.
  173. :param self: The self reference.
  174. :param msg: The JointState message type.
  175. """
  176. self.joint_state = msg
  177. def send_command(self, command):
  178. """
  179. Function that makes an action call and sends base joint trajectory goals
  180. :param self: The self reference.
  181. :param command: A dictionary type.
  182. """
  183. joint_state = self.joint_state
  184. if (joint_state is not None) and (command is not None):
  185. point = JointTrajectoryPoint()
  186. point.time_from_start = rospy.Duration(0.0)
  187. trajectory_goal = FollowJointTrajectoryGoal()
  188. trajectory_goal.goal_time_tolerance = rospy.Time(1.0)
  189. joint_name = command['joint']
  190. trajectory_goal.trajectory.joint_names = [joint_name]
  191. inc = command['inc']
  192. rospy.loginfo('inc = {0}'.format(inc))
  193. new_value = inc
  194. point.positions = [new_value]
  195. trajectory_goal.trajectory.points = [point]
  196. trajectory_goal.trajectory.header.stamp = rospy.Time.now()
  197. rospy.loginfo('joint_name = {0}, trajectory_goal = {1}'.format(joint_name, trajectory_goal))
  198. self.trajectory_client.send_goal(trajectory_goal)
  199. rospy.loginfo('Done sending command.')
  200. self.speech.print_commands()
  201. def main(self):
  202. """
  203. The main function that instantiates the HelloNode class, initializes the subscriber,
  204. and call other methods in both the VoiceTeleopNode and GetVoiceCommands classes.
  205. :param self: The self reference.
  206. """
  207. hm.HelloNode.main(self, 'voice_teleop', 'voice_teleop', wait_for_first_pointcloud=False)
  208. rospy.Subscriber('/stretch/joint_states', JointState, self.joint_states_callback)
  209. rate = rospy.Rate(self.rate)
  210. self.speech.print_commands()
  211. while not rospy.is_shutdown():
  212. command = self.speech.get_command()
  213. self.send_command(command)
  214. rate.sleep()
  215. if __name__ == '__main__':
  216. try:
  217. node = VoiceTeleopNode()
  218. node.main()
  219. except KeyboardInterrupt:
  220. rospy.loginfo('interrupt received, so shutting down')
  221. ```
  222. ### The Code Explained
  223. This code is similar to that of the [multipoint_command](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/multipoint_command.py) and [joint_state_printer](https://github.com/hello-robot/stretch_tutorials/blob/noetic/src/joint_state_printer.py) node. Therefore, this example will highlight sections that are different from those tutorials. Now let's break the code down.
  224. ```python
  225. #!/usr/bin/env python3
  226. ```
  227. Every Python ROS [Node](http://wiki.ros.org/Nodes) will have this declaration at the top. The first line makes sure your script is executed as a Python script.
  228. ```python
  229. import math
  230. import rospy
  231. import sys
  232. from sensor_msgs.msg import JointState
  233. from std_msgs.msg import Int32
  234. from control_msgs.msg import FollowJointTrajectoryGoal
  235. from trajectory_msgs.msg import JointTrajectoryPoint
  236. import hello_helpers.hello_misc as hm
  237. from speech_recognition_msgs.msg import SpeechRecognitionCandidates
  238. ```
  239. You need to import `rospy` if you are writing a ROS Node. Import the `FollowJointTrajectoryGoal` from the `control_msgs.msg` package to control the Stretch robot. Import `JointTrajectoryPoint` from the `trajectory_msgs` package to define robot trajectories. The `hello_helpers` package consists of a module that provides various Python scripts used across stretch_ros. In this instance, we are importing the `hello_misc` script. Import `sensor_msgs.msg` so that we can subscribe to JointState messages.
  240. ```python
  241. class GetVoiceCommands:
  242. ```
  243. Create a class that subscribes to the `speech-to-text` recognition messages, prints a voice command menu, and defines step size for translational and rotational mobile base motion.
  244. ```python
  245. self.step_size = 'medium'
  246. self.rad_per_deg = math.pi/180.0
  247. ```
  248. Set the default step size as medium and create a float value, `self.rad_per_deg`, to convert degrees to radians.
  249. ```python
  250. self.small_deg = 5.0
  251. self.small_rad = self.rad_per_deg * self.small_deg
  252. self.small_translate = 0.025
  253. self.medium_deg = 10.0
  254. self.medium_rad = self.rad_per_deg * self.medium_deg
  255. self.medium_translate = 0.05
  256. self.big_deg = 20.0
  257. self.big_rad = self.rad_per_deg * self.big_deg
  258. self.big_translate = 0.1
  259. ```
  260. Define the three rotation and translation step sizes.
  261. ```python
  262. self.voice_command = None
  263. self.sound_direction = 0
  264. self.speech_to_text_sub = rospy.Subscriber("/speech_to_text", SpeechRecognitionCandidates, self.callback_speech)
  265. self.sound_direction_sub = rospy.Subscriber("/sound_direction", Int32, self.callback_direction)
  266. ```
  267. Initialize the voice command and sound direction to values that will not result in moving the base.
  268. Set up two subscribers. The first one subscribes to the topic `/speech_to_text`, looking for `SpeechRecognitionCandidates` messages. When a message comes in, ROS is going to pass it to the function `callback_speech` automatically. The second subscribes to `/sound_direction` message and passes it to the `callback_direction` function.
  269. ```python
  270. self.sound_direction = msg.data * -self.rad_per_deg
  271. ```
  272. The `callback_direction` function converts the `sound_direction` topic from degrees to radians.
  273. ```python
  274. if self.step_size == 'small':
  275. inc = {'rad': self.small_rad, 'translate': self.small_translate}
  276. if self.step_size == 'medium':
  277. inc = {'rad': self.medium_rad, 'translate': self.medium_translate}
  278. if self.step_size == 'big':
  279. inc = {'rad': self.big_rad, 'translate': self.big_translate}
  280. return inc
  281. ```
  282. The `callback_speech` stores the increment size for translational and rotational base motion in `inc`. The increment size is contingent on the `self.step_size` string value.
  283. ```python
  284. command = None
  285. if self.voice_command == 'forward':
  286. command = {'joint': 'translate_mobile_base', 'inc': self.get_inc()['translate']}
  287. if self.voice_command == 'back':
  288. command = {'joint': 'translate_mobile_base', 'inc': -self.get_inc()['translate']}
  289. if self.voice_command == 'left':
  290. command = {'joint': 'rotate_mobile_base', 'inc': self.get_inc()['rad']}
  291. if self.voice_command == 'right':
  292. command = {'joint': 'rotate_mobile_base', 'inc': -self.get_inc()['rad']}
  293. if self.voice_command == 'stretch':
  294. command = {'joint': 'rotate_mobile_base', 'inc': self.sound_direction}
  295. ```
  296. In the `get_command()` function, the `command` is initialized as `None`, or set as a dictionary where the `joint` and `inc` values are stored. The `command` message type is dependent on the `self.voice_command` string value.
  297. ```python
  298. if (self.voice_command == "small") or (self.voice_command == "medium") or (self.voice_command == "big"):
  299. self.step_size = self.voice_command
  300. rospy.loginfo('Step size = {0}'.format(self.step_size))
  301. ```
  302. Based on the `self.voice_command` value set the step size for the increments.
  303. ```python
  304. if self.voice_command == 'quit':
  305. rospy.signal_shutdown("done")
  306. sys.exit(0)
  307. ```
  308. If the `self.voice_command` is equal to `quit`, then initiate a clean shutdown of ROS and exit the Python interpreter.
  309. ```python
  310. class VoiceTeleopNode(hm.HelloNode):
  311. """
  312. A class that inherits the HelloNode class from hm and sends joint trajectory
  313. commands.
  314. """
  315. def __init__(self):
  316. """
  317. A function that declares object from the GetVoiceCommands class, instantiates
  318. the HelloNode class, and set the publishing rate.
  319. :param self: The self reference.
  320. """
  321. hm.HelloNode.__init__(self)
  322. self.rate = 10.0
  323. self.joint_state = None
  324. self.speech = GetVoiceCommands()
  325. ```
  326. A class that inherits the `HelloNode` class from `hm` declares object from the `GetVoiceCommands` class and sends joint trajectory commands.
  327. ```python
  328. def send_command(self, command):
  329. """
  330. Function that makes an action call and sends base joint trajectory goals
  331. :param self: The self reference.
  332. :param command: A dictionary type.
  333. """
  334. joint_state = self.joint_state
  335. if (joint_state is not None) and (command is not None):
  336. point = JointTrajectoryPoint()
  337. point.time_from_start = rospy.Duration(0.0)
  338. ```
  339. The `send_command` function stores the joint state message and uses a conditional statement to send joint trajectory goals. Also, assign `point` as a `JointTrajectoryPoint` message type.
  340. ```python
  341. trajectory_goal = FollowJointTrajectoryGoal()
  342. trajectory_goal.goal_time_tolerance = rospy.Time(1.0)
  343. ```
  344. Assign `trajectory_goal` as a `FollowJointTrajectoryGoal` message type.
  345. ```python
  346. joint_name = command['joint']
  347. trajectory_goal.trajectory.joint_names = [joint_name]
  348. ```
  349. Extract the joint name from the command dictionary.
  350. ```python
  351. inc = command['inc']
  352. rospy.loginfo('inc = {0}'.format(inc))
  353. new_value = inc
  354. ```
  355. Extract the increment type from the command dictionary.
  356. ```python
  357. point.positions = [new_value]
  358. trajectory_goal.trajectory.points = [point]
  359. ```
  360. Assign the new value position to the trajectory goal message type.
  361. ```python
  362. self.trajectory_client.send_goal(trajectory_goal)
  363. rospy.loginfo('Done sending command.')
  364. ```
  365. Make the action call and send the goal of the new joint position.
  366. ```python
  367. self.speech.print_commands()
  368. ```
  369. Reprint the voice command menu after the trajectory goal is sent.
  370. ```python
  371. def main(self):
  372. """
  373. The main function that instantiates the HelloNode class, initializes the subscriber,
  374. and call other methods in both the VoiceTeleopNode and GetVoiceCommands classes.
  375. :param self: The self reference.
  376. """
  377. hm.HelloNode.main(self, 'voice_teleop', 'voice_teleop', wait_for_first_pointcloud=False)
  378. rospy.Subscriber('/stretch/joint_states', JointState, self.joint_states_callback)
  379. rate = rospy.Rate(self.rate)
  380. self.speech.print_commands()
  381. ```
  382. The main function instantiates the `HelloNode` class, initializes the subscriber, and calls other methods in both the `VoiceTeleopNode` and `GetVoiceCommands` classes.
  383. ```python
  384. while not rospy.is_shutdown():
  385. command = self.speech.get_command()
  386. self.send_command(command)
  387. rate.sleep()
  388. ```
  389. Run a while loop to continuously check speech commands and send those commands to execute an action.
  390. ```python
  391. try:
  392. node = VoiceTeleopNode()
  393. node.main()
  394. except KeyboardInterrupt:
  395. rospy.loginfo('interrupt received, so shutting down')
  396. ```
  397. Declare a `VoiceTeleopNode` object. Then execute the `main()` method.