OMPL Plannification
Path planning with OMPL
controller_turtlebot.py
1 #!/usr/bin/env python
2 
3 # ROS imports
4 import roslib; roslib.load_manifest('control_turtlebot')
5 import rospy
6 import tf
7 import math
8 
9 #ROS messages
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
13 
14 #Numpy
15 import numpy as np
16 
17 class Controller(object):
18 
19  def __init__(self):
20  self.odometry_sub_ = rospy.Subscriber("/odom", Odometry, self.odomCallback, queue_size = 1)
21  self.control_input_pub_ = rospy.Publisher("/mobile_base/commands/velocity", Twist, queue_size = 1)
22 
23  self.serv_ = rospy.Service('/controller_turtlebot/goto',
24  GotoWaypoint,
26 
27  self.current_position_ = np.zeros(2)
28  self.current_orientation_ = 0.0
29 
30  self.desired_position_ = np.zeros(2)
31  self.desired_orientation_ = 0.0
32 
33 
34  rospy.wait_for_service('/controller_turtlebot/find_path_to_goal')
35  try:
36  self.find_path_to_goal_serv_ = rospy.ServiceProxy('/controller_turtlebot/find_path_to_goal', FindPathToGoal)
37  except rospy.ServiceException, e:
38  print "Service call failed: %s"%e
39 
40  return
41 
42  def calculateControlInput(self, req):
43 
44  planner_request = FindPathToGoalRequest()
45  planner_request.goal_state_x = req.goal_state_x
46  planner_request.goal_state_y = req.goal_state_y
47  #planner_request.goal_state_z = req.goal_state_z
48 
49  planner_response = self.find_path_to_goal_serv_(planner_request)
50 
51  for pose in planner_response.poses:
52  #print pose
53  control_input = Twist()
54  self.desired_position_[0] = pose.position.x
55  self.desired_position_[1] = pose.position.y
56  #self.desired_position_[2] = pose.position.z
57 
58  loop_rate = rospy.Rate(100) # 10Hz
59  orientation_approach = False
60  while not rospy.is_shutdown():
61  inc_x = self.desired_position_[0] - self.current_position_[0]
62  inc_y = self.desired_position_[1] - self.current_position_[1]
63 
64  self.desired_orientation_ = wrapAngle(math.atan2(inc_y, inc_x))
65  yaw_error = wrapAngle(self.desired_orientation_ - self.current_orientation_)
66  distance_to_goal = math.sqrt(math.pow(inc_x, 2.0) + math.pow(inc_y, 2.0))
67 
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
72 
73  control_input.linear.x = 0.08
74  control_input.linear.y = 0.0
75  control_input.linear.z = 0.0
76  else:
77  control_input.angular.x = 0.0
78  control_input.angular.y = 0.0
79  control_input.angular.z = 0.0
80 
81  orientation_approach = True
82  liner_speed = abs(distance_to_goal) * 0.5
83 
84  if liner_speed < 0.1:
85  control_input.linear.x = 0.1
86  elif liner_speed > 0.2:
87  control_input.linear.x = 0.2
88  else:
89  control_input.linear.x = liner_speed
90 
91  control_input.linear.y = 0.0
92  control_input.linear.z = 0.0
93 
94  self.control_input_pub_.publish(control_input)
95 
96  rospy.logdebug("%s: current position: [%f, %f]\n", rospy.get_name(), self.current_position_[0], self.current_position_[1])
97  rospy.logdebug("%s: desired position: [%f, %f]\n", rospy.get_name(), self.desired_position_[0], self.desired_position_[1])
98  rospy.logdebug("%s: yaw_error: %f\n", rospy.get_name(), yaw_error)
99  rospy.logdebug("%s: current orientation: %f\n", rospy.get_name(), self.current_orientation_)
100  rospy.logdebug("%s: desired orientation: %f\n", rospy.get_name(), self.desired_orientation_)
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)
104 
105  if distance_to_goal <= 0.2:
106  break
107  loop_rate.sleep()
108 
109  return GotoWaypointResponse()
110 
111  def odomCallback(self, odometry_msg):
112  self.current_position_[0] = odometry_msg.pose.pose.position.x
113  self.current_position_[1] = odometry_msg.pose.pose.position.y
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])
115  self.current_orientation_ = wrapAngle(y)
116  return
117 
118 def wrapAngle(angle):
119  """wrapAngle
120 
121  Calculates angles values between 0 and 2pi"""
122  return (angle + ( 2.0 * math.pi * math.floor( ( math.pi - angle ) / ( 2.0 * math.pi ) ) ) )
123 
124 if __name__ == '__main__':
125  rospy.init_node('control_turtlebot', log_level=rospy.INFO)
126  rospy.loginfo("%s: starting turtlebot controller", rospy.get_name())
127 
128  controller = Controller()
129  rospy.spin()
def odomCallback(self, odometry_msg)