4 import roslib; roslib.load_manifest(
'control_turtlebot')
10 from geometry_msgs.msg
import Twist
11 from nav_msgs.msg
import Odometry
12 from control_turtlebot.srv
import GotoWaypoint, GotoWaypointResponse, FindPathToGoal, FindPathToGoalResponse, FindPathToGoalRequest
21 self.
control_input_pub_ = rospy.Publisher(
"/mobile_base/commands/velocity", Twist, queue_size = 1)
23 self.
serv_ = rospy.Service(
'/controller_turtlebot/goto',
34 rospy.wait_for_service(
'/controller_turtlebot/find_path_to_goal')
37 except rospy.ServiceException, e:
38 print "Service call failed: %s"%e
42 def calculateControlInput(self, req):
44 planner_request = FindPathToGoalRequest()
45 planner_request.goal_state_x = req.goal_state_x
46 planner_request.goal_state_y = req.goal_state_y
51 for pose
in planner_response.poses:
53 control_input = Twist()
58 loop_rate = rospy.Rate(100)
59 orientation_approach =
False 60 while not rospy.is_shutdown():
66 distance_to_goal = math.sqrt(math.pow(inc_x, 2.0) + math.pow(inc_y, 2.0))
68 if abs(yaw_error) > 0.04
and not orientation_approach:
69 control_input.angular.x = 0.0
70 control_input.angular.y = 0.0
71 control_input.angular.z = yaw_error * 1.0
73 control_input.linear.x = 0.08
74 control_input.linear.y = 0.0
75 control_input.linear.z = 0.0
77 control_input.angular.x = 0.0
78 control_input.angular.y = 0.0
79 control_input.angular.z = 0.0
81 orientation_approach =
True 82 liner_speed = abs(distance_to_goal) * 0.5
85 control_input.linear.x = 0.1
86 elif liner_speed > 0.2:
87 control_input.linear.x = 0.2
89 control_input.linear.x = liner_speed
91 control_input.linear.y = 0.0
92 control_input.linear.z = 0.0
94 self.control_input_pub_.publish(control_input)
98 rospy.logdebug(
"%s: yaw_error: %f\n", rospy.get_name(), yaw_error)
101 rospy.logdebug(
"%s: distance_to_goal: %f\n", rospy.get_name(), distance_to_goal)
102 rospy.logdebug(
"%s: control_input.linear.x %f\n", rospy.get_name(), control_input.linear.x)
103 rospy.logdebug(
"%s: control_input.angular.z %f\n", rospy.get_name(), control_input.angular.z)
105 if distance_to_goal <= 0.2:
109 return GotoWaypointResponse()
111 def odomCallback(self, odometry_msg):
114 (r, p, y) = tf.transformations.euler_from_quaternion([odometry_msg.pose.pose.orientation.x, odometry_msg.pose.pose.orientation.y, odometry_msg.pose.pose.orientation.z, odometry_msg.pose.pose.orientation.w])
118 def wrapAngle(angle):
121 Calculates angles values between 0 and 2pi""" 122 return (angle + ( 2.0 * math.pi * math.floor( ( math.pi - angle ) / ( 2.0 * math.pi ) ) ) )
124 if __name__ ==
'__main__':
125 rospy.init_node(
'control_turtlebot', log_level=rospy.INFO)
126 rospy.loginfo(
"%s: starting turtlebot controller", rospy.get_name())
def calculateControlInput(self, req)
def odomCallback(self, odometry_msg)