import math import rospy import tf from tf_conversions import transformations import csv from geometry_msgs.msg import Twist from visualization_msgs.msg import Marker from visualization_msgs.msg import MarkerArray
def_load_waypoints(self): ''' Load waypoints to a list ''' withopen(self._filename,'r') as f: rdr = csv.reader(f) for i,row inenumerate(rdr): if i>0: # remove header # convert str to float wp = [] for p in row: wp.append(float(p)) self._wps.append(wp) # record final waypoint index self._goalIdx = len(self._wps)-1
# def _preprocess_wps(self): # ''' not used yet ''' # offset = 7 # for i in self._wps: # if offset >= self._goalIdx: # break # max = 0 # idx = 0 # print(len(self._wps[i:offset])) # for wp in self._wps[:offset]: # if wp[-1] > max: # max = wp[-1] # idx = wp[0] # print(max,idx) # offset+=1
def_get_current_pos(self): ''' Get current position ''' try: trans, rot = self.tf_listener.lookupTransform('/map', '/base_link', rospy.Time(0)) except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException): returnFalse roll,pitch,yaw = transformations.euler_from_quaternion(rot) x = trans[0] y = trans[1] self._cur_pose = [x,y,yaw] iflen(self._cur_pose): returnTrue else: returnFalse
def_get_closet_wpIdx(self): ''' get closest waypoint from remaining waypoints ''' cur_wpIdx = self._wpIdx if self._get_current_pos(): min = math.sqrt(math.pow(self._cur_pose[0]-self._wps[0][1],2)+math.pow(self._cur_pose[1]-self._wps[0][2],2)) for wp in self._wps[cur_wpIdx:-1]: dst = math.sqrt(math.pow(self._cur_pose[0]-wp[1],2)+math.pow(self._cur_pose[1]-wp[2],2)) if dst < min: min = dst self._wpIdx = int(wp[0])