34 from actionlib_msgs.msg
import GoalStatus
35 from robot_controllers_msgs.msg
import QueryControllerStatesAction, \
36 QueryControllerStatesGoal, \
39 ACTION_NAME =
"/query_controller_states" 41 if __name__ ==
"__main__":
44 print(
"usage: start_controller.py <controller_name> [optional_controller_type]")
47 rospy.init_node(
"start_robot_controllers")
49 rospy.loginfo(
"Connecting to %s..." % ACTION_NAME)
51 client.wait_for_server()
52 rospy.loginfo(
"Done.")
54 state = ControllerState()
55 state.name = sys.argv[1]
57 state.type = sys.argv[2]
58 state.state = state.RUNNING
60 goal = QueryControllerStatesGoal()
61 goal.updates.append(state)
63 rospy.loginfo(
"Requesting that %s be started..." % state.name)
64 client.send_goal(goal)
65 client.wait_for_result()
66 if client.get_state() == GoalStatus.SUCCEEDED:
67 rospy.loginfo(
"Done.")
68 elif client.get_state() == GoalStatus.ABORTED:
69 rospy.logerr(client.get_goal_status_text())