2 # -*- coding: iso-8859-15 -*-
8 import dynamic_reconfigure.client
11 from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
12 from actionlib_msgs.msg import GoalStatus
17 rospy.init_node('follow_uwb')
18 rospy.on_shutdown(self.on_shutdown)
20 self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
21 self.tfBuffer = tf2_ros.Buffer()
22 self.listener = tf2_ros.TransformListener(self.tfBuffer)
24 rospy.loginfo("Setting paramters")
25 self.dynreconf = dynamic_reconfigure.client.Client("/move_base/TrajectoryPlannerROS")
26 #self.dynreconf.update_configuration({'max_vel_x': 1.0, 'max_vel_theta': 1.2, 'min_in_place_vel_theta': 1.0})
28 rospy.loginfo("Waiting for the move_base action server to come up")
29 self.move_base.wait_for_server()
30 rospy.loginfo("Got move_base action server")
32 def next_pos(self, x, y):
33 rospy.loginfo("Moving to (%f, %f)" % (x, y))
35 # calculate angle between current position and goal
36 angle_to_goal = atan2(y, x)
37 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle_to_goal)
40 goal.target_pose.header.frame_id = "base_link"
41 goal.target_pose.header.stamp = rospy.Time.now()
42 goal.target_pose.pose.position.x = x
43 goal.target_pose.pose.position.y = y
44 goal.target_pose.pose.orientation.x = odom_quat[0]
45 goal.target_pose.pose.orientation.y = odom_quat[1]
46 goal.target_pose.pose.orientation.z = odom_quat[2]
47 goal.target_pose.pose.orientation.w = odom_quat[3]
48 self.move_base.send_goal(goal)
50 while not self.move_base.wait_for_result(rospy.Duration(1.0)) and not rospy.is_shutdown():
51 # Get the current position
52 pos = self.tfBuffer.lookup_transform("uwb_beacon", 'base_link', rospy.Time(0), rospy.Duration(2.0))
53 # Cancel if we are close enough to goal
54 if np.linalg.norm([pos.transform.translation.y, pos.transform.translation.x]) < 1:
55 rospy.loginfo("Goal within 1m, canceling")
56 self.move_base.cancel_goal()
59 if self.move_base.get_state() == GoalStatus.SUCCEEDED:
60 rospy.loginfo("The base moved to (%f, %f)" % (x, y))
62 rospy.logerr("The base failed to (%f, %f). Error: %d" % (x, y, self.move_base.get_state()))
65 def on_shutdown(self):
66 rospy.loginfo("Canceling all goals")
67 self.move_base.cancel_all_goals()
70 rate = rospy.Rate(2.0)
71 while not rospy.is_shutdown():
72 # Get the current position
73 beacon_pos = self.tfBuffer.lookup_transform('base_link', "uwb_beacon", rospy.Time(0), rospy.Duration(2.0))
74 # Create a position 1m away by creating an inverse vector
75 coords_cur = (beacon_pos.transform.translation.x, beacon_pos.transform.translation.y)
77 # Check difference to last goal
78 if np.linalg.norm(np.array(coords_cur)) > 0.5:
79 print "Setting new goal"
81 thread.start_new_thread(self.next_pos, (coords_cur[0], coords_cur[1]))
85 if __name__ == "__main__":