patrol.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 import sys
4 from std_msgs.msg import Bool
5 from rtabmap_ros.msg import Goal
6 
7 pub = rospy.Publisher('/rtabmap/goal_node', Goal, queue_size=1)
8 waypoints = []
9 currentIndex = 0
10 
11 def callback(data):
12  global currentIndex
13  if data.data:
14  rospy.loginfo(rospy.get_caller_id() + "Goal '%s' reached! Publishing next goal in 1 sec...", waypoints[currentIndex])
15  else:
16  rospy.loginfo(rospy.get_caller_id() + "Goal '%s' failed! Publishing next goal in 1 sec...", waypoints[currentIndex])
17 
18  currentIndex = (currentIndex+1) % len(waypoints)
19 
20  rospy.sleep(1.)
21 
22  msg = Goal()
23  if waypoints[currentIndex].isdigit():
24  msg.node_id = int(waypoints[currentIndex])
25  msg.node_label = ""
26  else:
27  msg.node_id = 0
28  msg.node_label = waypoints[currentIndex]
29  msg.header.stamp = rospy.get_rostime()
30  rospy.loginfo("Publishing goal '%s'! (%d/%d)", waypoints[currentIndex], currentIndex+1, len(waypoints))
31  pub.publish(msg)
32 
33 def main():
34  rospy.init_node('patrol', anonymous=False)
35  rospy.Subscriber("/rtabmap/goal_reached", Bool, callback)
36  rospy.sleep(1.) # make sure that subscribers have seen this node before sending a goal
37 
38  # send the first goal
39  msg = Goal()
40  if waypoints[currentIndex].isdigit():
41  msg.node_id = int(waypoints[currentIndex])
42  msg.node_label = ""
43  else:
44  msg.node_id = 0
45  msg.node_label = waypoints[currentIndex]
46  while rospy.Time.now().secs == 0:
47  rospy.loginfo("Waiting clock...")
48  rospy.sleep(.1)
49  msg.header.stamp = rospy.Time.now()
50  rospy.loginfo("Publishing goal '%s'! (%d/%d)", waypoints[currentIndex], currentIndex+1, len(waypoints))
51  pub.publish(msg)
52  rospy.spin()
53 
54 if __name__ == '__main__':
55  if len(sys.argv) < 3:
56  print("usage: patrol.py waypointA waypointB waypointC ... (at least 2 waypoints, can be node id or label)")
57  else:
58  waypoints = sys.argv[1:]
59  rospy.loginfo("Waypoints: [%s]", str(waypoints).strip('[]'))
60  main()
def main()
Definition: patrol.py:33
def callback(data)
Definition: patrol.py:11


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04