marathon_routine_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 
5 from datetime import time, timedelta, datetime
6 from dateutil.tz import tzutc, tzlocal
7 
8 from routine_behaviours.marathon_routine import MarathonRoutine
9 
10 
11 if __name__ == '__main__':
12  rospy.init_node("marathon_routine")
13 
14  # start and end times -- all times should be in a particular timezone - local has stopped working!
15  # localtz = tzlocal()
16  localtz = tzutc()
17 
18  now = datetime.now(localtz).time().replace(tzinfo=localtz)
19  # useful for testing
20  # start = now
21 
22  start = time(8,00, tzinfo=localtz)
23  end = time(00,00, tzinfo=localtz)
24 
25  # how long to stand idle before doing something
26  idle_duration=rospy.Duration(5)
27 
28  # how long do you want it to take to do a tour. this must be greater than the time you think it will take!
29  # the number argument is in seconds
30  tour_duration_estimate = rospy.Duration(60 * 40 * 2)
31 
32  routine = MarathonRoutine(daily_start=start, daily_end=end,
33  idle_duration=idle_duration, tour_duration_estimate=tour_duration_estimate)
34 
35 
36  # choose which nodes are visited at random on idle
37  # routine.random_nodes = ['WayPoint2', 'WayPoint3']
38  # or
39  routine.random_nodes = routine.all_waypoints_except(['WayPoint2', 'WayPoint3'])
40 
41  # go around every node every tour_duration_estimate
42  # routine.create_patrol_routine()
43 
44  ten_am = time(10,00, tzinfo=localtz)
45  two_pm = time(14,00, tzinfo=localtz)
46 
47  thirty_mins = timedelta(minutes = 30)
48  sixty_mins = timedelta(minutes = 60)
49  ninety_mins = timedelta(minutes = 90)
50 
51 
52  # patrol just these selected waypoints every 30 minutes in the first part of the day
53  routine.create_patrol_routine(waypoints=['WayPoint2', 'WayPoint3'], daily_start=start, daily_end=ten_am, repeat_delta=thirty_mins)
54 
55  # then all but these every 60 minutes in the second part part of the day
56  routine.create_patrol_routine(waypoints=routine.all_waypoints_except(['WayPoint2', 'WayPoint3']), daily_start=ten_am, daily_end=two_pm, repeat_delta=sixty_mins)
57 
58  # then all waypoints these every 90 minutes in the final part of the day
59  routine.create_patrol_routine(waypoints=routine.all_waypoints(), daily_start=two_pm, daily_end=end, repeat_delta=ninety_mins)
60 
61 
62  # do 3d scans
63  scan_waypoints = ['WayPoint2', 'WayPoint3']
64  routine.create_3d_scan_routine(waypoints=scan_waypoints, repeat_delta=timedelta(hours=1))
65 
66  # where to stop and what to tweet with the image
67  twitter_waypoints = [['WayPoint6', 'I hope everyone is working hard today #ERW14 #RobotMarathon'],
68  ['WayPoint2', 'Knowledge is power for @UoBLibServices #ERW14 #RobotMarathon']]
69  # routine.create_tweet_routine(twitter_waypoints, daily_start=time(23,00, tzinfo=localtz), daily_end=time(00,00, tzinfo=localtz))
70  routine.create_tweet_routine(twitter_waypoints)
71 
72 
73  # do rgbd recording for a minute at these places every two hours
74  rgbd_waypoints = ['WayPoint2', 'WayPoint3']
75  routine.create_rgbd_record_routine(waypoints=rgbd_waypoints, duration=rospy.Duration(60), repeat_delta=timedelta(hours=2))
76 
77 
78  # the list of collections to be replicated
79  db = 'message_store'
80  collections = ['heads','metric_map_data','rosout_agg','robot_pose','task_events','scheduling_problems','ws_observations','monitored_nav_events', 'people_perception']
81  routine.message_store_entries_to_replicate(collections, db=db)
82 
83  db = 'roslog'
84  collections = ['head_xtion_compressed_depth_libav', 'head_xtion_compressed_rgb_theora', 'head_xtion_compressed_rgb_compressed']
85  routine.message_store_entries_to_replicate(collections, db=db)
86 
87  db = 'metric_maps'
88  collections = ['data', 'summary']
89  routine.message_store_entries_to_replicate(collections, db=db)
90 
91 
92  routine.start_routine()
93 
94  rospy.spin()


routine_behaviours
Author(s): Nick Hawes
autogenerated on Tue Mar 17 2015 21:43:31