3 roslib.load_manifest(
'turtlebot_actions')
18 Very simple move action test - commands the robot to turn 45 degrees and travel 0.5 metres forward. 22 rospy.init_node(
"test_move_action_client")
25 rospy.loginfo(
"Starting action client...")
27 action_client.wait_for_server()
28 rospy.loginfo(
"Action client connected to action server.")
31 rospy.loginfo(
"Calling the action server...")
32 action_goal = TurtlebotMoveGoal()
33 action_goal.turn_distance = -math.pi/4.0
34 action_goal.forward_distance = 0.5
36 if action_client.send_goal_and_wait(action_goal, rospy.Duration(50.0), rospy.Duration(50.0)) == GoalStatus.SUCCEEDED:
37 rospy.loginfo(
'Call to action server succeeded')
39 rospy.logerr(
'Call to action server failed')
42 if __name__ ==
"__main__":