4 from strands_executive_msgs
import task_utils
12 add_tasks_srv_name =
'/task_executor/add_tasks'
13 set_exe_stat_srv_name =
'/task_executor/set_execution_status'
14 rospy.loginfo(
"Waiting for task_executor service...")
15 rospy.wait_for_service(add_tasks_srv_name)
16 rospy.wait_for_service(set_exe_stat_srv_name)
18 add_tasks_srv = rospy.ServiceProxy(add_tasks_srv_name, AddTasks)
19 set_execution_status = rospy.ServiceProxy(set_exe_stat_srv_name, SetExecutionStatus)
20 return add_tasks_srv, set_execution_status
23 if __name__ ==
'__main__':
24 rospy.init_node(
"example_add_client")
29 print 'Requesting wait at ', sys.argv[1]
31 max_duration = rospy.Duration(int(sys.argv[2]))
32 wait_task = Task(action=
'wait_action',start_node_id=sys.argv[1], max_duration=max_duration)
33 task_utils.add_time_argument(wait_task, rospy.Time())
34 task_utils.add_duration_argument(wait_task, max_duration)
39 task_id = add_task([wait_task])
42 set_execution_status(
True)
45 rospy.sleep(int(sys.argv[2])/2)
46 set_execution_status(
False)