Go to the documentation of this file.00001
00002 import roslib
00003 roslib.load_manifest('turtlebot_actions')
00004
00005 import rospy
00006
00007 import os
00008 import sys
00009 import time
00010 import math
00011 from turtlebot_actions.msg import *
00012 from actionlib_msgs.msg import *
00013
00014
00015 import actionlib
00016
00017 '''
00018 Very simple move action test - commands the robot to turn 45 degrees and travel 0.5 metres forward.
00019 '''
00020
00021 def main():
00022 rospy.init_node("test_move_action_client")
00023
00024
00025 rospy.loginfo("Starting action client...")
00026 action_client = actionlib.SimpleActionClient('turtlebot_move', TurtlebotMoveAction)
00027 action_client.wait_for_server()
00028 rospy.loginfo("Action client connected to action server.")
00029
00030
00031 rospy.loginfo("Calling the action server...")
00032 action_goal = TurtlebotMoveGoal()
00033 action_goal.turn_distance = -math.pi/4.0
00034 action_goal.forward_distance = 0.5
00035
00036 if action_client.send_goal_and_wait(action_goal, rospy.Duration(50.0), rospy.Duration(50.0)) == GoalStatus.SUCCEEDED:
00037 rospy.loginfo('Call to action server succeeded')
00038 else:
00039 rospy.logerr('Call to action server failed')
00040
00041
00042 if __name__ == "__main__":
00043 main()