test_move.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import roslib
3 roslib.load_manifest('turtlebot_actions')
4 
5 import rospy
6 
7 import os
8 import sys
9 import time
10 import math
11 from turtlebot_actions.msg import *
12 from actionlib_msgs.msg import *
13 
14 
15 import actionlib
16 
17 '''
18  Very simple move action test - commands the robot to turn 45 degrees and travel 0.5 metres forward.
19 '''
20 
21 def main():
22  rospy.init_node("test_move_action_client")
23 
24  # Construct action ac
25  rospy.loginfo("Starting action client...")
26  action_client = actionlib.SimpleActionClient('turtlebot_move', TurtlebotMoveAction)
27  action_client.wait_for_server()
28  rospy.loginfo("Action client connected to action server.")
29 
30  # Call the action
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 # metres
35 
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')
38  else:
39  rospy.logerr('Call to action server failed')
40 
41 
42 if __name__ == "__main__":
43  main()
def main()
Definition: test_move.py:21


turtlebot_actions
Author(s): Helen Oleynikova, Melonee Wise
autogenerated on Mon Jun 10 2019 15:43:57