dock_on_button.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2015, Fetch Robotics Inc.
4 # Author: Michael Ferguson
5 
6 import rospy
7 import actionlib
8 from sensor_msgs.msg import Joy
9 from fetch_auto_dock_msgs.msg import DockAction, DockGoal
10 
11 # Listen to joy messages, when button held, dock
12 class DockTeleop:
13  ACTION_NAME = "/dock"
14 
15  def __init__(self):
16  rospy.loginfo("Connecting to %s..." % self.ACTION_NAME)
18  self.client.wait_for_server()
19  rospy.loginfo("Done.")
20 
21  self.dock_button = rospy.get_param("~dock_button", 13) # default button is the circle
22 
23  self.pressed = False
24  self.pressed_last = None
25 
26  self.joy_sub = rospy.Subscriber("joy", Joy, self.joy_callback)
27 
28  def joy_callback(self, msg):
29  try:
30  if msg.buttons[self.dock_button] > 0:
31  if not self.pressed:
32  self.pressed_last = rospy.Time.now()
33  self.pressed = True
34  elif self.pressed_last and rospy.Time.now() > self.pressed_last + rospy.Duration(1.0):
35  self.reset()
36  self.pressed_last = None
37  else:
38  self.pressed = False
39  except IndexError:
40  rospy.logwarn("dock_button is out of range")
41 
42  def reset(self):
43  goal = DockGoal()
44  self.client.send_goal(goal)
45 
46 if __name__ == "__main__":
47  rospy.init_node("dock_on_button")
48  c = DockTeleop()
49  rospy.spin()
def joy_callback(self, msg)


fetch_open_auto_dock
Author(s): Michael Ferguson, Griswald Brooks
autogenerated on Mon Feb 28 2022 22:21:37