4 from std_msgs.msg
import Bool
5 from rtabmap_ros.msg
import Goal
7 pub = rospy.Publisher(
'/rtabmap/goal_node', Goal, queue_size=1)
14 rospy.loginfo(rospy.get_caller_id() +
"Goal '%s' reached! Publishing next goal in 1 sec...", waypoints[currentIndex])
16 rospy.loginfo(rospy.get_caller_id() +
"Goal '%s' failed! Publishing next goal in 1 sec...", waypoints[currentIndex])
18 currentIndex = (currentIndex+1) % len(waypoints)
23 if waypoints[currentIndex].isdigit():
24 msg.node_id = int(waypoints[currentIndex])
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))
34 rospy.init_node(
'patrol', anonymous=
False)
35 rospy.Subscriber(
"/rtabmap/goal_reached", Bool, callback)
40 if waypoints[currentIndex].isdigit():
41 msg.node_id = int(waypoints[currentIndex])
45 msg.node_label = waypoints[currentIndex]
46 while rospy.Time.now().secs == 0:
47 rospy.loginfo(
"Waiting clock...")
49 msg.header.stamp = rospy.Time.now()
50 rospy.loginfo(
"Publishing goal '%s'! (%d/%d)", waypoints[currentIndex], currentIndex+1, len(waypoints))
54 if __name__ ==
'__main__':
56 print(
"usage: patrol.py waypointA waypointB waypointC ... (at least 2 waypoints, can be node id or label)")
58 waypoints = sys.argv[1:]
59 rospy.loginfo(
"Waypoints: [%s]", str(waypoints).strip(
'[]'))